#include <odometry_helper_ros.h>
Definition at line 48 of file odometry_helper_ros.h.
base_local_planner::OdometryHelperRos::OdometryHelperRos |
( |
std::string |
odom_topic = "" | ) |
|
Constructor.
- Parameters
-
odom_topic | The topic on which to subscribe to Odometry messages. If the empty string is given (the default), no subscription is done. |
Definition at line 41 of file odometry_helper_ros.cpp.
base_local_planner::OdometryHelperRos::~OdometryHelperRos |
( |
| ) |
|
|
inline |
void base_local_planner::OdometryHelperRos::getOdom |
( |
nav_msgs::Odometry & |
base_odom | ) |
|
std::string base_local_planner::OdometryHelperRos::getOdomTopic |
( |
| ) |
const |
|
inline |
void base_local_planner::OdometryHelperRos::odomCallback |
( |
const nav_msgs::Odometry::ConstPtr & |
msg | ) |
|
void base_local_planner::OdometryHelperRos::setOdomTopic |
( |
std::string |
odom_topic | ) |
|
Set the odometry topic. This overrides what was set in the constructor, if anything.
This unsubscribes from the old topic (if any) and subscribes to the new one (if any).
If odom_topic is the empty string, this just unsubscribes from the previous topic.
Definition at line 80 of file odometry_helper_ros.cpp.
nav_msgs::Odometry base_local_planner::OdometryHelperRos::base_odom_ |
|
private |
std::string base_local_planner::OdometryHelperRos::frame_id_ |
|
private |
boost::mutex base_local_planner::OdometryHelperRos::odom_mutex_ |
|
private |
std::string base_local_planner::OdometryHelperRos::odom_topic_ |
|
private |
The documentation for this class was generated from the following files: