#include <converters.hpp>
Public Member Functions | |
BaroStaticPressureRosToUavcan (ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic) | |
Private Member Functions | |
void | ros_callback (IN_ROS_MSG_PTR in_ros_msg) override |
Definition at line 174 of file converters.hpp.
|
inline |
Definition at line 179 of file converters.hpp.
|
overrideprivatevirtual |
Implements RosToUavcanConverter< std_msgs::Float32, uavcan::equipment::air_data::StaticPressure >.
Definition at line 109 of file converters.cpp.