Public Member Functions | Private Attributes
base_local_planner::OdometryHelperRos Class Reference

#include <odometry_helper_ros.h>

List of all members.

Public Member Functions

void getOdom (nav_msgs::Odometry &base_odom)
std::string getOdomTopic () const
 Return the current odometry topic.
void getRobotVel (tf::Stamped< tf::Pose > &robot_vel)
void odomCallback (const nav_msgs::Odometry::ConstPtr &msg)
 Callback for receiving odometry data.
 OdometryHelperRos (std::string odom_topic="")
 Constructor.
void setOdomTopic (std::string odom_topic)
 Set the odometry topic. This overrides what was set in the constructor, if anything.
 ~OdometryHelperRos ()

Private Attributes

nav_msgs::Odometry base_odom_
std::string frame_id_
 The frame_id associated this data.
boost::mutex odom_mutex_
ros::Subscriber odom_sub_
std::string odom_topic_

Detailed Description

Definition at line 48 of file odometry_helper_ros.h.


Constructor & Destructor Documentation

Constructor.

Parameters:
odom_topicThe 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.

Definition at line 56 of file odometry_helper_ros.h.


Member Function Documentation

void base_local_planner::OdometryHelperRos::getOdom ( nav_msgs::Odometry &  base_odom)

Definition at line 59 of file odometry_helper_ros.cpp.

Return the current odometry topic.

Definition at line 76 of file odometry_helper_ros.h.

Definition at line 65 of file odometry_helper_ros.cpp.

void base_local_planner::OdometryHelperRos::odomCallback ( const nav_msgs::Odometry::ConstPtr &  msg)

Callback for receiving odometry data.

Parameters:
msgAn Odometry message

Definition at line 45 of file odometry_helper_ros.cpp.

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.


Member Data Documentation

Definition at line 84 of file odometry_helper_ros.h.

The frame_id associated this data.

Definition at line 87 of file odometry_helper_ros.h.

Definition at line 85 of file odometry_helper_ros.h.

Definition at line 83 of file odometry_helper_ros.h.

Definition at line 80 of file odometry_helper_ros.h.


The documentation for this class was generated from the following files:


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:46:30