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 #include <graph_slam/global_map.h>
00032 #include <pose_graph/transforms.h>
00033 #include <occupancy_grid_utils/ray_tracer.h>
00034 #include <boost/foreach.hpp>
00035 #include <boost/optional.hpp>
00036
00037 namespace graph_slam
00038 {
00039
00040 namespace pg=pose_graph;
00041 namespace nm=nav_msgs;
00042 namespace gu=occupancy_grid_utils;
00043
00044 using std::min;
00045 using std::max;
00046
00047 nm::MapMetaData getGridBounds (const pg::NodePoseMap& poses, const double resolution)
00048 {
00049 boost::optional<double> min_x, min_y, max_x, max_y;
00050 BOOST_FOREACH (const pg::NodePoseMap::value_type& e, poses) {
00051 const double x = e.second.position.x;
00052 const double y = e.second.position.y;
00053 if (!min_x) {
00054 min_x = x;
00055 max_x = x;
00056 min_y = y;
00057 max_y = y;
00058 }
00059 else {
00060 min_x = min(x, *min_x);
00061 min_y = min(y, *min_y);
00062 max_x = max(x, *max_x);
00063 max_y = max(y, *max_y);
00064 }
00065 }
00066
00067 nm::MapMetaData info;
00068 info.origin.orientation.w = 1.0;
00069 info.origin.position.x = *min_x-PADDING;
00070 info.origin.position.y = *min_y-PADDING;
00071 info.width = (*max_x-*min_x+2*PADDING)/resolution;
00072 info.height = (*max_y-*min_y+2*PADDING)/resolution;
00073 info.resolution = resolution;
00074
00075 return info;
00076 }
00077
00078
00079 nm::OccupancyGrid::Ptr generateGlobalMap (const pg::PoseGraph& graph, const pg::NodePoseMap& poses,
00080 const double resolution)
00081 {
00082 nm::MapMetaData bounds = getGridBounds(poses, resolution);
00083 ROS_DEBUG_STREAM_NAMED("global_map", "Generating global map with dimensions " << bounds);
00084 gu::OverlayClouds overlay = gu::createCloudOverlay(bounds, pg::OPTIMIZED_FRAME,
00085 gu::DEFAULT_OCCUPANCY_THRESHOLD, 30.0);
00086 BOOST_FOREACH (const pg::NodePoseMap::value_type& e, poses) {
00087 if (graph.hasCloud(e.first)) {
00088
00089
00090 gu::LocalizedCloud::ConstPtr base_frame_cloud = graph.getCloud(e.first);
00091 const Eigen3::Affine3d base_to_opt = pg::poseToWorldTransform(e.second);
00092 gu::LocalizedCloud::Ptr opt_frame_cloud(new gu::LocalizedCloud());
00093 opt_frame_cloud->sensor_pose.pose = pg::applyTransform(base_to_opt, base_frame_cloud->sensor_pose.pose);
00094 opt_frame_cloud->sensor_pose.header.frame_id = pg::OPTIMIZED_FRAME;
00095 opt_frame_cloud->cloud.points = base_frame_cloud->cloud.points;
00096
00097
00098 gu::addCloud(&overlay, opt_frame_cloud);
00099 }
00100 }
00101
00102 nm::OccupancyGrid::Ptr grid = gu::getGrid(overlay);
00103 grid->header.stamp = ros::Time::now();
00104 ROS_DEBUG_NAMED ("global_map", "Done generating global map");
00105 return grid;
00106 }
00107
00108
00109 }