Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 #include "mrpt_bridge/network_of_poses.h"
00012 #include "mrpt_bridge/pose.h"
00013
00014 #include <geometry_msgs/Pose.h>
00015 #include <geometry_msgs/PoseWithCovariance.h>
00016 #include <mrpt_msgs/NodeIDWithPose.h>
00017
00018 #include <iostream>
00019
00020 namespace mrpt_bridge
00021 {
00023
00025
00026 void convert(
00027 const mrpt::graphs::CNetworkOfPoses2DInf& mrpt_graph,
00028 mrpt_msgs::NetworkOfPoses& ros_graph)
00029 {
00030 MRPT_START;
00031 using namespace geometry_msgs;
00032 using namespace mrpt::math;
00033 using namespace mrpt::graphs;
00034 using namespace mrpt::poses;
00035 using namespace std;
00036
00037 typedef typename mrpt::graphs::CNetworkOfPoses2DInf::global_poses_t::
00038 const_iterator poses_cit_t;
00039
00040 const CNetworkOfPoses2DInf::BASE::edges_map_t& constraints =
00041 mrpt_graph.BASE::edges;
00042
00043
00044 ros_graph.root = mrpt_graph.root;
00045
00046
00047 for (poses_cit_t poses_cit = mrpt_graph.nodes.begin();
00048 poses_cit != mrpt_graph.nodes.end(); ++poses_cit)
00049 {
00050 mrpt_msgs::NodeIDWithPose ros_node;
00051
00052
00053 ros_node.nodeID = poses_cit->first;
00054
00055 convert(poses_cit->second, ros_node.pose);
00056
00057
00058 ros_node.str_ID.data = "";
00059 ros_node.nodeID_loc = 0;
00060
00061 ros_graph.nodes.vec.push_back(ros_node);
00062 }
00063
00064
00065 for (CNetworkOfPoses2DInf::const_iterator constr_it = constraints.begin();
00066 constr_it != constraints.end(); ++constr_it)
00067 {
00068 mrpt_msgs::GraphConstraint ros_constr;
00069
00070
00071 ros_constr.nodeID_from = constr_it->first.first;
00072 ros_constr.nodeID_to = constr_it->first.second;
00073
00074
00075 if (mrpt_graph.edges_store_inverse_poses)
00076 {
00077 CPosePDFGaussianInf constr_inv;
00078 constr_it->second.inverse(constr_inv);
00079 convert(constr_inv, ros_constr.constraint);
00080 }
00081 else
00082 {
00083 convert(constr_it->second, ros_constr.constraint);
00084 }
00085
00086 ros_graph.constraints.push_back(ros_constr);
00087 }
00088
00089 MRPT_END;
00090 }
00091
00092 void convert(
00093 const mrpt::graphs::CNetworkOfPoses3DInf& mrpt_graph,
00094 mrpt_msgs::NetworkOfPoses& ros_graph)
00095 {
00096 THROW_EXCEPTION("Conversion not implemented yet");
00097 MRPT_TODO(
00098 "Implement CNetworkOfPoses3DInf => mrpt_msgs::NetworkOfPoses "
00099 "conversion.");
00100 }
00101
00102 void convert(
00103 const mrpt::graphs::CNetworkOfPoses2DInf_NA& mrpt_graph,
00104 mrpt_msgs::NetworkOfPoses& ros_graph)
00105 {
00106 MRPT_START;
00107
00108 using namespace geometry_msgs;
00109 using namespace mrpt::math;
00110 using namespace mrpt::graphs;
00111 using namespace mrpt::poses;
00112 using namespace std;
00113
00114 typedef typename mrpt::graphs::CNetworkOfPoses2DInf_NA::global_poses_t::
00115 const_iterator poses_cit_t;
00116
00118
00119
00120
00121
00122
00123
00124 const CNetworkOfPoses2DInf_NA::BASE::edges_map_t& constraints =
00125 mrpt_graph.BASE::edges;
00126
00127
00128 ros_graph.root = mrpt_graph.root;
00129
00130
00131 for (poses_cit_t poses_cit = mrpt_graph.nodes.begin();
00132 poses_cit != mrpt_graph.nodes.end(); ++poses_cit)
00133 {
00134 mrpt_msgs::NodeIDWithPose ros_node;
00135
00136
00137 ros_node.nodeID = poses_cit->first;
00138
00139 convert(poses_cit->second, ros_node.pose);
00140
00141
00142 ros_node.str_ID.data = poses_cit->second.agent_ID_str;
00143 ros_node.nodeID_loc = poses_cit->second.nodeID_loc;
00144
00145 ros_graph.nodes.vec.push_back(ros_node);
00146 }
00147
00148
00149
00150 for (CNetworkOfPoses2DInf::const_iterator constr_it = constraints.begin();
00151 constr_it != constraints.end(); ++constr_it)
00152 {
00153 mrpt_msgs::GraphConstraint ros_constr;
00154
00155
00156 ros_constr.nodeID_from = constr_it->first.first;
00157 ros_constr.nodeID_to = constr_it->first.second;
00158
00159
00160 if (mrpt_graph.edges_store_inverse_poses)
00161 {
00162 CPosePDFGaussianInf constr_inv;
00163 constr_it->second.inverse(constr_inv);
00164 convert(constr_inv, ros_constr.constraint);
00165 }
00166 else
00167 {
00168 convert(constr_it->second, ros_constr.constraint);
00169 }
00170
00171 ros_graph.constraints.push_back(ros_constr);
00172 }
00173
00174 MRPT_END;
00175 }
00176
00177 void convert(
00178 const mrpt::graphs::CNetworkOfPoses3DInf_NA& mrpt_graph,
00179 mrpt_msgs::NetworkOfPoses& ros_graph)
00180 {
00181 THROW_EXCEPTION("Conversion not implemented yet");
00182 }
00183
00185
00187
00188 void convert(
00189 const mrpt_msgs::NetworkOfPoses& ros_graph,
00190 mrpt::graphs::CNetworkOfPoses2DInf& mrpt_graph)
00191 {
00192 MRPT_START;
00193 using namespace mrpt::utils;
00194 using namespace mrpt::poses;
00195 using namespace mrpt_msgs;
00196 using namespace std;
00197
00198 typedef NetworkOfPoses::_nodes_type::_vec_type::const_iterator nodes_cit_t;
00199 typedef NetworkOfPoses::_constraints_type::const_iterator constraints_cit_t;
00200
00201
00202 mrpt_graph.root = ros_graph.root;
00203
00204
00205 for (nodes_cit_t nodes_cit = ros_graph.nodes.vec.begin();
00206 nodes_cit != ros_graph.nodes.vec.end(); ++nodes_cit)
00207 {
00208
00209 CPose2D mrpt_pose;
00210 convert(nodes_cit->pose, mrpt_pose);
00211
00212 mrpt_graph.nodes.insert(
00213 make_pair(static_cast<TNodeID>(nodes_cit->nodeID), mrpt_pose));
00214 }
00215
00216
00217 for (constraints_cit_t constr_cit = ros_graph.constraints.begin();
00218 constr_cit != ros_graph.constraints.end(); ++constr_cit)
00219 {
00220
00221 TPairNodeIDs constr_ends(
00222 make_pair(
00223 static_cast<TNodeID>(constr_cit->nodeID_from),
00224 static_cast<TNodeID>(constr_cit->nodeID_to)));
00225
00226
00227 mrpt::poses::CPosePDFGaussianInf mrpt_constr;
00228 convert(constr_cit->constraint, mrpt_constr);
00229
00230 mrpt_graph.edges.insert(make_pair(constr_ends, mrpt_constr));
00231 }
00232
00233 mrpt_graph.edges_store_inverse_poses = false;
00234
00235 MRPT_END;
00236 }
00237
00238 void convert(
00239 const mrpt_msgs::NetworkOfPoses& ros_graph,
00240 mrpt::graphs::CNetworkOfPoses3DInf& mrpt_graph)
00241 {
00242 THROW_EXCEPTION("Conversion not implemented yet");
00243 MRPT_TODO(
00244 "Implement mrpt_msgs::NetworkOfPoses => CNetworkOfPoses3DInf "
00245 "conversion.");
00246 }
00247
00248 void convert(
00249 const mrpt_msgs::NetworkOfPoses& ros_graph,
00250 mrpt::graphs::CNetworkOfPoses2DInf_NA& mrpt_graph)
00251 {
00252 MRPT_START;
00253 using namespace mrpt::utils;
00254 using namespace mrpt::poses;
00255 using namespace mrpt_msgs;
00256 using namespace std;
00257
00258 typedef NetworkOfPoses::_nodes_type::_vec_type::const_iterator nodes_cit_t;
00259 typedef NetworkOfPoses::_constraints_type::const_iterator constraints_cit_t;
00260
00261 typedef mrpt::graphs::CNetworkOfPoses2DInf_NA::global_pose_t
00262 mrpt_graph_pose_t;
00263
00264
00265 mrpt_graph.root = ros_graph.root;
00266
00267
00268 for (nodes_cit_t nodes_cit = ros_graph.nodes.vec.begin();
00269 nodes_cit != ros_graph.nodes.vec.end(); ++nodes_cit)
00270 {
00271 mrpt_graph_pose_t mrpt_node;
00272
00273
00274 convert(nodes_cit->pose, mrpt_node);
00275
00276
00277 mrpt_node.agent_ID_str = nodes_cit->str_ID.data;
00278 mrpt_node.nodeID_loc = nodes_cit->nodeID_loc;
00279
00280 mrpt_graph.nodes.insert(
00281 make_pair(static_cast<TNodeID>(nodes_cit->nodeID), mrpt_node));
00282 }
00283
00284
00285 for (constraints_cit_t constr_cit = ros_graph.constraints.begin();
00286 constr_cit != ros_graph.constraints.end(); ++constr_cit)
00287 {
00288
00289 TPairNodeIDs constr_ends(
00290 make_pair(
00291 static_cast<TNodeID>(constr_cit->nodeID_from),
00292 static_cast<TNodeID>(constr_cit->nodeID_to)));
00293
00294
00295 mrpt::poses::CPosePDFGaussianInf mrpt_constr;
00296 convert(constr_cit->constraint, mrpt_constr);
00297
00298 mrpt_graph.edges.insert(make_pair(constr_ends, mrpt_constr));
00299 }
00300
00301 mrpt_graph.edges_store_inverse_poses = false;
00302
00303 MRPT_END;
00304 }
00305
00306 void convert(
00307 mrpt_msgs::NetworkOfPoses& ros_graph,
00308 const mrpt::graphs::CNetworkOfPoses3DInf_NA& mrpt_graph)
00309 {
00310 THROW_EXCEPTION("Conversion not implemented yet");
00311 }
00312
00313 }