38 #ifndef ODOMETRY_HELPER_ROS2_H_ 39 #define ODOMETRY_HELPER_ROS2_H_ 42 #include <nav_msgs/Odometry.h> 44 #include <boost/thread.hpp> 62 void odomCallback(
const nav_msgs::Odometry::ConstPtr& msg);
64 void getOdom(nav_msgs::Odometry& base_odom);
void getRobotVel(tf::Stamped< tf::Pose > &robot_vel)
void getOdom(nav_msgs::Odometry &base_odom)
std::string getOdomTopic() const
Return the current odometry topic.
nav_msgs::Odometry base_odom_
ros::Subscriber odom_sub_
OdometryHelperRos(std::string odom_topic="")
Constructor.
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
Callback for receiving odometry data.
void setOdomTopic(std::string odom_topic)
Set the odometry topic. This overrides what was set in the constructor, if anything.
std::string frame_id_
The frame_id associated this data.