#include <odom_subscriber.h>
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" |
|
) |
| |
|
inlineexplicit |
Constructor that subscribes to an Odometry topic.
- Parameters
-
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 |
nav_2d_msgs::Twist2DStamped nav_2d_utils::OdomSubscriber::getTwistStamped |
( |
| ) |
|
|
inline |
void nav_2d_utils::OdomSubscriber::odomCallback |
( |
const nav_msgs::Odometry::ConstPtr & |
msg | ) |
|
|
inlineprotected |
boost::mutex nav_2d_utils::OdomSubscriber::odom_mutex_ |
|
protected |
nav_2d_msgs::Twist2DStamped nav_2d_utils::OdomSubscriber::odom_vel_ |
|
protected |
The documentation for this class was generated from the following file: