#include <odometry_helper.hpp>
Definition at line 32 of file odometry_helper.hpp.
yocs_navi_toolkit::OdometryHelper::OdometryHelper |
( |
const std::string & |
odometry_topic_name | ) |
|
yocs_navi_toolkit::OdometryHelper::~OdometryHelper |
( |
| ) |
|
|
virtual |
nav_msgs::Odometry yocs_navi_toolkit::OdometryHelper::odometry |
( |
| ) |
|
void yocs_navi_toolkit::OdometryHelper::odometryCallback |
( |
const nav_msgs::Odometry::ConstPtr & |
msg | ) |
|
void yocs_navi_toolkit::OdometryHelper::position |
( |
Eigen::Vector3f & |
position | ) |
|
void yocs_navi_toolkit::OdometryHelper::velocities |
( |
std::pair< float, float > & |
mobile_robot_velocities | ) |
|
Mobile robot velocities in a 2d use case.
- Parameters
-
mobile_robot_velocities | : linear translational velocity, v and angular rate, w |
Definition at line 52 of file odometry_helper.cpp.
void yocs_navi_toolkit::OdometryHelper::yaw |
( |
float & |
angle | ) |
|
Heading angle for mobile robot 2d use cases.
- Parameters
-
Definition at line 47 of file odometry_helper.cpp.
std::mutex yocs_navi_toolkit::OdometryHelper::data_mutex_ |
|
protected |
nav_msgs::Odometry yocs_navi_toolkit::OdometryHelper::odometry_ |
|
protected |
The documentation for this class was generated from the following files: