19 #ifndef SRC_UAVCAN_COMMUNICATOR_CONVERTERS_HPP_
20 #define SRC_UAVCAN_COMMUNICATOR_CONVERTERS_HPP_
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>
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>
63 template<
typename IN_UAVCAN,
typename OUT_ROS>
80 template<
typename IN_ROS,
typename OUT_UAVCAN>
106 std::cerr <<
_name <<
" publication failure: " << pub_res << std::endl;
113 uavcan::equipment::esc::RawCommand,
122 uavcan::equipment::actuator::ArrayCommand,
132 uavcan::equipment::ahrs::Solution,
142 uavcan::equipment::safety::ArmingStatus,
153 uavcan::equipment::esc::Status,
154 mavros_msgs::ESCTelemetryItem> {
164 uavcan::equipment::power::CircuitStatus,
165 mavros_msgs::BatteryStatus> {
176 uavcan::equipment::air_data::StaticPressure> {
186 uavcan::equipment::air_data::StaticTemperature> {
196 uavcan::equipment::air_data::RawAirData> {
203 _pressure(ros_node, uavcan_node,
"/uav/static_pressure"),
204 _temperature(ros_node, uavcan_node,
"/uav/static_temperature") {
212 sensor_msgs::NavSatFix,
213 uavcan::equipment::gnss::Fix2> {
230 uavcan::equipment::ahrs::RawIMU> {
239 sensor_msgs::MagneticField,
240 uavcan::equipment::ahrs::MagneticFieldStrength> {
248 mavros_msgs::ESCTelemetryItem,
249 uavcan::equipment::esc::Status> {
258 mavros_msgs::ESCStatusItem,
259 uavcan::equipment::ice::reciprocating::Status> {
272 uavcan::equipment::ice::FuelTankStatus> {
281 sensor_msgs::BatteryState,
282 uavcan::equipment::power::BatteryInfo> {
294 const char* ros_topic);
296 #endif // SRC_UAVCAN_COMMUNICATOR_CONVERTERS_HPP_