pose_helper.hpp
Go to the documentation of this file.
1 
4 /*****************************************************************************
5 ** Ifdefs
6 *****************************************************************************/
7 
8 #ifndef yocs_navi_toolkit_POSE_HELPER_HPP_
9 #define yocs_navi_toolkit_POSE_HELPER_HPP_
10 
11 /*****************************************************************************
12 ** Includes
13 *****************************************************************************/
14 
15 #include <ecl/linear_algebra.hpp>
16 #include <memory>
17 #include <mutex>
18 #include <geometry_msgs/PoseWithCovarianceStamped.h>
19 #include <ros/ros.h>
20 
21 
22 /*****************************************************************************
23 ** Namespaces
24 *****************************************************************************/
25 
26 namespace yocs_navi_toolkit {
27 
28 /*****************************************************************************
29 ** Interfaces
30 *****************************************************************************/
31 
33 {
34 public:
35  PoseHelper(const std::string& pose_topic_name);
36  virtual ~PoseHelper();
37 
38  /********************
39  ** Setters
40  ********************/
41  void poseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg);
42 
43  /********************
44  ** Getters
45  ********************/
46  // getters that return the data in various convenience formats
47 
51  void position(Eigen::Vector3f& position);
52 
58  void yaw(float& angle);
59 
60  geometry_msgs::PoseWithCovarianceStamped pose();
61 
62 protected:
64  std::mutex data_mutex_;
65  geometry_msgs::PoseWithCovarianceStamped pose_;
66 };
67 
68 /*****************************************************************************
69 ** Typedefs
70 *****************************************************************************/
71 
72 typedef std::shared_ptr<PoseHelper> PoseHelperPtr;
73 
74 /*****************************************************************************
75 ** Trailers
76 *****************************************************************************/
77 
78 } // namespace yocs_navi_toolkit
79 
80 #endif /* yocs_navi_toolkit_ODOMETRY_HELPER_HPP_ */
void yaw(float &angle)
Heading angle for mobile robot 2d use cases.
Definition: pose_helper.cpp:43
geometry_msgs::PoseWithCovarianceStamped pose_
Definition: pose_helper.hpp:65
PoseHelper(const std::string &pose_topic_name)
Definition: pose_helper.cpp:22
void position(Eigen::Vector3f &position)
3d position of the robot in eigen format.
Definition: pose_helper.cpp:48
geometry_msgs::PoseWithCovarianceStamped pose()
Definition: pose_helper.cpp:36
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
void poseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
Definition: pose_helper.cpp:30
ros::Subscriber pose_subscriber_
Definition: pose_helper.hpp:63
std::shared_ptr< PoseHelper > PoseHelperPtr
Definition: pose_helper.hpp:72


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