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 #include <topological_map_2d/ros_conversion.h>
00040 #include <pose_graph/constraint_graph.h>
00041 #include <pose_graph/diff_subscriber.h>
00042 #include <pose_graph/graph_db.h>
00043 #include <topological_nav_msgs/SwitchGrid.h>
00044 #include <pose_graph/graph_search.h>
00045 #include <laser_slam/LocalizedScan.h>
00046 #include <graph_mapping_utils/utils.h>
00047 #include <graph_mapping_msgs/LocalizationDistribution.h>
00048 #include <graph_mapping_msgs/GetPoses.h>
00049 #include <occupancy_grid_utils/ray_tracer.h>
00050 #include <tf/transform_listener.h>
00051 #include <tf/transform_broadcaster.h>
00052 #include <warehouse/warehouse_client.h>
00053 #include <visualization_msgs/Marker.h>
00054 #include <nav_msgs/OccupancyGrid.h>
00055
00056
00057 namespace laser_slam_mapper
00058 {
00059
00060 namespace wh=warehouse;
00061 namespace pg=pose_graph;
00062 namespace gmu=graph_mapping_utils;
00063 namespace gmm=graph_mapping_msgs;
00064 namespace vm=visualization_msgs;
00065 namespace nm=nav_msgs;
00066 namespace tmap=topological_map_2d;
00067 namespace ls=laser_slam;
00068 namespace gu=occupancy_grid_utils;
00069 namespace gm=geometry_msgs;
00070 namespace msg=topological_nav_msgs;
00071
00072 using std::map;
00073 using std::set;
00074 using std::string;
00075 using std::pair;
00076 using std::vector;
00077
00078 using gmu::toString;
00079
00080 typedef boost::optional<const gmm::ConstraintGraphDiff&> OptionalDiff;
00081 typedef boost::mutex::scoped_lock Lock;
00082 typedef map<unsigned, tf::Pose> NodePoses;
00083 typedef set<unsigned> Nodes;
00084 typedef set<unsigned> Grids;
00085 typedef map<unsigned, unsigned> NodeGridMap;
00086 typedef vector<string> StringVec;
00087
00088
00089
00090
00091
00092 class Mapper
00093 {
00094 public:
00095
00097 Mapper ();
00098
00099 private:
00100
00101
00102
00103
00104
00106 void updateLoop (const ros::TimerEvent& e);
00107
00109 void visualize (const ros::TimerEvent& e);
00110
00112 void diffCB (OptionalDiff diff, const pg::ConstraintGraph& g);
00113
00115 void locCB (const gmm::LocalizationDistribution& dist);
00116
00118 void publishRefTransforms(const ros::TimerEvent& e);
00119
00121 bool switchGrid (msg::SwitchGrid::Request& req,
00122 msg::SwitchGrid::Response& resp);
00123
00124
00125
00126
00127
00129 void ensureNodeCovered (unsigned n);
00130
00132 void addGrid (unsigned n);
00133
00135 void saveGrid (unsigned g);
00136
00140 void updateEdgeInfo (unsigned g, unsigned g2);
00141
00144 void updateEdgeInfo (unsigned g);
00145
00146
00147
00148
00149
00150
00152 tf::Pose poseOnGrid (unsigned n, unsigned g) const;
00153
00155 NodePoses optimizePoses (const pg::NodeSet& comp) const;
00156
00159 unsigned coveredBy (unsigned n, unsigned g, double r) const;
00160
00163 unsigned coveredBy (unsigned n, const Grids& g, double r) const;
00164
00166 nm::OccupancyGrid::ConstPtr computeLocalGrid (unsigned g) const;
00167
00169 Nodes nodesOnGrid (unsigned g) const;
00170
00173 Nodes overlayingNodes (unsigned g) const;
00174
00176 tf::Pose nodeGridTransform (unsigned n, unsigned g) const;
00177
00179 Nodes topologicallyCloseNodes (unsigned g, const double r) const;
00180
00183 Grids currentRelevantGrids () const;
00184
00185
00186
00187
00188
00189
00190
00192 void publishGraph ();
00193
00194
00195 void saveCurrentGrid ();
00196
00198 void visualizeGridBoundaries ();
00199
00201 void visualizeCurrentGrid ();
00202
00204 void visualizeEdges ();
00205
00206
00207
00208
00209
00210
00211
00212 ros::NodeHandle param_nh_;
00213
00214
00215 const double grid_size_;
00216
00217
00218
00219 const double grid_overlap_;
00220
00221
00222 const double resolution_;
00223
00224
00225 const string ref_frame_;
00226
00227
00228 const double update_rate_;
00229
00230
00231 const double robot_radius_;
00232
00233
00234
00235
00236
00237
00238 pg::ConstraintGraph pose_graph_;
00239
00240
00241 tmap::TopologicalMap tmap_;
00242
00243
00244 bool update_flag_;
00245
00246
00247 boost::optional<gm::PoseStamped> last_loc_;
00248
00249
00250 NodePoses opt_poses_;
00251
00252
00253 Nodes pending_nodes_;
00254
00255
00256 Nodes grid_nodes_;
00257
00258
00259 boost::optional<unsigned> current_grid_;
00260
00261
00262 NodeGridMap covering_grids_;
00263
00264
00265 unsigned next_edge_id_;
00266
00267
00268 ros::Time last_diff_time_;
00269
00270
00271 map<unsigned, ros::Time> grid_save_times_;
00272
00273
00274
00275
00276
00277
00278
00279 mutable boost::mutex mutex_;
00280
00281
00282 ros::NodeHandle nh_;
00283
00284
00285 tf::TransformListener tf_;
00286
00287
00288 tf::TransformBroadcaster tfb_;
00289
00290
00291 wh::WarehouseClient slam_db_;
00292
00293
00294 wh::WarehouseClient topo_db_;
00295
00296
00297 pg::CachedNodeMap<ls::LocalizedScan> scans_;
00298
00299
00300 wh::Collection<nm::OccupancyGrid> grids_;
00301
00302
00303 ros::Subscriber loc_sub_;
00304
00305
00306 pg::DiffSubscriber diff_sub_;
00307
00308
00309 ros::Publisher marker_pub_;
00310
00311
00312 ros::Publisher grid_pub_;
00313
00314
00315 ros::Publisher graph_pub_;
00316
00317
00318 ros::Publisher loc_pub_;
00319
00320
00321 ros::ServiceServer switch_grid_srv_;
00322
00323
00324
00325 mutable ros::ServiceClient get_poses_client_;
00326
00327
00328 ros::Timer update_timer_;
00329
00330
00331 ros::Timer vis_timer_;
00332
00333
00334 ros::Timer transform_pub_timer_;
00335
00336
00337 };
00338
00339
00340
00341
00342
00343
00344 StringVec gridMetadata ()
00345 {
00346 StringVec fields;
00347 fields.push_back("id");
00348 return fields;
00349 }
00350
00351 Mapper::Mapper () :
00352
00353 param_nh_("~"),
00354 grid_size_(gmu::getParam(param_nh_, "grid_size", 15.0)),
00355 grid_overlap_(gmu::getParam(param_nh_, "grid_overlap", 0.5)),
00356 resolution_(gmu::getParam(param_nh_, "resolution", 0.025)),
00357 ref_frame_(gmu::getParam<string>(param_nh_, "reference_frame")),
00358 update_rate_(gmu::getParam<double>(param_nh_, "update_rate", 0.4)),
00359 robot_radius_(gmu::getParam<double>(param_nh_, "robot_radius", -1)),
00360
00361
00362 update_flag_(true), next_edge_id_(1),
00363
00364
00365 slam_db_("graph_mapping"), topo_db_("topological_navigation"),
00366 scans_(&slam_db_, "scans"),
00367 grids_(topo_db_.setupCollection<nm::OccupancyGrid>("grids", StringVec(),
00368 gridMetadata())),
00369 loc_sub_(nh_.subscribe("graph_localization", 5, &Mapper::locCB, this)),
00370 diff_sub_(boost::bind(&Mapper::diffCB, this, _1, _2)),
00371 marker_pub_(nh_.advertise<vm::Marker>("visualization_marker", 5)),
00372 grid_pub_(nh_.advertise<nm::OccupancyGrid>("local_grid", 5)),
00373 graph_pub_(nh_.advertise<msg::TopologicalGraph>("topological_graph", 3)),
00374 loc_pub_(nh_.advertise<gm::PoseStamped>("topological_localization", 5)),
00375 switch_grid_srv_(nh_.advertiseService("switch_local_grid",
00376 &Mapper::switchGrid, this)),
00377 get_poses_client_(nh_.serviceClient<gmm::GetPoses>("get_node_poses")),
00378 update_timer_(nh_.createTimer(gmu::duration(update_rate_),
00379 &Mapper::updateLoop, this)),
00380 vis_timer_(nh_.createTimer(ros::Duration(2.0), &Mapper::visualize, this)),
00381 transform_pub_timer_(nh_.createTimer(ros::Duration(0.1),
00382 &Mapper::publishRefTransforms, this))
00383 {
00384 ROS_DEBUG_STREAM_NAMED ("init", "Mapper initialization complete");\
00385 }
00386
00387
00388
00389
00390
00391
00392
00393
00394 NodePoses Mapper::optimizePoses (const pg::NodeSet& comp) const
00395 {
00396 gmm::GetPoses srv;
00397 BOOST_FOREACH (const unsigned n, comp)
00398 srv.request.nodes.push_back(n);
00399 if (!get_poses_client_.call(srv))
00400 throw std::runtime_error("Service call to optimizer failed");
00401 NodePoses poses;
00402 unsigned i=0;
00403 BOOST_FOREACH (const unsigned n, srv.request.nodes)
00404 poses[n] = gmu::toPose(srv.response.poses[i++]);
00405 return poses;
00406 }
00407
00408 void Mapper::updateLoop (const ros::TimerEvent& e)
00409 {
00410 pg::NodeSet comp;
00411 pg::NodePoseMap opt_poses;
00412 {
00413 Lock l(mutex_);
00414
00415
00416 if (!last_loc_)
00417 {
00418 ROS_INFO_THROTTLE (5.0, "Topological mapper waiting for "
00419 "initial localization");
00420 return;
00421 }
00422
00423
00424 comp = pg::componentContaining(pose_graph_, gmu::refNode(*last_loc_));
00425 }
00426 opt_poses = optimizePoses(comp);
00427
00428 Lock l(mutex_);
00429 opt_poses_ = opt_poses;
00430 pose_graph_.setOptimizedPoses(opt_poses_);
00431
00432 BOOST_FOREACH (const unsigned n, pending_nodes_)
00433 {
00434 if (!gmu::contains(opt_poses_, n))
00435 {
00436 ROS_DEBUG_STREAM_NAMED ("update_int", "No optimized pose yet for " <<
00437 n << "; skipping it.");
00438 continue;
00439 }
00440 ROS_DEBUG_STREAM_NAMED ("update_int", "Processing pending node " << n);
00441
00442 const double r = 1-grid_overlap_;
00443 if (!(current_grid_ && coveredBy(n, *current_grid_, r)) &&
00444 !coveredBy(n, grid_nodes_, r))
00445 {
00446 addGrid(n);
00447 updateEdgeInfo(n);
00448 saveGrid(n);
00449 covering_grids_[n] = n;
00450 }
00451 else
00452 {
00453 covering_grids_[n] = coveredBy(n, grid_nodes_, r);
00454 }
00455 }
00456 pending_nodes_.clear();
00457
00458
00459 BOOST_FOREACH (const unsigned g, currentRelevantGrids())
00460 updateEdgeInfo (g);
00461
00462
00463
00464 publishGraph();
00465 saveCurrentGrid();
00466
00467
00468 }
00469
00470 unsigned Mapper::coveredBy (const unsigned n, const unsigned g,
00471 const double r) const
00472 {
00473 const tf::Pose& center = gmu::keyValue(opt_poses_, g);
00474 const tf::Pose& pose = gmu::keyValue(opt_poses_, n);
00475 const tf::Pose rel_pose = gmu::relativePose(pose, center);
00476 const double d = grid_size_*r*0.5;
00477 const double rx = rel_pose.getOrigin().x();
00478 const double ry = rel_pose.getOrigin().y();
00479 return (fabs(rx)<d && fabs(ry)<d) ? g : 0;
00480 }
00481
00482
00483 unsigned Mapper::coveredBy (const unsigned n, const set<unsigned>& grids,
00484 const double r) const
00485 {
00486 BOOST_FOREACH (const unsigned g, grids)
00487 {
00488 if (coveredBy(n, g, r))
00489 return g;
00490 }
00491 return 0;
00492 }
00493
00494 void Mapper::addGrid (const unsigned n)
00495 {
00496 ROS_DEBUG_STREAM_NAMED ("update", "Adding grid centered at node " << n);
00497 grid_nodes_.insert(n);
00498 msg::TopologicalMapNode info;
00499 info.id = n;
00500 info.y_size = grid_size_;
00501 info.x_size = grid_size_;
00502 info.resolution = resolution_;
00503 tmap_.addNode(info);
00504 }
00505
00506
00507 void Mapper::updateEdgeInfo (const unsigned g, const unsigned g2)
00508 {
00509 if (g!=g2 && gmu::contains(grid_nodes_, g2))
00510 {
00511 ROS_DEBUG_NAMED ("update_int", "Processing nearby nodes %u and %u",
00512 g, g2);
00513
00514 pair<tmap::GraphEdge, bool> res =
00515 edge(tmap_.node(g), tmap_.node(g2), tmap_);
00516 if (res.second)
00517 {
00518
00519
00520 msg::TopologicalMapEdge& info = tmap_[res.first];
00521 const tf::Pose dest = gmu::keyValue(opt_poses_, info.dest);
00522 const tf::Pose src = gmu::keyValue(opt_poses_, info.src);
00523 tmap_.edgeInfo(tmap_[res.first].id).offset =
00524 gmu::toPose(gmu::relativePose(dest, src));
00525 }
00526 else
00527 {
00528
00529 const tf::Pose dest = gmu::keyValue(opt_poses_, g2);
00530 const tf::Pose src = gmu::keyValue(opt_poses_, g);
00531 const double d2 = dest.getOrigin().distance2(src.getOrigin());
00532 if (d2 < 2*grid_size_*grid_size_)
00533 {
00534 msg::TopologicalMapEdge e;
00535 e.id = next_edge_id_++;
00536 e.src = g;
00537 e.dest = g2;
00538 e.offset = gmu::toPose(gmu::relativePose(dest, src));
00539 tmap_.addEdge(e);
00540 ROS_DEBUG_NAMED("update", "Adding edge from %u to %u", g, g2);
00541 }
00542 }
00543 }
00544 }
00545
00546 void Mapper::updateEdgeInfo (const unsigned g)
00547 {
00548 ROS_DEBUG_NAMED ("update_int", "Updating edge info for %u", g);
00549 BOOST_FOREACH (const unsigned n,
00550 topologicallyCloseNodes(g, grid_size_*1.5))
00551 {
00552 updateEdgeInfo(g, n);
00553 }
00554 }
00555
00556
00557 Nodes Mapper::topologicallyCloseNodes (const unsigned g, const double r) const
00558 {
00559 const btVector3 pos = gmu::keyValue(opt_poses_, g).getOrigin();
00560 pg::OptimizedDistancePredicate pred(pose_graph_, pos, r);
00561 return filterNearbyNodes (pose_graph_, g, pred);
00562 }
00563
00564 Grids Mapper::currentRelevantGrids () const
00565 {
00566 Grids grids;
00567 if (current_grid_)
00568 grids.insert(*current_grid_);
00569 return grids;
00570 }
00571
00572
00573
00574
00575
00576
00577
00578
00579
00580 void Mapper::locCB (const gmm::LocalizationDistribution& dist)
00581 {
00582 Lock l(mutex_);
00583 if (dist.samples.size()!=1)
00584 throw std::logic_error("Localization distribution was not deterministic ");
00585 last_loc_ = dist.samples[0];
00586
00587 const unsigned ref_node = gmu::refNode(*last_loc_);
00588 if (!gmu::contains(opt_poses_, ref_node))
00589 {
00590 ROS_DEBUG_STREAM_NAMED ("localization", "Not updating localization due to"
00591 " lack of optimized pose for " << ref_node);
00592 return;
00593 }
00594 if (!current_grid_ || !coveredBy(ref_node, *current_grid_, 1-grid_overlap_))
00595 {
00596 if (gmu::contains(covering_grids_, ref_node))
00597 {
00598 current_grid_ = covering_grids_[ref_node];
00599 ROS_DEBUG_STREAM_NAMED ("localization", "On new grid " << *current_grid_);
00600 }
00601 }
00602
00603 gm::PoseStamped loc;
00604 loc.header.frame_id = tmap::gridFrame(*current_grid_);
00605 loc.header.stamp = dist.stamp;
00606 loc.pose = gmu::transformPose(nodeGridTransform(ref_node, *current_grid_),
00607 last_loc_->pose);
00608 loc_pub_.publish(loc);
00609 }
00610
00611
00612
00613
00614 void Mapper::diffCB (OptionalDiff diff,
00615 const pg::ConstraintGraph& g)
00616 {
00617 Lock l(mutex_);
00618 if (diff)
00619 {
00620 BOOST_FOREACH (const gmm::Node& n, diff->new_nodes)
00621 pending_nodes_.insert(n.id);
00623 }
00624 else
00625 {
00626 BOOST_FOREACH (const unsigned n, g.allNodes())
00627 pending_nodes_.insert(n);
00628 }
00629 pose_graph_ = g;
00630
00631
00632 pose_graph_.setOptimizedPoses(opt_poses_);
00633
00634 last_diff_time_ = ros::Time::now();
00635 }
00636
00637 bool Mapper::switchGrid (msg::SwitchGrid::Request& req,
00638 msg::SwitchGrid::Response& resp)
00639 {
00640 Lock l(mutex_);
00641 ROS_DEBUG_STREAM_NAMED ("localization",
00642 "Switching to grid " << req.grid);
00643 current_grid_ = req.grid;
00644 return true;
00645 }
00646
00647
00648
00649
00650
00651
00652
00653 Nodes Mapper::nodesOnGrid (const unsigned g) const
00654 {
00655 Nodes nodes;
00656 BOOST_FOREACH (const NodePoses::value_type& e, opt_poses_)
00657 {
00658 if (coveredBy(e.first, g, 1.0))
00659 nodes.insert(e.first);
00660 }
00661 return nodes;
00662 }
00663
00664 Nodes Mapper::overlayingNodes (const unsigned g) const
00665 {
00666 const Nodes potential_nodes = topologicallyCloseNodes(g, grid_size_*1.5);
00667 Nodes nodes;
00668 BOOST_FOREACH (const unsigned n, potential_nodes)
00669 {
00670 ls::LocalizedScan::ConstPtr scan = scans_.get(n);
00671 const tf::Pose trans = nodeGridTransform(n, g);
00672 const tf::Point b = trans*gmu::toPoint(scan->barycenter);
00673 if ((fabs(b.x()) < grid_size_/2.0) &&
00674 (fabs(b.y()) < grid_size_/2.0))
00675 nodes.insert(n);
00676 }
00677 ROS_DEBUG_STREAM_NAMED ("overlay", "Overlaying grid " << g << " using "
00678 << toString(nodes) << " (potential nodes were )"
00679 << toString(potential_nodes));
00680
00681 return nodes;
00682 }
00683
00685 tf::Pose Mapper::nodeGridTransform (const unsigned n, const unsigned g) const
00686 {
00687 const tf::Pose& grid_center_pose = gmu::keyValue(opt_poses_, g);
00688 const tf::Pose& node_pose = gmu::keyValue(opt_poses_, n);
00689 return grid_center_pose.inverseTimes(node_pose);
00690 }
00691
00692
00693 nm::OccupancyGrid::ConstPtr Mapper::computeLocalGrid (const unsigned g) const
00694 {
00695 ROS_ASSERT_MSG (gmu::contains(grid_nodes_, g), "%u is not a grid node", g);
00696 const std::string frame = tmap::gridFrame(g);
00697
00699 nm::OccupancyGrid dims;
00700 dims.info.resolution = resolution_;
00701 dims.info.width = grid_size_/resolution_;
00702 dims.info.height = grid_size_/resolution_;
00703
00704 const double r=grid_size_/2.0;
00705 dims.info.origin.position.x = -r;
00706 dims.info.origin.position.y = -r;
00707 dims.info.origin.orientation.w = 1.0;
00708 dims.header.frame_id = frame;
00709 gu::OverlayClouds overlay = gu::createCloudOverlay(dims, frame);
00710
00712 BOOST_FOREACH (const unsigned n, overlayingNodes(g))
00713 {
00714 ls::LocalizedScan::ConstPtr stored_scan = scans_.get(n);
00715 gu::LocalizedCloud::Ptr cloud(new gu::LocalizedCloud());
00716 cloud->header.frame_id = frame;
00717 cloud->sensor_pose = gmu::transformPose(nodeGridTransform(n, g),
00718 stored_scan->sensor_pose);
00719 cloud->cloud = stored_scan->cloud;
00720 addCloud(&overlay, cloud);
00721 }
00722
00724 if (robot_radius_ > 0)
00725 {
00726 const tf::Transform world_to_grid = gmu::keyValue(opt_poses_, g).inverse();
00727 BOOST_FOREACH (const unsigned n, nodesOnGrid(g))
00728 {
00729 const tf::Pose node_pose = gmu::keyValue(opt_poses_, n);
00730 const gm::Point pos = gmu::toPoint(world_to_grid*node_pose.getOrigin());
00731 addKnownFreePoint(&overlay, pos, robot_radius_);
00732 }
00733 }
00734
00735 return getGrid(overlay);
00736 }
00737
00738
00739
00740
00741
00742 void Mapper::visualize (const ros::TimerEvent&)
00743 {
00744 visualizeGridBoundaries();
00745 visualizeCurrentGrid();
00746 visualizeEdges();
00747 }
00748
00749 void Mapper::visualizeCurrentGrid ()
00750 {
00751 if (!last_loc_)
00752 return;
00753
00754 Lock l(mutex_);
00755 const unsigned n = gmu::refNode(*last_loc_);
00756 if (!gmu::contains(covering_grids_, n))
00757 {
00758 ROS_DEBUG_STREAM_NAMED ("visualization", "Not visualizing current grid "
00759 " because don't have covering grid for " << n);
00760 return;
00761 }
00762 grid_pub_.publish(computeLocalGrid(*current_grid_));
00763 }
00764
00765 void Mapper::visualizeGridBoundaries ()
00766 {
00767 vm::Marker grids;
00768 grids.header.frame_id = ref_frame_;
00769 grids.header.stamp = ros::Time::now();
00770 grids.ns = "topological_map";
00771 grids.type = vm::Marker::LINE_LIST;
00772 grids.action = vm::Marker::ADD;
00773 grids.scale.x = 0.03;
00774 grids.color.r = 1.0;
00775 grids.color.g = 0.6;
00776 grids.color.b = 0.0;
00777 grids.color.a = 1.0;
00778
00779 BOOST_FOREACH (const unsigned g, grid_nodes_)
00780 {
00781 const double s = grid_size_*0.5;
00782 const tf::Pose origin = gmu::keyValue(opt_poses_, g);
00783 const int xm[] = {-1, 1, 1, -1};
00784 const int ym[] = {1, 1, -1, -1};
00785 for (int i=0; i<4; i++)
00786 {
00787 const int j = i ? i-1 : 3;
00788 const btVector3 p1(s*xm[j], s*ym[j], 0);
00789 const btVector3 p2(s*xm[i], s*ym[i], 0);
00790 grids.points.push_back(gmu::toPoint(origin*p1));
00791 grids.points.push_back(gmu::toPoint(origin*p2));
00792 }
00793 }
00794 marker_pub_.publish(grids);
00795 }
00796
00797 void Mapper::visualizeEdges ()
00798 {
00799 vm::Marker edges;
00800 edges.header.frame_id = ref_frame_;
00801 edges.header.stamp = ros::Time::now();
00802 edges.ns = "topological_map_edges";
00803 edges.type = vm::Marker::LINE_LIST;
00804 edges.action = vm::Marker::ADD;
00805 edges.scale.x = 0.03;
00806 edges.color.r = 1.0;
00807 edges.color.g = 0.0;
00808 edges.color.b = 0.0;
00809 edges.color.a = 1.0;
00810 BOOST_FOREACH (const unsigned g, grid_nodes_)
00811 {
00812 const tf::Pose origin = gmu::keyValue(opt_poses_, g);
00813 BOOST_FOREACH (const tmap::GraphEdge e, out_edges(tmap_.node(g), tmap_))
00814 {
00815 if (tmap_[e].src == g)
00816 {
00817 edges.points.push_back(gmu::toPoint(origin.getOrigin()));
00818 edges.points.push_back(gmu::transformPoint(origin,
00819 tmap_[e].offset.position));
00820 }
00821 }
00822 }
00823 marker_pub_.publish(edges);
00824 }
00825
00826 void Mapper::saveGrid (const unsigned g)
00827 {
00828 typedef wh::MessageWithMetadata<nm::OccupancyGrid>::ConstPtr GridWithMetadata;
00829 ROS_DEBUG_STREAM_NAMED ("grid", "Storing local grid " << g);
00830 nm::OccupancyGrid::ConstPtr grid = computeLocalGrid(g);
00831 const string id = boost::lexical_cast<string>(g);
00832
00833 vector<wh::Condition> conditions(1);
00834 conditions[0].field_name = "id";
00835 conditions[0].predicate = wh::Condition::EQUALS;
00836 conditions[0].args.push_back(id);
00837
00838 vector<GridWithMetadata> existing = grids_.pullAllResults(conditions, true);
00839 ROS_DEBUG_NAMED ("grid", "There were %zu existing grids", existing.size());
00840 if (existing.size()>0)
00841 {
00842 const unsigned num_removed = grids_.removeMessages(conditions);
00843 ROS_DEBUG_NAMED ("grid", "Removed %u existing grids", num_removed);
00844 }
00845
00846 grids_.publish(*grid, wh::MetadataString().add("id", id));
00847 grid_save_times_[g] = ros::Time::now();
00848 }
00849
00850 void Mapper::publishGraph ()
00851 {
00852 msg::TopologicalGraph::Ptr m;
00853 m = tmap::toMessage(tmap_);
00854 graph_pub_.publish(m);
00855 }
00856
00857
00858 void Mapper::publishRefTransforms (const ros::TimerEvent& e)
00859 {
00860 Lock l(mutex_);
00861 BOOST_FOREACH (const unsigned g, grid_nodes_)
00862 {
00863 tf::StampedTransform tr(gmu::keyValue(opt_poses_, g), ros::Time::now(),
00864 ref_frame_, tmap::gridFrame(g));
00865 tfb_.sendTransform(tr);
00866 }
00867 }
00868
00869 void Mapper::saveCurrentGrid ()
00870 {
00871
00872 if (current_grid_) {
00873 if (!gmu::contains(grid_save_times_, *current_grid_) ||
00874 gmu::keyValue(grid_save_times_, *current_grid_) < last_diff_time_) {
00875 saveGrid(*current_grid_);
00876 grid_pub_.publish(computeLocalGrid(*current_grid_));
00877 }
00878 }
00879 }
00880
00881
00882 }
00883
00884
00885
00886
00887 int main (int argc, char** argv)
00888 {
00889 ros::init(argc, argv, "topological_mapper");
00890 laser_slam_mapper::Mapper node;
00891 ros::spin();
00892 return 0;
00893 }