#include <converters.hpp>

Public Member Functions | |
| AhrsSolutionUavcanToRos (ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic) | |
Private Member Functions | |
| void | uavcan_callback (const uavcan::ReceivedDataStructure< IN_UAVCAN_MSG > &uavcan_msg) override |
Additional Inherited Members | |
Protected Types inherited from UavcanToRosConverter< uavcan::equipment::ahrs::Solution, sensor_msgs::Imu > | |
| typedef uavcan::equipment::ahrs::Solution | IN_UAVCAN_MSG |
| typedef sensor_msgs::Imu | OUT_ROS_MSG |
Protected Member Functions inherited from UavcanToRosConverter< uavcan::equipment::ahrs::Solution, sensor_msgs::Imu > | |
| virtual void | uavcan_callback (const uavcan::ReceivedDataStructure< IN_UAVCAN_MSG > &uavcan_msg)=0 |
| UavcanToRosConverter (ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic) | |
Protected Attributes inherited from UavcanToRosConverter< uavcan::equipment::ahrs::Solution, sensor_msgs::Imu > | |
| OUT_ROS_MSG | ros_msg_ |
| ros::Publisher | ros_pub_ |
| uavcan::Subscriber< IN_UAVCAN_MSG > | uavcan_sub_ |
Definition at line 119 of file converters.hpp.
|
inline |
Definition at line 124 of file converters.hpp.
|
overrideprivate |
Definition at line 38 of file converters.cpp.