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
00042 #include <laser_slam/point_cloud_snapshotter.h>
00043 #include <laser_slam/scan_intersection.h>
00044 #include <pose_graph/exception.h>
00045 #include <graph_slam/graph_mapper.h>
00046 #include <graph_mapping_utils/ros.h>
00047 #include <graph_mapping_utils/geometry.h>
00048 #include <graph_mapping_utils/msg.h>
00049 #include <graph_mapping_utils/to_string.h>
00050 #include <pose_graph/graph_search.h>
00051 #include <tf/transform_broadcaster.h>
00052 #include <boost/thread.hpp>
00053
00054 namespace laser_slam
00055 {
00056
00057 namespace msg=graph_mapping_msgs;
00058 namespace pg=pose_graph;
00059 namespace util=graph_mapping_utils;
00060 namespace gm=geometry_msgs;
00061
00062 using std::vector;
00063
00064 typedef boost::optional<ros::Time> MaybeTime;
00065 typedef boost::optional<gm::PoseStamped> MaybeLoc;
00066
00067 const double SCAN_TIME_INC = 0.2;
00068
00069 class LaserMapper : public graph_slam::GraphMapper
00070 {
00071 public:
00072
00073 LaserMapper ();
00074 ~LaserMapper() {}
00075
00076
00077
00078 virtual MaybeTime newNodeTime ();
00079
00080 private:
00081
00082 bool relativelyUnseen (const ros::Time t) const;
00083
00084 ros::NodeHandle nh_, param_nh_;
00085
00086 const double min_unseen_proportion_;
00087
00088 ros::ServiceClient recent_time_client_;
00089 ScanIntersection scan_int_;
00090
00091 };
00092
00093
00094 ScanIntersection makeScanInt ()
00095 {
00096 vector<btVector3> poly(4);
00097 poly[1].setX(1);
00098 poly[1].setY(5);
00099 poly[2].setX(8);
00100 poly[3].setX(1);
00101 poly[3].setY(-5);
00102 return ScanIntersection(poly, 1000);
00103 }
00104
00105
00106 LaserMapper::LaserMapper() :
00107 GraphMapper(), param_nh_("~"),
00108 min_unseen_proportion_(util::getParam<double>(param_nh_,
00109 "min_unseen_proportion", 0.2)),
00110 recent_time_client_(nh_.serviceClient<RecentScanTime>("recent_scan_time")),
00111 scan_int_(makeScanInt())
00112 {
00113 }
00114
00115
00116 bool LaserMapper::relativelyUnseen (const ros::Time t) const
00117 {
00118 MaybeLoc l = localizations_.lastLocalization();
00119 if (l)
00120 {
00121 try {
00122 const unsigned ref = util::refNode(*l);
00123 const tf::Pose ref_pose = graph_.getOptimizedPose(ref);
00124 const tf::Pose opt_pose = util::absolutePose(ref_pose, l->pose);
00125 pg::OptimizedDistancePredicate pred(graph_, opt_pose.getOrigin(),
00126 5.0);
00127 pg::NodeSet nodes = filterNearbyNodes(graph_, ref, pred);
00128 vector<tf::Pose> scan_poses;
00129 scan_poses.reserve(nodes.size());
00130 BOOST_FOREACH (const unsigned n, nodes)
00131 scan_poses.push_back(graph_.getOptimizedPose(n));
00132 const double prop = scan_int_.unseenProportion(opt_pose, scan_poses);
00133
00134 ROS_DEBUG_STREAM_NAMED ("add_node", "Proportion of scan that was unseen was " << prop);
00135 return prop > min_unseen_proportion_;
00136 }
00137 catch (pg::NoOptimizedPoseException& e)
00138 {
00139 ROS_INFO_STREAM ("Not adding node because of exception: " << e.what());
00140 return false;
00141 }
00142 }
00143 else
00144 {
00145 ROS_INFO ("Not checking scan unseen-ness because have no localization");
00146 return true;
00147 }
00148 }
00149
00150
00151 MaybeTime LaserMapper::newNodeTime ()
00152 {
00153 MaybeTime t;
00154 RecentScanTime srv;
00155 const ros::Time now = ros::Time::now();
00156 srv.request.t1 = now-ros::Duration(SCAN_TIME_INC);
00157 srv.request.t2 = now;
00158 if (recent_time_client_.call(srv))
00159 {
00160 if (srv.response.found && relativelyUnseen(srv.response.t))
00161 t = srv.response.t;
00162 }
00163 else
00164 ROS_ERROR ("Service call to recent_scan_time failed. Not saving a scan.");
00165 return t;
00166 }
00167
00168
00169 }
00170
00171
00172 int main (int argc, char** argv)
00173 {
00174 ros::init(argc, argv, "laser_slam_node");
00175
00176
00177 ros::AsyncSpinner spinner(3);
00178 spinner.start();
00179
00180
00181 laser_slam::LaserMapper node;
00182 ros::spin();
00183 return 0;
00184 }