Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
ROSComms.h
Go to the documentation of this file.
1/*
2 * Copyright (C) 2020-2021 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16#pragma once
17
18#include <ros/ros.h>
19#include <string>
20
21#include "comm_types.h"
22#include "std_msgs/String.h"
23
24namespace mock_drivers
25{
33template <typename...>
35
36template <typename T>
43{
44private:
45 std::function<void(T)> callback_function_;
47 bool latch_;
49 std::string topic_;
50
51public:
57 bool getLatch()
58 {
59 return latch_;
60 }
61
68 {
69 return queue_size_;
70 }
71
77 std::string getTopic()
78 {
79 return topic_;
80 }
81
88 {
89 return comm_type_;
90 }
91
97 void callback(T msg);
98
105
107 ROSComms();
116 ROSComms(CommTypes ct, bool latch, int qs, std::string t);
117
126 ROSComms(std::function<void(T)> cbf, CommTypes ct, bool latch, int qs, std::string t);
127};
128
135template <typename M, typename T>
136class ROSComms<M, T>
137{
138private:
139 std::function<void(M, T)> callback_function_;
141 std::string topic_;
142
143public:
149 std::string getTopic()
150 {
151 return topic_;
152 }
159 {
160 return comm_type_;
161 }
162
171 bool callback(M req, T res);
172
178 M getReqType();
179
185 T getResType();
186
196 ROSComms(std::function<bool(M, T)> cbf, CommTypes ct, std::string t);
197};
198} // namespace mock_drivers
199
200#include "ROSComms.ipp"
ROSComms()
Default constructor.
std::string getTopic()
Returns the name string (topic) associated with the service.
Definition: ROSComms.h:149
CommTypes getCommType()
returns the comms type of this object
Definition: ROSComms.h:158
std::function< void(M, T)> callback_function_
Definition: ROSComms.h:139
Class which serves as an abstraction of a pub/sub framework.
Definition: ROSComms.h:43
T getTemplateType()
Returns an instance of the type this object is parameterized on. This is used for forwarding the data...
int getQueueSize()
Returns the data stream queue size.
Definition: ROSComms.h:67
bool getLatch()
Returns the latched status of this data stream.
Definition: ROSComms.h:57
std::string getTopic()
Returns the name string (topic) associated with the data stream.
Definition: ROSComms.h:77
std::function< void(T)> callback_function_
Definition: ROSComms.h:45
CommTypes getCommType()
returns the comms type of this object
Definition: ROSComms.h:87
This class is used to transfer all the information required to initialize ros topics/services.
Definition: ROSComms.h:34
CommTypes
Enum defining the different possible communications types.
Definition: comm_types.h:22
bool callback(cav_srvs::PlanTrajectory::Request &req, cav_srvs::PlanTrajectory::Response &res)
Definition: helper.cpp:21