converters.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020-2023 RaccoonLab.
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License as published by
6  * the Free Software Foundation, version 3.
7  *
8  * This program is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
11  * General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * Author: Dmitry Ponomarev <ponomarevda96@gmail.com>
17  */
18 
19 #ifndef SRC_UAVCAN_COMMUNICATOR_CONVERTERS_HPP_
20 #define SRC_UAVCAN_COMMUNICATOR_CONVERTERS_HPP_
21 
22 #include <ros/ros.h>
23 #include <sensor_msgs/Imu.h>
24 #include <sensor_msgs/NavSatFix.h>
25 #include <sensor_msgs/Joy.h>
26 #include <sensor_msgs/MagneticField.h>
27 #include <sensor_msgs/BatteryState.h>
28 #include <std_msgs/Bool.h>
29 #include <std_msgs/UInt8.h>
30 #include <std_msgs/Float32.h>
31 #include <geometry_msgs/Twist.h>
32 #include <mavros_msgs/BatteryStatus.h>
33 #include <mavros_msgs/ESCTelemetryItem.h>
34 #include <mavros_msgs/ESCStatusItem.h>
35 
36 #include <iostream>
37 #include <memory>
38 #include <string>
39 
40 #include <uavcan/uavcan.hpp>
41 #include <uavcan/equipment/actuator/ArrayCommand.hpp>
42 #include <uavcan/equipment/ahrs/MagneticFieldStrength.hpp>
43 #include <uavcan/equipment/ahrs/RawIMU.hpp>
44 #include <uavcan/equipment/ahrs/Solution.hpp>
45 #include <uavcan/equipment/air_data/RawAirData.hpp>
46 #include <uavcan/equipment/air_data/StaticPressure.hpp>
47 #include <uavcan/equipment/air_data/StaticTemperature.hpp>
48 #include <uavcan/equipment/esc/RawCommand.hpp>
49 #include <uavcan/equipment/esc/Status.hpp>
50 #include <uavcan/equipment/gnss/Fix2.hpp>
51 #include <uavcan/equipment/ice/FuelTankStatus.hpp>
52 #include <uavcan/equipment/ice/reciprocating/Status.hpp>
53 #include <uavcan/equipment/power/CircuitStatus.hpp>
54 #include <uavcan/equipment/power/BatteryInfo.hpp>
55 #include <uavcan/equipment/safety/ArmingStatus.hpp>
56 
57 constexpr unsigned NodeMemoryPoolSize = 16384;
59 
60 
61 class Converter {};
62 
63 template<typename IN_UAVCAN, typename OUT_ROS>
65 protected:
66  typedef OUT_ROS OUT_ROS_MSG;
67  typedef IN_UAVCAN IN_UAVCAN_MSG;
71 
72  virtual void uavcan_callback(const uavcan::ReceivedDataStructure<IN_UAVCAN_MSG>& uavcan_msg) = 0;
73  UavcanToRosConverter(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic) :
74  uavcan_sub_(uavcan_node) {
75  ros_pub_ = ros_node.advertise<OUT_ROS_MSG>(ros_topic, 5);
76  uavcan_sub_.start(std::bind(&UavcanToRosConverter::uavcan_callback, this, std::placeholders::_1));
77  }
78 };
79 
80 template<typename IN_ROS, typename OUT_UAVCAN>
82 public:
83  typedef OUT_UAVCAN OUT_UAVCAN_MSG;
85  bool enabled{true};
86 protected:
87  typedef IN_ROS IN_ROS_MSG;
88  typedef typename IN_ROS::Ptr IN_ROS_MSG_PTR;
89 
92  std::string _name;
93 
94  virtual void ros_callback(IN_ROS_MSG_PTR in_ros_msg) = 0;
95  RosToUavcanConverter(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic, std::string name):
96  uavcan_pub_(uavcan_node), _name(name) {
97  ros_sub_ = ros_node.subscribe(ros_topic, 1, &RosToUavcanConverter::ros_callback, this);
98  }
99 
100  void broadcast() {
101  if (enabled == false) {
102  return;
103  }
104  int pub_res = uavcan_pub_.broadcast(out_uavcan_msg_);
105  if (pub_res < 0) {
106  std::cerr << _name << " publication failure: " << pub_res << std::endl;
107  }
108  }
109 };
110 
111 
113  uavcan::equipment::esc::RawCommand,
114  sensor_msgs::Joy> {
115  void uavcan_callback(const uavcan::ReceivedDataStructure<IN_UAVCAN_MSG>& uavcan_msg) override;
116 public:
117  RawCommandUavcanToRos(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
118  UavcanToRosConverter(ros_node, uavcan_node, ros_topic) { }
119 };
120 
122  uavcan::equipment::actuator::ArrayCommand,
123  sensor_msgs::Joy> {
124  void uavcan_callback(const uavcan::ReceivedDataStructure<IN_UAVCAN_MSG>& uavcan_msg) override;
125 public:
126  ArrayCommandUavcanToRos(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
127  UavcanToRosConverter(ros_node, uavcan_node, ros_topic) { }
128 };
129 
130 
132  uavcan::equipment::ahrs::Solution,
133  sensor_msgs::Imu> {
134  void uavcan_callback(const uavcan::ReceivedDataStructure<IN_UAVCAN_MSG>& uavcan_msg) override;
135 public:
136  AhrsSolutionUavcanToRos(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
137  UavcanToRosConverter(ros_node, uavcan_node, ros_topic) { }
138 };
139 
140 
142  uavcan::equipment::safety::ArmingStatus,
143  std_msgs::Bool> {
144  void uavcan_callback(const uavcan::ReceivedDataStructure<IN_UAVCAN_MSG>& uavcan_msg) override;
145 
146 public:
147  ArmUavcanToRos(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
148  UavcanToRosConverter(ros_node, uavcan_node, ros_topic) {}
149 };
150 
151 
153  uavcan::equipment::esc::Status,
154  mavros_msgs::ESCTelemetryItem> {
155  void uavcan_callback(const uavcan::ReceivedDataStructure<IN_UAVCAN_MSG>& uavcan_msg) override;
156 
157 public:
158  EscStatusUavcanToRos(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
159  UavcanToRosConverter(ros_node, uavcan_node, ros_topic) {}
160 };
161 
162 
164  uavcan::equipment::power::CircuitStatus,
165  mavros_msgs::BatteryStatus> {
166  void uavcan_callback(const uavcan::ReceivedDataStructure<IN_UAVCAN_MSG>& uavcan_msg) override;
167 
168 public:
169  CircuitStatusUavcanToRos(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
170  UavcanToRosConverter(ros_node, uavcan_node, ros_topic) {}
171 };
172 
173 
175  std_msgs::Float32,
176  uavcan::equipment::air_data::StaticPressure> {
177  void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override;
178 public:
179  BaroStaticPressureRosToUavcan(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
180  RosToUavcanConverter(ros_node, uavcan_node, ros_topic, __FUNCTION__) {}
181 };
182 
183 
185  std_msgs::Float32,
186  uavcan::equipment::air_data::StaticTemperature> {
187  void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override;
188 public:
189  BaroStaticTemperatureRosToUavcan(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
190  RosToUavcanConverter(ros_node, uavcan_node, ros_topic, __FUNCTION__) {}
191 };
192 
193 
195  std_msgs::Float32,
196  uavcan::equipment::air_data::RawAirData> {
197  void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override;
200 public:
201  DiffPressureRosToUavcan(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
202  RosToUavcanConverter(ros_node, uavcan_node, ros_topic, __FUNCTION__),
203  _pressure(ros_node, uavcan_node, "/uav/static_pressure"),
204  _temperature(ros_node, uavcan_node, "/uav/static_temperature") {
205  _pressure.enabled = false;
206  _temperature.enabled = false;
207  }
208 };
209 
210 
212  sensor_msgs::NavSatFix,
213  uavcan::equipment::gnss::Fix2> {
214  void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override;
215  void ros_velocity_callback(geometry_msgs::Twist::Ptr in_ros_msg);
217 public:
218  GpsRosToUavcan(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
219  RosToUavcanConverter(ros_node, uavcan_node, ros_topic, __FUNCTION__) {
220  ros_velocity_sub_ = ros_node.subscribe("/uav/velocity", 1, &GpsRosToUavcan::ros_velocity_callback, this);
221  out_uavcan_msg_.sats_used = 10.0;
222  out_uavcan_msg_.status = 3;
223  out_uavcan_msg_.pdop = 1.0;
224  }
225 };
226 
227 
229  sensor_msgs::Imu,
230  uavcan::equipment::ahrs::RawIMU> {
231  void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override;
232 public:
233  ImuRosToUavcan(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
234  RosToUavcanConverter(ros_node, uavcan_node, ros_topic, __FUNCTION__) {}
235 };
236 
237 
239  sensor_msgs::MagneticField,
240  uavcan::equipment::ahrs::MagneticFieldStrength> {
241  void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override;
242 public:
243  MagnetometerRosToUavcan(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
244  RosToUavcanConverter(ros_node, uavcan_node, ros_topic, __FUNCTION__) {}
245 };
246 
248  mavros_msgs::ESCTelemetryItem,
249  uavcan::equipment::esc::Status> {
250  void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override;
251 
252 public:
253  EscStatusRosToUavcan(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
254  RosToUavcanConverter(ros_node, uavcan_node, ros_topic, __FUNCTION__) {}
255 };
256 
258  mavros_msgs::ESCStatusItem,
259  uavcan::equipment::ice::reciprocating::Status> {
260  void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override;
261  void ros_status_callback(std_msgs::UInt8 in_ros_msg);
263 public:
264  IceReciprocatingStatusRosToUavcan(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
265  RosToUavcanConverter(ros_node, uavcan_node, ros_topic, __FUNCTION__) {
267  }
268 };
269 
271  std_msgs::UInt8,
272  uavcan::equipment::ice::FuelTankStatus> {
273  void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override;
274 
275 public:
276  IceFuelTankStatusRosToUavcan(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
277  RosToUavcanConverter(ros_node, uavcan_node, ros_topic, __FUNCTION__) {}
278 };
279 
281  sensor_msgs::BatteryState,
282  uavcan::equipment::power::BatteryInfo> {
283  void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override;
284 
285 public:
286  BatteryInfoRosToUavcan(ros::NodeHandle& ros_node, UavcanNode& uavcan_node, const char* ros_topic):
287  RosToUavcanConverter(ros_node, uavcan_node, ros_topic, __FUNCTION__) {}
288 };
289 
290 
291 std::unique_ptr<Converter> instantiate_converter(std::string converter_name,
292  ros::NodeHandle& ros_node,
293  UavcanNode& uavcan_node,
294  const char* ros_topic);
295 
296 #endif // SRC_UAVCAN_COMMUNICATOR_CONVERTERS_HPP_
CircuitStatusUavcanToRos::uavcan_callback
void uavcan_callback(const uavcan::ReceivedDataStructure< IN_UAVCAN_MSG > &uavcan_msg) override
Definition: converters.cpp:90
ImuRosToUavcan
Definition: converters.hpp:228
ros::Publisher
RawCommandUavcanToRos::RawCommandUavcanToRos
RawCommandUavcanToRos(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:117
IceReciprocatingStatusRosToUavcan::ros_callback
void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override
Definition: converters.cpp:186
uavcan::Subscriber< IN_UAVCAN_MSG >
UavcanToRosConverter::ros_msg_
OUT_ROS_MSG ros_msg_
Definition: converters.hpp:70
RosToUavcanConverter::OUT_UAVCAN_MSG
OUT_UAVCAN OUT_UAVCAN_MSG
Definition: converters.hpp:83
uavcan::Publisher< OUT_UAVCAN_MSG >
BaroStaticPressureRosToUavcan::BaroStaticPressureRosToUavcan
BaroStaticPressureRosToUavcan(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:179
BaroStaticTemperatureRosToUavcan::BaroStaticTemperatureRosToUavcan
BaroStaticTemperatureRosToUavcan(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:189
DiffPressureRosToUavcan::_pressure
BaroStaticPressureRosToUavcan _pressure
Definition: converters.hpp:198
IceFuelTankStatusRosToUavcan
Definition: converters.hpp:270
UavcanToRosConverter::OUT_ROS_MSG
OUT_ROS OUT_ROS_MSG
Definition: converters.hpp:66
BaroStaticTemperatureRosToUavcan
Definition: converters.hpp:184
ArmUavcanToRos::ArmUavcanToRos
ArmUavcanToRos(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:147
ros.h
EscStatusRosToUavcan::EscStatusRosToUavcan
EscStatusRosToUavcan(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:253
RosToUavcanConverter::IN_ROS_MSG_PTR
IN_ROS::Ptr IN_ROS_MSG_PTR
Definition: converters.hpp:88
EscStatusUavcanToRos::EscStatusUavcanToRos
EscStatusUavcanToRos(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:158
BatteryInfoRosToUavcan
Definition: converters.hpp:280
GpsRosToUavcan::ros_callback
void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override
Definition: converters.cpp:137
RawCommandUavcanToRos
Definition: converters.hpp:112
MagnetometerRosToUavcan::ros_callback
void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override
Definition: converters.cpp:168
DiffPressureRosToUavcan::DiffPressureRosToUavcan
DiffPressureRosToUavcan(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:201
uavcan::ReceivedDataStructure
Definition: generic_subscriber.hpp:39
CircuitStatusUavcanToRos::CircuitStatusUavcanToRos
CircuitStatusUavcanToRos(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:169
UavcanNode
uavcan::Node< NodeMemoryPoolSize > UavcanNode
Definition: converters.hpp:58
MagnetometerRosToUavcan
Definition: converters.hpp:238
AhrsSolutionUavcanToRos
Definition: converters.hpp:131
UavcanToRosConverter::uavcan_callback
virtual void uavcan_callback(const uavcan::ReceivedDataStructure< IN_UAVCAN_MSG > &uavcan_msg)=0
uavcan::Subscriber::start
int start(const Callback &callback)
Definition: subscriber.hpp:83
DiffPressureRosToUavcan
Definition: converters.hpp:194
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
RosToUavcanConverter::ros_sub_
ros::Subscriber ros_sub_
Definition: converters.hpp:91
CircuitStatusUavcanToRos
Definition: converters.hpp:163
ImuRosToUavcan::ros_callback
void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override
Definition: converters.cpp:155
ArrayCommandUavcanToRos::uavcan_callback
void uavcan_callback(const uavcan::ReceivedDataStructure< IN_UAVCAN_MSG > &uavcan_msg) override
Definition: converters.cpp:36
RosToUavcanConverter::broadcast
void broadcast()
Definition: converters.hpp:100
instantiate_converter
std::unique_ptr< Converter > instantiate_converter(std::string converter_name, ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.cpp:223
RosToUavcanConverter::IN_ROS_MSG
IN_ROS IN_ROS_MSG
Definition: converters.hpp:87
IceFuelTankStatusRosToUavcan::IceFuelTankStatusRosToUavcan
IceFuelTankStatusRosToUavcan(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:276
RawCommandUavcanToRos::uavcan_callback
void uavcan_callback(const uavcan::ReceivedDataStructure< IN_UAVCAN_MSG > &uavcan_msg) override
Definition: converters.cpp:49
EscStatusUavcanToRos::uavcan_callback
void uavcan_callback(const uavcan::ReceivedDataStructure< IN_UAVCAN_MSG > &uavcan_msg) override
Definition: converters.cpp:98
ArrayCommandUavcanToRos::ArrayCommandUavcanToRos
ArrayCommandUavcanToRos(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:126
BatteryInfoRosToUavcan::BatteryInfoRosToUavcan
BatteryInfoRosToUavcan(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:286
EscStatusRosToUavcan::ros_callback
void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override
Definition: converters.cpp:175
RosToUavcanConverter::_name
std::string _name
Definition: converters.hpp:92
AhrsSolutionUavcanToRos::uavcan_callback
void uavcan_callback(const uavcan::ReceivedDataStructure< IN_UAVCAN_MSG > &uavcan_msg) override
Definition: converters.cpp:63
BaroStaticPressureRosToUavcan::ros_callback
void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override
Definition: converters.cpp:109
UavcanToRosConverter::ros_pub_
ros::Publisher ros_pub_
Definition: converters.hpp:68
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
IceFuelTankStatusRosToUavcan::ros_callback
void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override
Definition: converters.cpp:196
BatteryInfoRosToUavcan::ros_callback
void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override
Definition: converters.cpp:201
Converter
Definition: converters.hpp:61
ArmUavcanToRos
Definition: converters.hpp:141
uavcan.hpp
ArmUavcanToRos::uavcan_callback
void uavcan_callback(const uavcan::ReceivedDataStructure< IN_UAVCAN_MSG > &uavcan_msg) override
Definition: converters.cpp:83
EscStatusUavcanToRos
Definition: converters.hpp:152
IceReciprocatingStatusRosToUavcan
Definition: converters.hpp:257
EscStatusRosToUavcan
Definition: converters.hpp:247
RosToUavcanConverter::uavcan_pub_
uavcan::Publisher< OUT_UAVCAN_MSG > uavcan_pub_
Definition: converters.hpp:90
GpsRosToUavcan::ros_velocity_callback
void ros_velocity_callback(geometry_msgs::Twist::Ptr in_ros_msg)
Definition: converters.cpp:148
GpsRosToUavcan
Definition: converters.hpp:211
BaroStaticTemperatureRosToUavcan::ros_callback
void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override
Definition: converters.cpp:116
UavcanToRosConverter
Definition: converters.hpp:64
DiffPressureRosToUavcan::ros_callback
void ros_callback(IN_ROS_MSG_PTR in_ros_msg) override
Definition: converters.cpp:123
AhrsSolutionUavcanToRos::AhrsSolutionUavcanToRos
AhrsSolutionUavcanToRos(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:136
RosToUavcanConverter::enabled
bool enabled
Definition: converters.hpp:85
DiffPressureRosToUavcan::_temperature
BaroStaticTemperatureRosToUavcan _temperature
Definition: converters.hpp:199
RosToUavcanConverter::RosToUavcanConverter
RosToUavcanConverter(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic, std::string name)
Definition: converters.hpp:95
MagnetometerRosToUavcan::MagnetometerRosToUavcan
MagnetometerRosToUavcan(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:243
RosToUavcanConverter
Definition: converters.hpp:81
IceReciprocatingStatusRosToUavcan::IceReciprocatingStatusRosToUavcan
IceReciprocatingStatusRosToUavcan(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:264
IceReciprocatingStatusRosToUavcan::ros_status_sub_
ros::Subscriber ros_status_sub_
Definition: converters.hpp:262
uavcan::Publisher::broadcast
int broadcast(const DataType &message)
Definition: publisher.hpp:52
UavcanToRosConverter::IN_UAVCAN_MSG
IN_UAVCAN IN_UAVCAN_MSG
Definition: converters.hpp:67
IceReciprocatingStatusRosToUavcan::ros_status_callback
void ros_status_callback(std_msgs::UInt8 in_ros_msg)
Definition: converters.cpp:191
ImuRosToUavcan::ImuRosToUavcan
ImuRosToUavcan(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:233
GpsRosToUavcan::ros_velocity_sub_
ros::Subscriber ros_velocity_sub_
Definition: converters.hpp:216
RosToUavcanConverter::out_uavcan_msg_
OUT_UAVCAN_MSG out_uavcan_msg_
Definition: converters.hpp:84
NodeMemoryPoolSize
constexpr unsigned NodeMemoryPoolSize
Definition: converters.hpp:57
UavcanToRosConverter::uavcan_sub_
uavcan::Subscriber< IN_UAVCAN_MSG > uavcan_sub_
Definition: converters.hpp:69
uavcan::Node
Definition: node.hpp:38
BaroStaticPressureRosToUavcan
Definition: converters.hpp:174
ros::NodeHandle
ros::Subscriber
ArrayCommandUavcanToRos
Definition: converters.hpp:121
RosToUavcanConverter::ros_callback
virtual void ros_callback(IN_ROS_MSG_PTR in_ros_msg)=0
UavcanToRosConverter::UavcanToRosConverter
UavcanToRosConverter(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:73
GpsRosToUavcan::GpsRosToUavcan
GpsRosToUavcan(ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic)
Definition: converters.hpp:218


uavcan_communicator
Author(s):
autogenerated on Fri Dec 13 2024 03:10:02