Go to the documentation of this file.
38 #ifndef ODOMETRY_HELPER_ROS2_H_
39 #define ODOMETRY_HELPER_ROS2_H_
41 #include <nav_msgs/Odometry.h>
43 #include <boost/thread.hpp>
44 #include <geometry_msgs/PoseStamped.h>
48 class OdometryHelperRos {
62 void odomCallback(
const nav_msgs::Odometry::ConstPtr& msg);
64 void getOdom(nav_msgs::Odometry& base_odom);
66 void getRobotVel(geometry_msgs::PoseStamped& robot_vel);
void setOdomTopic(std::string odom_topic)
Set the odometry topic. This overrides what was set in the constructor, if anything.
nav_msgs::Odometry base_odom_
OdometryHelperRos(std::string odom_topic="")
Constructor.
void getOdom(nav_msgs::Odometry &base_odom)
std::string frame_id_
The frame_id associated this data.
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
Callback for receiving odometry data.
std::string getOdomTopic() const
Return the current odometry topic.
void getRobotVel(geometry_msgs::PoseStamped &robot_vel)
ros::Subscriber odom_sub_
base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:24