#include <odom_subscriber.h>
Public Member Functions | |
nav_2d_msgs::Twist2D | getTwist () |
nav_2d_msgs::Twist2DStamped | getTwistStamped () |
OdomSubscriber (ros::NodeHandle &nh, std::string default_topic="odom") | |
Constructor that subscribes to an Odometry topic. | |
Protected Member Functions | |
void | odomCallback (const nav_msgs::Odometry::ConstPtr &msg) |
Protected Attributes | |
boost::mutex | odom_mutex_ |
ros::Subscriber | odom_sub_ |
nav_2d_msgs::Twist2DStamped | odom_vel_ |
Wrapper for some common odometry operations. Subscribes to the topic with a mutex.
Definition at line 52 of file odom_subscriber.h.
nav_2d_utils::OdomSubscriber::OdomSubscriber | ( | ros::NodeHandle & | nh, |
std::string | default_topic = "odom" |
||
) | [inline, explicit] |
Constructor that subscribes to an Odometry topic.
nh | NodeHandle for creating subscriber |
default_topic | Name of the topic that will be loaded of the odom_topic param is not set. |
Definition at line 61 of file odom_subscriber.h.
nav_2d_msgs::Twist2D nav_2d_utils::OdomSubscriber::getTwist | ( | ) | [inline] |
Definition at line 68 of file odom_subscriber.h.
nav_2d_msgs::Twist2DStamped nav_2d_utils::OdomSubscriber::getTwistStamped | ( | ) | [inline] |
Definition at line 69 of file odom_subscriber.h.
void nav_2d_utils::OdomSubscriber::odomCallback | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) | [inline, protected] |
Definition at line 72 of file odom_subscriber.h.
boost::mutex nav_2d_utils::OdomSubscriber::odom_mutex_ [protected] |
Definition at line 82 of file odom_subscriber.h.
Definition at line 80 of file odom_subscriber.h.
nav_2d_msgs::Twist2DStamped nav_2d_utils::OdomSubscriber::odom_vel_ [protected] |
Definition at line 81 of file odom_subscriber.h.