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_POSE_GRAPH_H
00043 #define POSE_GRAPH_POSE_GRAPH_H
00044
00045 #include "geometry.h"
00046 #include "ids.h"
00047 #include <occupancy_grid_utils/LocalizedCloud.h>
00048 #include <boost/scoped_ptr.hpp>
00049 #include <boost/optional.hpp>
00050 #include <set>
00051 #include <vector>
00052
00053 namespace pose_graph {
00054
00055
00056
00057
00058
00060 struct ShortestPathResult
00061 {
00063 bool path_found;
00064
00066 std::vector<NodeId> nodes;
00067
00069 std::vector<EdgeId> edges;
00070
00072 double cost;
00073 };
00074
00076 typedef std::map<NodeId, geometry_msgs::Pose> NodePoseMap;
00077
00079 const std::string OPTIMIZED_FRAME("graph_optimization");
00080
00081
00082
00083
00084
00085
00086
00087 class PoseGraphImpl;
00088
00089 class PoseGraph
00090 {
00091 public:
00092
00093
00094
00095
00096
00097
00099 PoseGraph ();
00100
00102 PoseGraph (const PoseGraph& g);
00103
00105 PoseGraph& operator= (const PoseGraph& g);
00106
00108 ~PoseGraph();
00109
00110
00111
00112
00113
00114
00118 NodeId addNode ();
00119
00123 void addNode (NodeId id);
00124
00131 EdgeId addEdge (NodeId from, NodeId to, const PoseConstraint& constraint);
00132
00140 void addEdge (NodeId from, NodeId to, const PoseConstraint& constraint, EdgeId id);
00141
00144 void setInitialPoseEstimate (NodeId n, const geometry_msgs::Pose& pose);
00145
00149 const geometry_msgs::Pose& getInitialPoseEstimate (NodeId n) const;
00150
00151
00152
00153
00154
00155
00157 std::set<NodeId> allNodes() const;
00158
00160 std::set<EdgeId> allEdges() const;
00161
00165 const PoseConstraint& getConstraint (EdgeId id) const;
00166
00169 double edgeLength (EdgeId id) const;
00170
00173 std::set<EdgeId> incidentEdges (NodeId n) const;
00174
00177 std::pair<NodeId, NodeId> incidentNodes (EdgeId e) const;
00178
00181 std::set<NodeId> neighbors (NodeId n) const;
00182
00184 bool nodeIdExists (NodeId id) const;
00185
00187 bool edgeIdExists (EdgeId id) const;
00188
00194 PoseGraph subgraph (const std::set<NodeId>& nodes) const;
00195
00201 geometry_msgs::Pose relativePose (NodeId n, NodeId ref) const;
00202
00205 NodeId otherNode (const NodeId n, const EdgeId e) const;
00206
00207
00208
00209
00210
00211
00216 ShortestPathResult shortestPath(NodeId src, NodeId dest) const;
00217
00223 std::set<NodeId> nearbyNodes (NodeId src, double radius) const;
00224
00225
00226
00227
00228
00229
00233 void attachCloud (NodeId id, occupancy_grid_utils::LocalizedCloud::ConstPtr cloud);
00234
00239 occupancy_grid_utils::LocalizedCloud::ConstPtr getCloud (NodeId id) const;
00240
00243 bool hasCloud (NodeId id) const;
00244
00253 void attachScan (NodeId id, sensor_msgs::LaserScan::ConstPtr cloud);
00254
00261 sensor_msgs::LaserScan::ConstPtr getScan (NodeId id) const;
00262
00265 bool hasScan (NodeId id) const;
00266
00268 static std::string nodeFrameName (const NodeId id);
00269
00270 private:
00271
00272 boost::scoped_ptr<PoseGraphImpl> impl_;
00273
00274 };
00275
00276
00277 }
00278
00279
00280 #endif // POSE_GRAPH_POSE_GRAPH_H