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
00039 #ifndef GRAPH_MAPPING_UTILS_MSG_H
00040 #define GRAPH_MAPPING_UTILS_MSG_H
00041
00042 #include <graph_mapping_msgs/Node.h>
00043 #include <graph_mapping_msgs/Edge.h>
00044 #include <graph_mapping_msgs/NodePoses.h>
00045 #include "geometry.h"
00046 #include <boost/lexical_cast.hpp>
00047 #include <boost/format.hpp>
00048
00049
00050 namespace graph_mapping_utils
00051 {
00052
00053 using graph_mapping_msgs::Node;
00054 using graph_mapping_msgs::Edge;
00055 using graph_mapping_msgs::PoseWithPrecision;
00056 using graph_mapping_msgs::NodePoses;
00057 using std::string;
00058
00059 inline
00060 Node makeNode (unsigned n)
00061 {
00062 Node node;
00063 node.id = n;
00064 return node;
00065 }
00066
00067 inline
00068 Edge makeEdge (unsigned e, unsigned from, unsigned to, const PoseWithPrecision& constraint)
00069 {
00070 Edge edge;
00071 edge.id = e;
00072 edge.constraint.src = from;
00073 edge.constraint.dest = to;
00074 edge.constraint.constraint = constraint;
00075 return edge;
00076 }
00077
00078 inline
00079 unsigned index(const unsigned i, const unsigned j)
00080 {
00081 return 6*i + j;
00082 }
00083
00085 inline
00086 boost::array<double, 36> makePrecisionMatrix (const double x, const double y, const double xy, const double theta)
00087 {
00088 boost::array<double, 36> prec;
00089 std::fill(prec.begin(), prec.end(), 0.0);
00090 prec[index(0,0)] = x;
00091 prec[index(1,1)] = y;
00092 prec[index(0,1)] = xy;
00093 prec[index(1,0)] = xy;
00094 prec[index(5,5)] = theta;
00095
00096 return prec;
00097 }
00098
00099
00100 typedef std::map<unsigned, tf::Pose> NodePoseMap;
00101 NodePoseMap fromMsg (const NodePoses& poses);
00102 NodePoses::ConstPtr toMsg (const NodePoseMap& poses);
00103
00104 struct InvalidGraphLocalizationException: public std::logic_error
00105 {
00106 InvalidGraphLocalizationException (const string& frame) :
00107 std::logic_error((boost::format("Frame %1% is not of form nodeXXX")
00108 % frame).str())
00109 {}
00110 };
00111
00116 inline
00117 unsigned refNode (const geometry_msgs::PoseStamped& p)
00118 {
00119 try
00120 {
00121 return boost::lexical_cast<unsigned>((p.header.frame_id.c_str()+4));
00122 }
00123 catch (boost::bad_lexical_cast&)
00124 {
00125 throw InvalidGraphLocalizationException(p.header.frame_id);
00126 }
00127 }
00128
00129 inline
00130 string nodeFrame (const unsigned n)
00131 {
00132 return ("node" + boost::lexical_cast<string>(n));
00133 }
00134
00136 inline
00137 tf::Pose optimizedPose (const gm::PoseStamped& loc,
00138 const std::map<unsigned, tf::Pose>& opt_poses)
00139 {
00140 const tf::Pose& ref_pose = keyValue(opt_poses, refNode(loc));
00141 return toPose(transformPose(ref_pose, loc.pose));
00142 }
00143
00144
00145 }
00146
00147 #endif // include guard
00148
00149