35 #ifndef NAV_2D_UTILS_ODOM_SUBSCRIBER_H 36 #define NAV_2D_UTILS_ODOM_SUBSCRIBER_H 40 #include <nav_msgs/Odometry.h> 41 #include <nav_2d_msgs/Twist2DStamped.h> 42 #include <boost/thread/mutex.hpp> 63 std::string odom_topic;
64 nh.
param(
"odom_topic", odom_topic, default_topic);
87 #endif // NAV_2D_UTILS_ODOM_SUBSCRIBER_H
A set of utility functions for Bounds objects interacting with other messages/types.
nav_2d_msgs::Twist2DStamped getTwistStamped()
#define ROS_INFO_ONCE(...)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
nav_2d_msgs::Twist2D getTwist()
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
OdomSubscriber(ros::NodeHandle &nh, std::string default_topic="odom")
Constructor that subscribes to an Odometry topic.
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
ros::Subscriber odom_sub_
nav_2d_msgs::Twist2D twist3Dto2D(const geometry_msgs::Twist &cmd_vel)
nav_2d_msgs::Twist2DStamped odom_vel_