odometry_helper.hpp
Go to the documentation of this file.
1 
4 /*****************************************************************************
5 ** Ifdefs
6 *****************************************************************************/
7 
8 #ifndef yocs_navi_toolkit_ODOMETRY_HELPER_HPP_
9 #define yocs_navi_toolkit_ODOMETRY_HELPER_HPP_
10 
11 /*****************************************************************************
12 ** Includes
13 *****************************************************************************/
14 
15 #include <ecl/linear_algebra.hpp>
16 #include <memory>
17 #include <mutex>
18 #include <nav_msgs/Odometry.h>
19 #include <ros/ros.h>
20 #include <utility>
21 
22 /*****************************************************************************
23 ** Namespaces
24 *****************************************************************************/
25 
26 namespace yocs_navi_toolkit {
27 
28 /*****************************************************************************
29 ** Interfaces
30 *****************************************************************************/
31 
33 {
34 public:
35  OdometryHelper(const std::string& odometry_topic_name);
36  virtual ~OdometryHelper();
37 
38  /********************
39  ** Setters
40  ********************/
41  void odometryCallback(const nav_msgs::Odometry::ConstPtr& msg);
42 
43  /********************
44  ** Getters
45  ********************/
46  // convenience getters in various formats.
47 
51  void position(Eigen::Vector3f& position);
52 
58  void yaw(float& angle);
59 
65  void velocities(std::pair<float, float>& mobile_robot_velocities);
66  nav_msgs::Odometry odometry();
67 
68 protected:
70  std::mutex data_mutex_;
71  nav_msgs::Odometry odometry_;
72 };
73 
74 /*****************************************************************************
75 ** Typedefs
76 *****************************************************************************/
77 
78 typedef std::shared_ptr<OdometryHelper> OdometryHelperPtr;
79 
80 /*****************************************************************************
81 ** Trailers
82 *****************************************************************************/
83 
84 } // namespace yocs_navi_toolkit
85 
86 #endif /* yocs_navi_toolkit_ODOMETRY_HELPER_HPP_ */
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
void odometryCallback(const nav_msgs::Odometry::ConstPtr &msg)
OdometryHelper(const std::string &odometry_topic_name)
void velocities(std::pair< float, float > &mobile_robot_velocities)
Mobile robot velocities in a 2d use case.
void yaw(float &angle)
Heading angle for mobile robot 2d use cases.
std::shared_ptr< OdometryHelper > OdometryHelperPtr
void position(Eigen::Vector3f &position)
3d position of the robot in eigen format.


yocs_navi_toolkit
Author(s): Daniel Stonier
autogenerated on Mon Jun 10 2019 15:53:55