Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00042 #ifndef POSE_GRAPH_TRANSFORM_H
00043 #define POSE_GRAPH_TRANSFORM_H
00044
00045 #include <Eigen3/Dense>
00046 #include <tf/transform_datatypes.h>
00047 #include <geometry_msgs/Pose.h>
00048 #include <geometry_msgs/Point32.h>
00049 #include <geometry_msgs/Pose2D.h>
00050 #include <nav_msgs/OccupancyGrid.h>
00051
00052 namespace pose_graph
00053 {
00054
00055 using Eigen3::Affine3d;
00056 using Eigen3::Vector3d;
00057 using Eigen3::Quaterniond;
00058 using geometry_msgs::Pose;
00059 using geometry_msgs::Point32;
00060 using geometry_msgs::Pose2D;
00061 using geometry_msgs::Point;
00062
00063
00065 Affine3d poseToWorldTransform (const Pose& pose);
00066
00068 Affine3d relativeTransform (const Pose& pose1, const Pose& pose2);
00069
00071 Affine3d relativeTransform (const Pose2D& pose1, const Pose2D& pose2);
00072
00075 Pose relativePose (const Pose& pose1, const Pose& pose2);
00076
00078 Point pointInReferenceFrame (const Point& p, const Pose& pose);
00079
00082 Affine3d transformBetween (const Pose& pose1, const Pose& pose2);
00083
00085 Pose applyTransform (const Affine3d& trans, const Pose& pose);
00086
00088 Point32 transformPoint (const Affine3d& trans, const Point32& pt);
00089
00091 Point transformPoint (const Affine3d& trans, const Point& pt);
00092
00094 Pose perturbPose (const Pose& pose, double r);
00095
00097 Eigen3::Vector4d quaternionMsgToVector4d (const geometry_msgs::Quaternion& m);
00098
00100 Eigen3::Vector4d translationToVector4d(const geometry_msgs::Point& p);
00101
00103 Pose2D projectToPose2D (const Pose& pose);
00104
00106 Pose convertToPose (const Pose2D& pose2d);
00107
00109 Pose convertToPose (const Affine3d trans);
00110
00112 Pose2D makePose2D (double x, double y, double theta=0.0);
00113
00115 nav_msgs::OccupancyGrid transformGrid (const Affine3d& trans, const nav_msgs::OccupancyGrid& g);
00116
00118 nav_msgs::MapMetaData getMapInfo (const Pose& pose, const double size, const double resolution);
00119
00120
00121 }
00122
00123 #endif