#include <converters.hpp>
Public Member Functions | |
GpsRosToUavcan (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 |
void | ros_velocity_callback (geometry_msgs::Twist::Ptr in_ros_msg) |
Private Attributes | |
ros::Subscriber | ros_velocity_sub_ |
Definition at line 211 of file converters.hpp.
|
inline |
Definition at line 218 of file converters.hpp.
|
overrideprivatevirtual |
Implements RosToUavcanConverter< sensor_msgs::NavSatFix, uavcan::equipment::gnss::Fix2 >.
Definition at line 137 of file converters.cpp.
|
private |
Definition at line 148 of file converters.cpp.
|
private |
Definition at line 216 of file converters.hpp.