#include <robot_information.h>
Public Types | |
typedef boost::shared_ptr < RobotInformation > | Ptr |
Public Member Functions | |
const std::string & | getGlobalFrame () const |
const std::string & | getRobotFrame () const |
bool | getRobotPose (geometry_msgs::PoseStamped &robot_pose) const |
bool | getRobotVelocity (geometry_msgs::TwistStamped &robot_velocity, ros::Duration look_back_duration) const |
const ros::Duration & | getTfTimeout () const |
const TF & | getTransformListener () const |
RobotInformation (TF &tf_listener, const std::string &global_frame, const std::string &robot_frame, const ros::Duration &tf_timeout) | |
Private Attributes | |
const std::string & | global_frame_ |
const std::string & | robot_frame_ |
const TF & | tf_listener_ |
const ros::Duration & | tf_timeout_ |
Definition at line 53 of file robot_information.h.
typedef boost::shared_ptr<RobotInformation> mbf_abstract_nav::RobotInformation::Ptr |
Definition at line 57 of file robot_information.h.
mbf_abstract_nav::RobotInformation::RobotInformation | ( | TF & | tf_listener, |
const std::string & | global_frame, | ||
const std::string & | robot_frame, | ||
const ros::Duration & | tf_timeout | ||
) |
Definition at line 44 of file robot_Information.cpp.
const std::string & mbf_abstract_nav::RobotInformation::getGlobalFrame | ( | ) | const |
Definition at line 75 of file robot_Information.cpp.
const std::string & mbf_abstract_nav::RobotInformation::getRobotFrame | ( | ) | const |
Definition at line 77 of file robot_Information.cpp.
bool mbf_abstract_nav::RobotInformation::getRobotPose | ( | geometry_msgs::PoseStamped & | robot_pose | ) | const |
Definition at line 55 of file robot_Information.cpp.
bool mbf_abstract_nav::RobotInformation::getRobotVelocity | ( | geometry_msgs::TwistStamped & | robot_velocity, |
ros::Duration | look_back_duration | ||
) | const |
Definition at line 69 of file robot_Information.cpp.
const ros::Duration & mbf_abstract_nav::RobotInformation::getTfTimeout | ( | ) | const |
Definition at line 81 of file robot_Information.cpp.
const TF & mbf_abstract_nav::RobotInformation::getTransformListener | ( | ) | const |
Definition at line 79 of file robot_Information.cpp.
const std::string& mbf_abstract_nav::RobotInformation::global_frame_ [private] |
Definition at line 80 of file robot_information.h.
const std::string& mbf_abstract_nav::RobotInformation::robot_frame_ [private] |
Definition at line 82 of file robot_information.h.
const TF& mbf_abstract_nav::RobotInformation::tf_listener_ [private] |
Definition at line 78 of file robot_information.h.
const ros::Duration& mbf_abstract_nav::RobotInformation::tf_timeout_ [private] |
Definition at line 84 of file robot_information.h.