#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 | |
![]() | |
typedef uavcan::equipment::ahrs::Solution | IN_UAVCAN_MSG |
typedef sensor_msgs::Imu | OUT_ROS_MSG |
![]() | |
UavcanToRosConverter (ros::NodeHandle &ros_node, UavcanNode &uavcan_node, const char *ros_topic) | |
![]() | |
OUT_ROS_MSG | ros_msg_ |
ros::Publisher | ros_pub_ |
uavcan::Subscriber< IN_UAVCAN_MSG > | uavcan_sub_ |
Definition at line 131 of file converters.hpp.
|
inline |
Definition at line 136 of file converters.hpp.
|
overrideprivatevirtual |
Implements UavcanToRosConverter< uavcan::equipment::ahrs::Solution, sensor_msgs::Imu >.
Definition at line 63 of file converters.cpp.