#include <pose_helper.hpp>
|
| geometry_msgs::PoseWithCovarianceStamped | pose () |
| |
| void | poseCallback (const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg) |
| |
| | PoseHelper (const std::string &pose_topic_name) |
| |
| void | position (Eigen::Vector3f &position) |
| | 3d position of the robot in eigen format. More...
|
| |
| void | yaw (float &angle) |
| | Heading angle for mobile robot 2d use cases. More...
|
| |
| virtual | ~PoseHelper () |
| |
Definition at line 32 of file pose_helper.hpp.
| yocs_navi_toolkit::PoseHelper::PoseHelper |
( |
const std::string & |
pose_topic_name | ) |
|
| yocs_navi_toolkit::PoseHelper::~PoseHelper |
( |
| ) |
|
|
virtual |
| geometry_msgs::PoseWithCovarianceStamped yocs_navi_toolkit::PoseHelper::pose |
( |
| ) |
|
| void yocs_navi_toolkit::PoseHelper::poseCallback |
( |
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr & |
msg | ) |
|
| void yocs_navi_toolkit::PoseHelper::position |
( |
Eigen::Vector3f & |
position | ) |
|
3d position of the robot in eigen format.
Definition at line 48 of file pose_helper.cpp.
| void yocs_navi_toolkit::PoseHelper::yaw |
( |
float & |
angle | ) |
|
Heading angle for mobile robot 2d use cases.
- Parameters
-
Definition at line 43 of file pose_helper.cpp.
| std::mutex yocs_navi_toolkit::PoseHelper::data_mutex_ |
|
protected |
| geometry_msgs::PoseWithCovarianceStamped yocs_navi_toolkit::PoseHelper::pose_ |
|
protected |
The documentation for this class was generated from the following files: