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 LASER_SLAM_UTIL_H
00040 #define LASER_SLAM_UTIL_H
00041
00042 #include <graph_mapping_msgs/ConstraintGraphDiff.h>
00043 #include <graph_mapping_msgs/GetPoses.h>
00044 #include <graph_mapping_utils/geometry.h>
00045 #include <laser_slam/LocalizedScan.h>
00046 #include <pose_graph/diff_subscriber.h>
00047 #include <pose_graph/graph_db.h>
00048 #include <tf/transform_listener.h>
00049 #include <ros/ros.h>
00050 #include <boost/optional.hpp>
00051
00052 namespace laser_slam
00053 {
00054
00055 namespace pg=pose_graph;
00056 namespace msg=graph_mapping_msgs;
00057 namespace gm=geometry_msgs;
00058 namespace util=graph_mapping_utils;
00059
00060 pg::NodeSet largestComp (const pg::ConstraintGraph& g);
00061
00062 typedef boost::shared_ptr<tf::TransformListener> TfPtr;
00063 typedef boost::optional<const msg::ConstraintGraphDiff&> OptionalDiff;
00064 typedef pose_graph::CachedNodeMap<LocalizedScan> ScanMap;
00065
00066 void optimizeGraph (pg::ConstraintGraph* g, pg::NodePoseMap* poses,
00067 const pg::NodeSet& nodes, ros::ServiceClient& srv);
00068
00069
00070 struct BarycenterDistancePredicate
00071 {
00072 BarycenterDistancePredicate (const pg::ConstraintGraph& g,
00073 const ScanMap& scans, const gm::Point p, const double max_dist) :
00074 g(&g), scans(&scans), p(&p), max_dist(max_dist)
00075 { }
00076
00077 BarycenterDistancePredicate () : g(NULL), scans(NULL), p(NULL), max_dist(-42.42) {}
00078
00079 bool operator() (const pg::GraphVertex v) const
00080 {
00081 const unsigned n(g->graph()[v].id);
00082 if (!g->hasOptimizedPose(n)) {
00083 return false;
00084 }
00085
00086
00087
00088
00089
00090 else {
00091 try {
00092 const tf::Pose node_pose = g->getOptimizedPose(n);
00093 LocalizedScan::ConstPtr scan = scans->get(n);
00094 const gm::Point b = util::transformPoint(node_pose, scan->barycenter);
00095 return (util::euclideanDistance(*p, b) < max_dist);
00096 }
00097 catch (pg::DataNotFoundException& e) {
00098 ROS_INFO_STREAM("Didn't have scan for " << n);
00099 return false;
00100 }
00101 }
00102 }
00103
00104 const pg::ConstraintGraph* g;
00105 const ScanMap* scans;
00106 const gm::Point* p;
00107 double max_dist;
00108 };
00109
00110 }
00111
00112 #endif // include guard