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 #include <laser_slam/odom_constraints.h>
00032
00033 namespace laser_slam
00034 {
00035
00036 namespace pg=pose_graph;
00037 namespace util=graph_mapping_utils;
00038 namespace msg=graph_mapping_msgs;
00039 namespace gm=geometry_msgs;
00040 namespace gs=graph_slam;
00041
00042 using std::string;
00043 using util::toString;
00044
00045 typedef boost::mutex::scoped_lock Lock;
00046
00047 ScanMatchConstraints::ScanMatchConstraints (ros::NodeHandle p_nh, TfPtr tf) :
00048 fixed_frame_(util::getParam<string>(p_nh, "fixed_frame")),
00049 base_frame_(util::getParam<string>(p_nh, "base_frame")),
00050 laser_frame_(util::getParam<string>(p_nh, "laser_frame")),
00051 opt_frame_(util::searchParam<string>(p_nh, "optimization_frame")),
00052 local_window_size_(util::getParam<double>(p_nh, "local_window_size", 10.0)),
00053 running_scan_match_size_(util::getParam<double>(p_nh, "running_scan_match_size", 0.3)),
00054 running_scan_match_res_(util::getParam<double>(p_nh, "running_scan_match_resolution", 0.01)),
00055 near_link_min_chain_size_(util::getParam<int>(p_nh, "near_link_min_chain_size", 8)),
00056 chain_distance_threshold_(util::getParam<double>(p_nh, "chain_distance_threshold", 2.0)),
00057 loop_scan_match_size_(util::getParam<double>(p_nh, "loop_scan_match_size", 5.0)),
00058 loop_scan_match_res_(util::getParam<double>(p_nh, "loop_scan_match_resolution", 0.05)),
00059 loop_match_window_size_(util::getParam<double>(p_nh, "loop_closure_window_size", 5.0)),
00060 loop_match_min_chain_size_(util::getParam<int>(p_nh, "loop_closure_min_chain_size", 10)),
00061 min_loop_response_(util::getParam<double>(p_nh, "min_loop_closure_response", 0.7)),
00062 max_loop_match_variance_(util::getParam<double>(p_nh, "max_loop_match_variance", 0.16)),
00063 min_sequential_response_(util::getParam<double>(p_nh, "min_sequential_response", 0.7)),
00064 max_nbd_size_(util::getParam<double>(p_nh, "scan_match_nbd_size", 20)),
00065 running_buffer_size_(util::getParam<int>(p_nh, "running_buffer_size", 50)),
00066 initialized_(false), distance_since_last_added_node_(0), running_nodes_(running_buffer_size_),
00067 tf_(tf), db_("graph_mapping"), before_(&db_, PREV_NODE_TOPIC), after_(&db_, NEXT_NODE_TOPIC),
00068 scans_(&db_, "scans"), ff_poses_(&db_, "fixed_frame_poses"),
00069 loc_buf_(LOCALIZATION_BUFFER_SIZE, fixed_frame_, base_frame_, tf, MAX_EXTRAPOLATION),
00070 diff_sub_(boost::bind(&ScanMatchConstraints::addConstraints, this, _1, _2)),
00071 loc_sub_(nh_.subscribe("graph_localization", 5, &ScanMatchConstraints::locCallback, this)),
00072 constraint_pub_(nh_.advertise<msg::GraphConstraint>("graph_constraints", 10)),
00073 marker_pub_(nh_.advertise<vm::Marker>("visualization_marker", 1)),
00074 pose_pub_(nh_.advertise<gm::PoseStamped>("opt_pose_estimate", 1)),
00075 get_poses_client_(nh_.serviceClient<msg::GetPoses>("get_node_poses")),
00076 distance_update_timer_(nh_.createTimer(ros::Duration(DISTANCE_UPDATE_INC),
00077 &ScanMatchConstraints::updateDistanceTravelled, this))
00078 {
00079 Lock l(mutex_);
00080
00081
00082 while (ros::ok()) {
00083 ros::Time t = ros::Time::now();
00084 if (tf_->waitForTransform(base_frame_, laser_frame_, t, ros::Duration(5.0))) {
00085 gm::PoseStamped id, laser_pose;
00086 id.pose.orientation.w = 1.0;
00087 id.header.stamp = t;
00088 id.header.frame_id = laser_frame_;
00089 tf_->transformPose(base_frame_, id, laser_pose);
00090 laser_offset_ = util::toPose(laser_pose.pose);
00091 break;
00092 }
00093 ROS_INFO_STREAM ("Waiting for transform between " << base_frame_ << " and " << laser_frame_);
00094 }
00095
00096 initialized_ = ros::ok();
00097 ROS_DEBUG_NAMED ("init", "Initialized scan match constraint generator");
00098 }
00099
00100 void ScanMatchConstraints::locCallback (msg::LocalizationDistribution::ConstPtr m)
00101 {
00102 Lock lock(mutex_);
00103 ROS_ASSERT (m->samples.size()==1);
00104 const gm::PoseStamped& l = m->samples[0];
00105 const unsigned ref = util::refNode(l);
00106 if (!(running_nodes_.size() > 0 && *(--running_nodes_.end()) == ref))
00107 running_nodes_.push_back(ref);
00108 const btVector3 p = fixedFramePose(ref).getOrigin();
00109 const double max_dist = running_buffer_size_ * EXPECTED_NODE_DISTANCE;
00110 while (running_nodes_.size() > 3 && p.distance(fixedFramePose(running_nodes_[0]).getOrigin()) > max_dist)
00111 running_nodes_.pop_front();
00112
00113 }
00114
00115
00116
00117 void ScanMatchConstraints::addConstraints
00118 (OptionalDiff diff, const pose_graph::ConstraintGraph& orig)
00119 {
00120
00121 pg::ConstraintGraph g = orig;
00122 ROS_ASSERT(0 < LOOP_MATCH_FINE_MULTIPLIER && LOOP_MATCH_FINE_MULTIPLIER < 1);
00123 if (diff && diff->new_nodes.size() == 1 && g.allNodes().size() > 1) {
00124
00125
00126 const unsigned n(diff->new_nodes[0].id);
00127
00128 ros::Time t;
00129 while (ros::ok()) {
00130 try
00131 {
00132 t = scans_.get(n)->scan.header.stamp;
00133 break;
00134 }
00135 catch (pg::DataNotFoundException& e)
00136 {
00137 ROS_WARN_STREAM_NAMED ("scan_match_constraints",
00138 "Not generating constraints to " << n <<
00139 " because scan " << n << " was unavailable.");
00140 ros::Duration(POLL_INC).sleep();
00141 }
00142 }
00143
00144
00145 unsigned j=0;
00146 gm::PoseStamped graph_loc;
00147 while (ros::ok()) {
00148 if (loc_buf_.hasLocalization(t)) {
00149 graph_loc = loc_buf_.localizationAt(t);
00150 break;
00151 }
00152 if (++j>5) {
00153 ROS_WARN_STREAM_NAMED ("scan_match_constraints", "Not generating constraints to " << n <<
00154 " because localization for time " << t << " unavailable.");
00155 return;
00156 }
00157 ros::Duration(POLL_INC).sleep();
00158 }
00159
00160 ROS_DEBUG_STREAM_NAMED ("scan_match_constraints", "Generating scan match constraints given new node "
00161 << n << " and ref node " << util::refNode(graph_loc));
00162 Lock l(mutex_);
00163
00164
00165 if (!sequential_matcher_) {
00166 sequential_matcher_.reset(new ksm::KartoScanMatcher(scans_.get(n)->scan, util::projectToPose2D(laser_offset_),
00167 running_scan_match_size_,
00168 running_scan_match_res_));
00169 ksm::DoubleVector resolutions, sizes;
00170 sizes.push_back(loop_scan_match_size_);
00171 resolutions.push_back(loop_scan_match_res_);
00172
00173
00174 sizes.push_back(loop_scan_match_size_*LOOP_MATCH_FINE_MULTIPLIER);
00175 resolutions.push_back(loop_scan_match_res_*LOOP_MATCH_FINE_MULTIPLIER);
00176 loop_matcher_.reset(new ksm::KartoScanMatcher(scans_.get(n)->scan, util::projectToPose2D(laser_offset_),
00177 sizes, resolutions));
00178
00179 ROS_DEBUG_NAMED ("scan_match_constraints", "Matchers initialized");
00180 }
00181 ROS_ASSERT(loop_matcher_);
00182
00183 {
00184 const unsigned ref = util::refNode(graph_loc);
00185 pg::NodeSet comp = pg::componentContaining(g, ref);
00186
00187 optimizeGraph(&g, &optimized_poses_, comp, get_poses_client_);
00188 ROS_ASSERT (!util::contains(optimized_poses_, n));
00189 }
00190
00191 pg::NodeSet running_nodes = getRunningNodes(g, n, graph_loc);
00192 ROS_DEBUG_STREAM_NAMED ("scan_match_constraints", "Running nodes are "
00193 << util::toString(running_nodes));
00194 ConstraintVec constraints = getRunningConstraints(n, g, graph_loc,
00195 running_nodes);
00196
00197
00198
00199
00200 const ConstraintVec loop_constraints = getLoopConstraints(n, g, graph_loc, running_nodes);
00201 constraints.insert(constraints.end(), loop_constraints.begin(), loop_constraints.end());
00202
00203
00204 BOOST_FOREACH (const msg::GraphConstraint& c, constraints)
00205 constraint_pub_.publish(c);
00206
00207 if (last_added_node_ && distance_since_last_added_node_ < chain_distance_threshold_)
00208 addSequenceLink(*last_added_node_, n);
00209
00210 last_added_node_ = n;
00211 distance_since_last_added_node_ = 0.0;
00212 ROS_DEBUG_NAMED ("scan_match_constraints", "Added %zu constraints",
00213 constraints.size());
00214 }
00215 }
00216
00217 pg::NodeSet ScanMatchConstraints::getRunningNodes (const pg::ConstraintGraph& g, const unsigned new_node,
00218 const gm::PoseStamped& graph_loc) const
00219 {
00220
00221 LocalizedScan::ConstPtr scan = scans_.get(new_node);
00222 const unsigned ref = util::refNode(graph_loc);
00223 const tf::Pose opt_pose_estimate = g.getOptimizedPose(ref)*util::toPose(graph_loc.pose);
00224
00225 const gm::Point barycenter = util::transformPoint(opt_pose_estimate, scan->barycenter);
00226 BarycenterDistancePredicate pred(g, scans_, barycenter, local_window_size_);
00227 const pg::NodeSet nearby = pg::filterNearbyNodes(g, ref, pred);
00228
00229 Chain chain = getChain(ref, nearby, pg::NodeSet());
00230 pg::NodeSet running(chain.begin(), chain.end());
00231 return running;
00232 }
00233
00234 tf::Pose ScanMatchConstraints::fixedFramePose (const unsigned n) const
00235 {
00236 return util::toPose(*ff_poses_.get(n));
00237 }
00238
00239 void ScanMatchConstraints::updateDistanceTravelled (const ros::TimerEvent& e)
00240 {
00241 Lock l(mutex_);
00242 const ros::Time t = ros::Time::now();
00243 const ros::Duration inc(DISTANCE_UPDATE_INC);
00244 const ros::Time prev = t - inc;
00245 util::MaybeTransform tr = util::getTransform(*tf_, base_frame_, prev,
00246 base_frame_, t, fixed_frame_,
00247 inc);
00248 if (tr)
00249 distance_since_last_added_node_ += tr->getOrigin().length();
00250 else
00251 {
00252 ROS_WARN_STREAM ("Couldn't get transform between times " << t << " and " << prev <<
00253 " in distance update.");
00254 distance_since_last_added_node_ += DISTANCE_UPDATE_INC * MAX_SPEED;
00255 }
00256 }
00257
00258 ConstraintVec ScanMatchConstraints::getNearLinkConstraints (const unsigned new_node, const pg::ConstraintGraph& g,
00259 const gm::PoseStamped& graph_loc,
00260 const pg::NodeSet& running_nodes) const
00261 {
00262 ConstraintVec constraints;
00263 LocalizedScan::ConstPtr scan = scans_.get(new_node);
00264 const unsigned ref = util::refNode(graph_loc);
00265 const tf::Pose opt_pose_estimate = g.getOptimizedPose(ref)*util::toPose(graph_loc.pose);
00266
00267 const gm::Point barycenter = util::transformPoint(opt_pose_estimate, scan->barycenter);
00268 BarycenterDistancePredicate pred(g, scans_, barycenter, local_window_size_);
00269 const pg::NodeSet nearby = pg::filterNearbyNodes(g, ref, pred);
00270
00271 pg::NodeSet processed(running_nodes.begin(), running_nodes.end());
00272
00273 BOOST_FOREACH (const unsigned n, nearby) {
00274 const Chain chain = getChain(n, nearby, processed);
00275 if (chain.size() >= near_link_min_chain_size_) {
00276 const pg::NodeSet nodes(chain.begin(), chain.end());
00277 const pg::NodeSet node_subset = util::sampleSubset(nodes, max_nbd_size_);
00278 const ksm::ScanMatchResult res =
00279 scanMatchNodes(g, sequential_matcher_, node_subset, scans_,
00280 scan->scan, opt_pose_estimate, laser_offset_);
00281 if (res.response > min_sequential_response_) {
00282 const msg::GraphConstraint constraint = makeConstraint(g, new_node, res, nodes, scan);
00283 constraints.push_back(constraint);
00284 ROS_DEBUG_STREAM_NAMED ("scan_match_constraints", "Adding near chain constraint to " << constraint.src);
00285 }
00286 processed.insert(chain.begin(), chain.end());
00287 }
00288 }
00289 return constraints;
00290 }
00291
00292 ConstraintVec ScanMatchConstraints::getLoopConstraints (const unsigned n, const pg::ConstraintGraph& g,
00293 const gm::PoseStamped& graph_loc,
00294 const pg::NodeSet& running) const
00295 {
00296 ConstraintVec constraints;
00297 LocalizedScan::ConstPtr scan = scans_.get(n);
00298 const unsigned ref = util::refNode(graph_loc);
00299 const tf::Pose opt_pose_estimate = g.getOptimizedPose(ref)*util::toPose(graph_loc.pose);
00300
00301 const gm::Point barycenter = util::transformPoint(opt_pose_estimate, scan->barycenter);
00302 BarycenterDistancePredicate pred(g, scans_, barycenter, loop_match_window_size_);
00303 typedef boost::filtered_graph<pg::Graph, pg::AllEdges, BarycenterDistancePredicate> FilteredGraph;
00304 const FilteredGraph filtered(g.graph(), pg::AllEdges(), pred);
00305
00306
00307
00308
00309 typedef std::map<pg::GraphVertex, boost::default_color_type> ColorMap;
00310 ColorMap cmap;
00311 boost::associative_property_map<ColorMap> color_pmap(cmap);
00312
00313
00314 typedef std::map<pg::GraphVertex, unsigned> ComponentMap;
00315 ComponentMap comp_map;
00316 boost::associative_property_map<ComponentMap> comp_pmap(comp_map);
00317
00318
00319 const unsigned num_comps = connected_components(filtered, comp_pmap, color_map(color_pmap));
00320 std::vector<pg::NodeSet> comps(num_comps);
00321 BOOST_FOREACH (const ComponentMap::value_type& e, comp_map) {
00322 comps[e.second].insert(filtered[e.first].id);
00323 }
00324
00325
00326
00327 std::set<unsigned> not_loop_matchable;
00328 {
00329 ComponentMap::const_iterator pos = comp_map.find(g.idVertex(n));
00330 if (pos!=comp_map.end())
00331 not_loop_matchable.insert(pos->second);
00332 BOOST_FOREACH (const unsigned running_node, running) {
00333 pos = comp_map.find(g.idVertex(running_node));
00334 if (pos!=comp_map.end())
00335 not_loop_matchable.insert(pos->second);
00336 }
00337 }
00338
00339 ROS_DEBUG_STREAM_COND_NAMED
00340 (num_comps>1, "loop_closure", "There were " << num_comps <<
00341 " components, with nonmatchable components " <<
00342 util::toString(not_loop_matchable));
00343
00344
00345
00346 for (unsigned comp=0; comp<num_comps; comp++)
00347 {
00348 if (util::contains(not_loop_matchable, comp))
00349 continue;
00350 if (comps[comp].size() < (unsigned)loop_match_min_chain_size_)
00351 {
00352 ROS_DEBUG_STREAM_NAMED ("loop_closure", "Skipping component of size "
00353 << util::toString(comps[comp]));
00354 continue;
00355 }
00356 const pg::NodeSet node_subset =
00357 util::sampleSubset(comps[comp], max_nbd_size_);
00358 ksm::ScanMatchResult res =
00359 scanMatchNodes(g, loop_matcher_, node_subset, scans_, scan->scan,
00360 opt_pose_estimate, laser_offset_);
00361 ROS_DEBUG_STREAM_NAMED ("loop_closure", "Potential loop match " << comp
00362 << " of size " << loop_match_min_chain_size_ <<
00363 " has response " << res.response <<
00364 " and covariances " << res.cov(0,0) << ", " <<
00365 res.cov(1,1));
00366 if (res.response > min_loop_response_ &&
00367 res.cov(0,0) < max_loop_match_variance_ &&
00368 res.cov(1,1) < max_loop_match_variance_) {
00369 ROS_DEBUG_STREAM_NAMED ("loop_closure",
00370 "Adding loop constraint to component " << comp);
00371 constraints.push_back(makeConstraint(g, n, res, comps[comp], scan));
00372 }
00373 }
00374 return constraints;
00375 }
00376
00377 ConstraintVec ScanMatchConstraints::getRunningConstraints
00378 (const unsigned n, const pg::ConstraintGraph& g,
00379 const gm::PoseStamped& graph_loc, const pg::NodeSet& running) const
00380 {
00381 ConstraintVec constraints;
00382 const unsigned ref = util::refNode(graph_loc);
00383 LocalizedScan::ConstPtr scan = scans_.get(n);
00384
00385
00386
00387 const tf::Pose opt_pose_estimate =
00388 g.getOptimizedPose(ref)*util::toPose(graph_loc.pose);
00389
00390
00391 const pg::NodeSet nodes = util::sampleSubset(running, max_nbd_size_);
00392 ksm::ScanMatchResult res =
00393 scanMatchNodes(g, sequential_matcher_, nodes, scans_, scan->scan,
00394 opt_pose_estimate, laser_offset_);
00395
00396
00397 const msg::GraphConstraint running_constraint = makeConstraint(g, n, res,
00398 running, scan);
00399 constraints.push_back(running_constraint);
00400 ROS_DEBUG_STREAM_NAMED ("scan_match_constraints", "Added running constraint "
00401 "to " << running_constraint.src);
00402
00403
00404 if (last_added_node_ &&
00405 distance_since_last_added_node_ < chain_distance_threshold_*0.5 &&
00406 constraints[0].src != *last_added_node_ &&
00407 g.hasOptimizedPose(*last_added_node_)) {
00408 const tf::Pose last_pose = g.getOptimizedPose(*last_added_node_);
00409 if (last_pose.getOrigin().distance(opt_pose_estimate.getOrigin()) <
00410 local_window_size_) {
00411 constraints.push_back(makeConstraint(g, n, *last_added_node_, res, scan));
00412 ROS_DEBUG_STREAM_NAMED ("scan_match_constraints", "Also adding constraint"
00413 " to last added node " << *last_added_node_);
00414 }
00415 }
00416 return constraints;
00417 }
00418
00419
00420
00421
00422 msg::GraphConstraint ScanMatchConstraints::makeConstraint (const pg::ConstraintGraph& g, const unsigned n,
00423 const ksm::ScanMatchResult& res, const pg::NodeSet& nodes,
00424 LocalizedScan::ConstPtr scan) const
00425 {
00426 const tf::Pose base_pose = util::toPose(res.pose);
00427 const gm::Point new_barycenter = util::transformPoint(base_pose, scans_.get(n)->barycenter);
00428 const unsigned closest = nodeWithNearestBarycenter(g, nodes, new_barycenter);
00429
00430
00431
00432 return makeConstraint(g, n, closest, res, scan);
00433 }
00434
00435
00436 msg::GraphConstraint ScanMatchConstraints::makeConstraint (const pg::ConstraintGraph& g, const unsigned n,
00437 const unsigned ref, const ksm::ScanMatchResult& res,
00438 LocalizedScan::ConstPtr scan) const
00439 {
00440 const tf::Pose base_pose = util::toPose(res.pose);
00441
00442
00443
00444 const tf::Pose node_in_laser_frame = util::toPose(scan->sensor_pose).inverse();
00445 const tf::Pose node_pose = base_pose*laser_offset_*node_in_laser_frame;
00446
00447 msg::GraphConstraint constraint;
00448 constraint.src = ref;
00449 constraint.dest = n;
00450 constraint.constraint.pose = util::toPose(util::relativePose(node_pose, g.getOptimizedPose(ref)));
00451
00453 const Eigen::Matrix3f prec2D = res.cov.inverse();
00454 constraint.constraint.precision = util::makePrecisionMatrix(prec2D(0,0), prec2D(1,1), prec2D(0,1), prec2D(2,2));
00455
00456 return constraint;
00457 }
00458
00459
00460
00461 unsigned ScanMatchConstraints::nodeWithNearestBarycenter (const pg::ConstraintGraph& g,
00462 const pg::NodeSet& nodes, const gm::Point& p) const
00463 {
00464 boost::optional<unsigned> closest;
00465 double dist = -42.42;
00466 BOOST_FOREACH (const unsigned n2, nodes) {
00467 const tf::Pose node_pose = g.getOptimizedPose(n2);
00468 const gm::Point& b = util::transformPoint(node_pose, scans_.get(n2)->barycenter);
00469 const double dx=b.x-p.x;
00470 const double dy=b.y-p.y;
00471 const double new_dist = dx*dx + dy*dy;
00472 if (!closest || new_dist < dist) {
00473 dist = new_dist;
00474 closest = n2;
00475 }
00476 }
00477 ROS_ASSERT(closest);
00478 return *closest;
00479 }
00480
00481
00482
00483
00484
00485
00486
00487
00488
00489 MaybeNode ScanMatchConstraints::previousNode (const unsigned n) const
00490 {
00491 MaybeNode prev;
00492 if (before_.hasData(n))
00493 prev = before_.get(n)->data;
00494 return prev;
00495 }
00496
00497 MaybeNode ScanMatchConstraints::nextNode (const unsigned n) const
00498 {
00499 MaybeNode next;
00500 if (after_.hasData(n))
00501 next = after_.get(n)->data;
00502 return next;
00503 }
00504
00505 void ScanMatchConstraints::addSequenceLink (const unsigned n1, const unsigned n2)
00506 {
00507 std_msgs::UInt64 m1, m2;
00508 m1.data = n1;
00509 m2.data = n2;
00510 before_.set(n2, m1);
00511 after_.set(n1, m2);
00512 ROS_DEBUG_STREAM_NAMED ("scan_chain_constraints", "Adding sequence link from " << n1 << " to " << n2);
00513 }
00514
00515 Chain ScanMatchConstraints::getChain (const unsigned n, const pg::NodeSet& nodes,
00516 const pg::NodeSet& forbidden) const
00517 {
00518 using util::contains;
00519 if (contains(forbidden, n) || !contains(nodes, n))
00520 return Chain();
00521
00522 Chain before, after;
00523 {
00524 unsigned current = n;
00525 while (true) {
00526 MaybeNode prev = previousNode(current);
00527 if (prev && contains(nodes, *prev) && !contains(forbidden, *prev)) {
00528 before.push_back(*prev);
00529 current = *prev;
00530 }
00531 else
00532 break;
00533 }
00534 }
00535
00536 {
00537 unsigned current = n;
00538 while (true) {
00539 MaybeNode next = nextNode(current);
00540 if (next && contains(nodes, *next) && !contains(forbidden, *next)) {
00541 after.push_back(*next);
00542 current = *next;
00543 }
00544 else
00545 break;
00546 }
00547 }
00548
00549 Chain chain(before.size() + after.size() + 1);
00550 copy(before.rbegin(), before.rend(), chain.begin());
00551 chain[before.size()] = n;
00552 copy(after.begin(), after.end(), chain.begin() + (before.size() + 1));
00553 return chain;
00554 }
00555
00556
00557 }
00558
00559
00560
00561
00562
00563