odometry_helper.hpp
Go to the documentation of this file.
1 
4 /*****************************************************************************
5 ** Ifdefs
6 *****************************************************************************/
7 
8 #ifndef ECL_ODOMETRY_ODOMETRY_HELPER_HPP_
9 #define ECL_ODOMETRY_ODOMETRY_HELPER_HPP_
10 
11 /*****************************************************************************
12 ** Includes
13 *****************************************************************************/
14 
15 #include <ecl/config/macros.hpp>
16 #include "macros.hpp"
17 #include "odometry_typedefs.hpp"
18 
19 /*****************************************************************************
20 ** Namespaces
21 *****************************************************************************/
22 
23 namespace ecl {
24 namespace odometry {
25 
26 /*****************************************************************************
27 ** Methods
28 *****************************************************************************/
29 
35 ecl_geometry_PUBLIC double distance(const Pose2D& pose, const Trajectory2D& trajectory);
41 ecl_geometry_PUBLIC double distance(const Position2D& position, const Trajectory2D& trajectory);
42 
43 ecl_geometry_PUBLIC bool empty(const Trajectory2D& trajectory);
44 ecl_geometry_PUBLIC bool empty(const Odom2DTrajectory& trajectory);
46 ecl_geometry_PUBLIC int size(const Trajectory2D& trajectory);
47 ecl_geometry_PUBLIC int size(const Odom2DTrajectory& trajectory);
49 ecl_geometry_PUBLIC double distance(const Odom2D& a, const Odom2D& b);
50 ecl_geometry_PUBLIC double distance(const Pose2D& a, const Pose2D& b);
51 ecl_geometry_PUBLIC double distance(const Pose2D& a, const Odom2D& b);
52 ecl_geometry_PUBLIC double distanceSqared(const Odom2D& a, const Odom2D& b);
53 ecl_geometry_PUBLIC double distanceSqared(const Pose2D& a, const Pose2D& b);
60 ecl_geometry_PUBLIC void addAtEnd(Trajectory2D& target, const Trajectory2D& addition);
66 ecl_geometry_PUBLIC void addAtEnd(Odom2DTrajectory& target, const Odom2DTrajectory& addition);
67 
68 ecl_geometry_PUBLIC Trajectory2D vectorToTrajectory(const std::vector<Pose2D>& vec);
69 ecl_geometry_PUBLIC Odom2DTrajectory vectorToTrajectory(const std::vector<Odom2D>& vec);
76 ecl_geometry_PUBLIC void resize(Trajectory2D& trajectory, const int& size);
82 ecl_geometry_PUBLIC void resize(Odom2DTrajectory& trajectory, const int& size);
83 
84 ecl_geometry_PUBLIC void setAt(Trajectory2D& trajectory, const int& index, const Pose2D& pose);
85 ecl_geometry_PUBLIC void setAt(Odom2DTrajectory& trajectory, const int& index, const Odom2D& odom);
87 ecl_geometry_PUBLIC Pose2D getAt(const Trajectory2D& trajectory, const int& index);
88 ecl_geometry_PUBLIC Odom2D getAt(const Odom2DTrajectory& trajectory, const int& index);
98 ecl_geometry_PUBLIC void setVelocityX(Odom2D& odom, const float& value);
99 ecl_geometry_PUBLIC void setVelocityY(Odom2D& odom, const float& value);
100 ecl_geometry_PUBLIC void setVelocityAngular(Odom2D& odom, const float& value);
102 ecl_geometry_PUBLIC void setVelocityX(Twist2D& twist, const float& value);
103 ecl_geometry_PUBLIC void setVelocityY(Twist2D& twist, const float& value);
104 ecl_geometry_PUBLIC void setVelocityAngular(Twist2D& twist, const float& value);
106 ecl_geometry_PUBLIC void setX(Odom2D& odom, const float& value);
107 ecl_geometry_PUBLIC void setY(Odom2D& odom, const float& value);
108 ecl_geometry_PUBLIC void setYaw(Odom2D& odom, const float& value);
110 ecl_geometry_PUBLIC void setX(Pose2D& pose, const float& value);
111 ecl_geometry_PUBLIC void setY(Pose2D& pose, const float& value);
112 ecl_geometry_PUBLIC void setYaw(Pose2D& pose, const float& value);
114 ecl_geometry_PUBLIC void setX(Position2D& position, const float& value);
115 ecl_geometry_PUBLIC void setY(Position2D& position, const float& value);
117 ecl_geometry_PUBLIC float getVelocityX(const Odom2D& odom);
118 ecl_geometry_PUBLIC float getVelocityY(const Odom2D& odom);
119 ecl_geometry_PUBLIC float getVelocityAngular(const Odom2D& odom);
121 ecl_geometry_PUBLIC float getVelocityX(const Twist2D& twist);
122 ecl_geometry_PUBLIC float getVelocityY(const Twist2D& twist);
123 ecl_geometry_PUBLIC float getVelocityAngular(const Twist2D& twist);
125 ecl_geometry_PUBLIC float getX(const Odom2D& odom);
126 ecl_geometry_PUBLIC float getY(const Odom2D& odom);
127 ecl_geometry_PUBLIC float getYaw(const Odom2D& odom);
133 ecl_geometry_PUBLIC float getX(const Pose2D& pose);
134 ecl_geometry_PUBLIC float getY(const Pose2D& pose);
135 ecl_geometry_PUBLIC float getYaw(const Pose2D& pose);
139 ecl_geometry_PUBLIC float getX(const Position2D& position);
140 ecl_geometry_PUBLIC float getY(const Position2D& position);
142 /*****************************************************************************
143 ** C++11 helpers
144 *****************************************************************************/
145 
146 #if defined(ECL_CXX11_FOUND)
147 
148  ecl_geometry_PUBLIC bool empty(const Trajectory2DPtr& trajectory_ptr);
149  ecl_geometry_PUBLIC bool empty(const Odom2DTrajectoryPtr& trajectory_ptr);
151  ecl_geometry_PUBLIC int size(const Trajectory2DPtr& trajectory);
152  ecl_geometry_PUBLIC int size(const Odom2DTrajectoryPtr& trajectory);
154  ecl_geometry_PUBLIC Trajectory2DPtr vectorToTrajectoryPtr(const std::vector<Pose2D>& vec);
155  ecl_geometry_PUBLIC Odom2DTrajectoryPtr vectorToTrajectoryPtr(const std::vector<Odom2D>& vec);
157 #endif /*ECL_CXX11_FOUND*/
158 
159 /*****************************************************************************
160 ** Trailers
161 *****************************************************************************/
162 
163 } // namespace odometry
164 } // namsepace ecl
165 
166 #endif /*ECL_ODOMETRY_ODOMETRY_HELPER_HPP_*/
167 
ecl_geometry_PUBLIC Twist2DVector getTwists(const Odom2DTrajectory &trajectory)
Extract twists of odom trajectory.
Embedded control libraries.
Eigen::Vector3f Twist2D
Float representation of velocities in 2D (v_x, v_y, w).
ecl_geometry_PUBLIC void setX(Odom2D &odom, const float &value)
Set x position.
ecl_geometry_PUBLIC Trajectory2D getPoses(const Odom2DTrajectory &trajectory)
Extract poses of odom trajectory.
ecl_geometry_PUBLIC Position2D getPosition(const Odom2D &odom)
Extract position from odometry.
ecl_geometry_PUBLIC void setVelocityAngular(Odom2D &odom, const float &value)
Set angular velocity.
ecl_geometry_PUBLIC void resize(Trajectory2D &trajectory, const int &size)
Resizes trajectory appending uninitialised values if needed.
Eigen::Matrix3Xf Trajectory2D
Float representation of a trajectory in 2D (poses in 2D).
ecl_geometry_PUBLIC float getY(const Odom2D &odom)
Get y position.
#define ecl_geometry_PUBLIC
Definition: macros.hpp:37
Eigen::Matrix< float, 6, Eigen::Dynamic > Odom2DTrajectory
Float collection of 2D odometries (x, y, heading, v_x, v_y, w).
ecl_geometry_PUBLIC Pose2D getPose(const Odom2D &odom)
Extract pose from odometry.
ecl_geometry_PUBLIC float getX(const Odom2D &odom)
Get x position.
ecl_geometry_PUBLIC void setY(Odom2D &odom, const float &value)
Set y position.
ecl_geometry_PUBLIC bool empty(const Trajectory2D &trajectory)
Check if trajectory ptr is empty (ptr not set or has no poses)
ecl_geometry_PUBLIC Pose2D getBack(const Trajectory2D &trajectory)
Get back (last) element of trajectory.
Eigen::Vector2f Position2D
Float representation for a 2D position (x-, y-position).
Eigen::Matrix3Xf Twist2DVector
Float collection of 2D twists (twist: v_x, v_y, w).
Eigen::Matrix< float, 6, 1 > Odom2D
Float representation of 2D odometry (x, y, heading, v_x, v_y, w).
ecl_geometry_PUBLIC Trajectory2D vectorToTrajectory(const std::vector< Pose2D > &vec)
Convert vector of Pose2D to Trajectory2D.
ecl_geometry_PUBLIC float getYaw(const Odom2D &odom)
Get yaw (heading)
ecl_geometry_PUBLIC void setVelocityY(Odom2D &odom, const float &value)
Set linear velocity y direction.
ecl_geometry_PUBLIC double distanceSqared(const Odom2D &a, const Odom2D &b)
Squared distance between the positions of odometries.
Eigen::Vector3f Pose2D
Float representation of a pose in 2D (x, y, heading).
ecl_geometry_PUBLIC int size(const Trajectory2D &trajectory)
Get the size of the trajectory.
ecl_geometry_PUBLIC void setYaw(Odom2D &odom, const float &value)
Set yaw (heading)
ecl_geometry_PUBLIC void addAtEnd(Trajectory2D &target, const Trajectory2D &addition)
Concat two odometry trajectories.
ecl_geometry_PUBLIC float getVelocityX(const Odom2D &odom)
Get linear velocity x direction.
ecl_geometry_PUBLIC Pose2D getFront(const Trajectory2D &trajectory)
Get front (first) element of trajectory.
ecl_geometry_PUBLIC Pose2D getAt(const Trajectory2D &trajectory, const int &index)
Get element of trajectory.
ecl_geometry_PUBLIC void setAt(Trajectory2D &trajectory, const int &index, const Pose2D &pose)
Set element at index of trajectory.
ecl_geometry_PUBLIC float getVelocityAngular(const Odom2D &odom)
Get angular velocity.
ecl_geometry_PUBLIC float getVelocityY(const Odom2D &odom)
Get linear velocity y direction.
ecl_geometry_PUBLIC void setVelocityX(Odom2D &odom, const float &value)
Set linear velocity x direction.
ecl_geometry_PUBLIC double distance(const Pose2D &pose, const Trajectory2D &trajectory)
Shortest distance between a pose and a trajectory.
ecl_geometry_PUBLIC Twist2D getTwist(const Odom2D &odom)
Extract twist from odometry.


ecl_geometry
Author(s): Daniel Stonier
autogenerated on Mon Jun 10 2019 13:08:37