odometry_helper.hpp
Go to the documentation of this file.
00001 
00004 /*****************************************************************************
00005 ** Ifdefs
00006 *****************************************************************************/
00007 
00008 #ifndef ECL_ODOMETRY_ODOMETRY_HELPER_HPP_
00009 #define ECL_ODOMETRY_ODOMETRY_HELPER_HPP_
00010 
00011 /*****************************************************************************
00012 ** Includes
00013 *****************************************************************************/
00014 
00015 #include <ecl/config/macros.hpp>
00016 #include "macros.hpp"
00017 #include "odometry_typedefs.hpp"
00018 
00019 /*****************************************************************************
00020 ** Namespaces
00021 *****************************************************************************/
00022 
00023 namespace ecl {
00024 namespace odometry {
00025 
00026 /*****************************************************************************
00027 ** Methods
00028 *****************************************************************************/
00029 
00035 ecl_geometry_PUBLIC double distance(const Pose2D& pose, const Trajectory2D& trajectory);
00041 ecl_geometry_PUBLIC double distance(const Position2D& position, const Trajectory2D& trajectory);
00042 
00043 ecl_geometry_PUBLIC bool empty(const Trajectory2D& trajectory); 
00044 ecl_geometry_PUBLIC bool empty(const Odom2DTrajectory& trajectory); 
00046 ecl_geometry_PUBLIC int size(const Trajectory2D& trajectory); 
00047 ecl_geometry_PUBLIC int size(const Odom2DTrajectory& trajectory); 
00049 ecl_geometry_PUBLIC double distance(const Odom2D& a, const Odom2D& b); 
00050 ecl_geometry_PUBLIC double distance(const Pose2D& a, const Pose2D& b); 
00051 ecl_geometry_PUBLIC double distance(const Pose2D& a, const Odom2D& b); 
00052 ecl_geometry_PUBLIC double distanceSqared(const Odom2D& a, const Odom2D& b); 
00053 ecl_geometry_PUBLIC double distanceSqared(const Pose2D& a, const Pose2D& b); 
00060 ecl_geometry_PUBLIC void addAtEnd(Trajectory2D& target, const Trajectory2D& addition);
00066 ecl_geometry_PUBLIC void addAtEnd(Odom2DTrajectory& target, const Odom2DTrajectory& addition);
00067 
00068 ecl_geometry_PUBLIC Trajectory2D vectorToTrajectory(const std::vector<Pose2D>& vec); 
00069 ecl_geometry_PUBLIC Odom2DTrajectory vectorToTrajectory(const std::vector<Odom2D>& vec); 
00076 ecl_geometry_PUBLIC void resize(Trajectory2D& trajectory, const int& size);
00082 ecl_geometry_PUBLIC void resize(Odom2DTrajectory& trajectory, const int& size);
00083 
00084 ecl_geometry_PUBLIC void setAt(Trajectory2D& trajectory, const int& index,  const Pose2D& pose); 
00085 ecl_geometry_PUBLIC void setAt(Odom2DTrajectory& trajectory, const int& index, const Odom2D& odom); 
00087 ecl_geometry_PUBLIC Pose2D getAt(const Trajectory2D& trajectory, const int& index); 
00088 ecl_geometry_PUBLIC Odom2D getAt(const Odom2DTrajectory& trajectory, const int& index); 
00090 ecl_geometry_PUBLIC Pose2D getFront(const Trajectory2D& trajectory); 
00091 ecl_geometry_PUBLIC Pose2D getBack(const Trajectory2D& trajectory); 
00092 ecl_geometry_PUBLIC Odom2D getFront(const Odom2DTrajectory& trajectory); 
00093 ecl_geometry_PUBLIC Odom2D getBack(const Odom2DTrajectory& trajectory); 
00095 ecl_geometry_PUBLIC Trajectory2D getPoses(const Odom2DTrajectory& trajectory); 
00096 ecl_geometry_PUBLIC Twist2DVector getTwists(const Odom2DTrajectory& trajectory); 
00098 ecl_geometry_PUBLIC void setVelocityX(Odom2D& odom, const float& value); 
00099 ecl_geometry_PUBLIC void setVelocityY(Odom2D& odom, const float& value); 
00100 ecl_geometry_PUBLIC void setVelocityAngular(Odom2D& odom, const float& value); 
00102 ecl_geometry_PUBLIC void setVelocityX(Twist2D& twist, const float& value); 
00103 ecl_geometry_PUBLIC void setVelocityY(Twist2D& twist, const float& value); 
00104 ecl_geometry_PUBLIC void setVelocityAngular(Twist2D& twist, const float& value); 
00106 ecl_geometry_PUBLIC void setX(Odom2D& odom, const float& value); 
00107 ecl_geometry_PUBLIC void setY(Odom2D& odom, const float& value); 
00108 ecl_geometry_PUBLIC void setYaw(Odom2D& odom, const float& value); 
00110 ecl_geometry_PUBLIC void setX(Pose2D& pose, const float& value); 
00111 ecl_geometry_PUBLIC void setY(Pose2D& pose, const float& value); 
00112 ecl_geometry_PUBLIC void setYaw(Pose2D& pose, const float& value); 
00114 ecl_geometry_PUBLIC void setX(Position2D& position, const float& value); 
00115 ecl_geometry_PUBLIC void setY(Position2D& position, const float& value); 
00117 ecl_geometry_PUBLIC float getVelocityX(const Odom2D& odom); 
00118 ecl_geometry_PUBLIC float getVelocityY(const Odom2D& odom); 
00119 ecl_geometry_PUBLIC float getVelocityAngular(const Odom2D& odom); 
00121 ecl_geometry_PUBLIC float getVelocityX(const Twist2D& twist); 
00122 ecl_geometry_PUBLIC float getVelocityY(const Twist2D& twist); 
00123 ecl_geometry_PUBLIC float getVelocityAngular(const Twist2D& twist); 
00125 ecl_geometry_PUBLIC float getX(const Odom2D& odom); 
00126 ecl_geometry_PUBLIC float getY(const Odom2D& odom); 
00127 ecl_geometry_PUBLIC float getYaw(const Odom2D& odom); 
00129 ecl_geometry_PUBLIC Pose2D getPose(const Odom2D& odom); 
00130 ecl_geometry_PUBLIC Position2D getPosition(const Odom2D& odom); 
00131 ecl_geometry_PUBLIC Twist2D getTwist(const Odom2D& odom); 
00133 ecl_geometry_PUBLIC float getX(const Pose2D& pose); 
00134 ecl_geometry_PUBLIC float getY(const Pose2D& pose); 
00135 ecl_geometry_PUBLIC float getYaw(const Pose2D& pose); 
00137 ecl_geometry_PUBLIC Position2D getPosition(const Pose2D& pose); 
00139 ecl_geometry_PUBLIC float getX(const Position2D& position); 
00140 ecl_geometry_PUBLIC float getY(const Position2D& position); 
00142 /*****************************************************************************
00143 ** C++11 helpers
00144 *****************************************************************************/
00145 
00146 #if defined(ECL_CXX11_FOUND)
00147 
00148   ecl_geometry_PUBLIC bool empty(const Trajectory2DPtr& trajectory_ptr); 
00149   ecl_geometry_PUBLIC bool empty(const Odom2DTrajectoryPtr& trajectory_ptr); 
00151   ecl_geometry_PUBLIC int size(const Trajectory2DPtr& trajectory); 
00152   ecl_geometry_PUBLIC int size(const Odom2DTrajectoryPtr& trajectory); 
00154   ecl_geometry_PUBLIC Trajectory2DPtr vectorToTrajectoryPtr(const std::vector<Pose2D>& vec); 
00155   ecl_geometry_PUBLIC Odom2DTrajectoryPtr vectorToTrajectoryPtr(const std::vector<Odom2D>& vec); 
00157 #endif /*ECL_CXX11_FOUND*/
00158 
00159 /*****************************************************************************
00160 ** Trailers
00161 *****************************************************************************/
00162 
00163 } // namespace odometry
00164 } // namsepace ecl
00165 
00166 #endif /*ECL_ODOMETRY_ODOMETRY_HELPER_HPP_*/
00167 


ecl_geometry
Author(s): Daniel Stonier
autogenerated on Mon Jul 3 2017 02:21:51