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 <laser_slam/global_map.h>
00040 #include <laser_slam/LocalizedScan.h>
00041 #include <occupancy_grid_utils/ray_tracer.h>
00042 #include <pcl_ros/transforms.h>
00043 #include <pcl/ros/conversions.h>
00044 #include <graph_mapping_utils/geometry.h>
00045 #include <boost/optional.hpp>
00046 #include <boost/foreach.hpp>
00047
00048
00049 namespace laser_slam
00050 {
00051
00052 namespace pg=pose_graph;
00053 namespace nm=nav_msgs;
00054 namespace sm=sensor_msgs;
00055 namespace gu=occupancy_grid_utils;
00056 namespace util=graph_mapping_utils;
00057
00058 using std::min;
00059 using std::max;
00060 using std::string;
00061
00062
00063
00064 nm::MapMetaData getGridBounds (const pg::ConstraintGraph& graph, const double resolution)
00065 {
00066 boost::optional<double> min_x, min_y, max_x, max_y;
00067 BOOST_FOREACH (unsigned n, graph.allNodes()) {
00068 if (!graph.hasOptimizedPose(n))
00069 continue;
00070 const tf::Pose pose = graph.getOptimizedPose(n);
00071 const double x = pose.getOrigin().x();
00072 const double y = pose.getOrigin().y();
00073 if (!min_x) {
00074 min_x = x;
00075 max_x = x;
00076 min_y = y;
00077 max_y = y;
00078 }
00079 else {
00080 min_x = min(x, *min_x);
00081 min_y = min(y, *min_y);
00082 max_x = max(x, *max_x);
00083 max_y = max(y, *max_y);
00084 }
00085 }
00086
00087 nm::MapMetaData info;
00088 info.origin.orientation.w = 1.0;
00089 info.origin.position.x = *min_x-PADDING;
00090 info.origin.position.y = *min_y-PADDING;
00091 info.width = (*max_x-*min_x+2*PADDING)/resolution;
00092 info.height = (*max_y-*min_y+2*PADDING)/resolution;
00093 info.resolution = resolution;
00094
00095 return info;
00096 }
00097
00098
00099 nm::OccupancyGrid::ConstPtr generateGlobalMap (const pg::ConstraintGraph& graph, const ScanMap& scans,
00100 const double resolution, const string& global_frame,
00101 const bool cleanup_grid, const pg::NodePoseMap& opt_poses_,
00102 const double robot_radius)
00103 {
00104 nm::OccupancyGrid fake_grid;
00105 fake_grid.info = getGridBounds(graph, resolution);
00106 ROS_DEBUG_STREAM_NAMED ("global_map", "Generating global map with dimensions " << fake_grid.info
00107 << " from graph with " << graph.allNodes().size() << " nodes");
00108
00109 gu::OverlayClouds overlay = gu::createCloudOverlay(fake_grid, global_frame, 0.1, 30.0);
00110 BOOST_FOREACH (unsigned n, util::sampleSubset(graph.allNodes(), 200)) {
00111 if (!graph.hasOptimizedPose(n)) {
00112 ROS_DEBUG_STREAM_NAMED ("global_map_internal", "Omitting node " << n <<
00113 " from global overlay, as it has no optimized pose");
00114 continue;
00115 }
00116 const tf::Pose pose = graph.getOptimizedPose(n);
00117 try {
00118 LocalizedScan::ConstPtr m = scans.get(n);
00119 gu::LocalizedCloud::Ptr global_frame_cloud(new gu::LocalizedCloud());
00120 global_frame_cloud->sensor_pose = util::transformPose(pose, m->sensor_pose);
00121 global_frame_cloud->header.frame_id = global_frame;
00122 global_frame_cloud->cloud.points = m->cloud.points;
00123
00124
00125 gu::addCloud(&overlay, global_frame_cloud);
00126 }
00127 catch (pose_graph::DataNotFoundException) {
00128 ROS_DEBUG_STREAM_NAMED ("global_map_internal", "Omitting node " << n <<
00129 " from global overlay, as it has no associated scan");
00130 }
00131 }
00132 if (robot_radius>0)
00133 {
00134 BOOST_FOREACH (const pg::NodePoseMap::value_type& e, opt_poses_)
00135 {
00136 gu::addKnownFreePoint(&overlay, util::toPoint(e.second.getOrigin()), robot_radius);
00137 }
00138 }
00139
00140 nm::OccupancyGrid::Ptr grid = gu::getGrid(overlay);
00141 if (cleanup_grid) {
00142 gu::OverlayClouds overlay2 = gu::createCloudOverlay(*grid, global_frame, 0.1, 30.0);
00143 BOOST_FOREACH (unsigned n, graph.allNodes()) {
00144 if (!graph.hasOptimizedPose(n))
00145 continue;
00146 const tf::Pose pose = graph.getOptimizedPose(n);
00147 try {
00148 LocalizedScan::ConstPtr m = scans.get(n);
00149 gu::LocalizedCloud::Ptr global_frame_cloud(new gu::LocalizedCloud());
00150 global_frame_cloud->sensor_pose = util::transformPose(pose, m->sensor_pose);
00151 global_frame_cloud->header.frame_id = global_frame;
00152 global_frame_cloud->cloud.points = m->cloud.points;
00153
00154
00155 gu::addCloud(&overlay2, global_frame_cloud);
00156 }
00157 catch (pose_graph::DataNotFoundException) {
00158 ROS_DEBUG_STREAM_NAMED ("global_map_internal", "Omitting node " << n <<
00159 " from global overlay, as it has no associated scan");
00160 }
00161 }
00162
00163 if (robot_radius>0)
00164 {
00165 BOOST_FOREACH (const pg::NodePoseMap::value_type& e, opt_poses_)
00166 {
00167 gu::addKnownFreePoint(&overlay2, util::toPoint(e.second.getOrigin()), robot_radius);
00168 }
00169 }
00170 nm::OccupancyGrid::Ptr grid2 = gu::getGrid(overlay2);
00171 grid2->header.stamp = ros::Time::now();
00172 ROS_DEBUG_STREAM_NAMED ("global_map", "Done generating global map");
00173 return grid2;
00174 }
00175 else
00176 return grid;
00177 }
00178
00179
00180 sm::PointCloud2::ConstPtr generateGlobalCloud
00181 (const pg::ConstraintGraph& graph, const CloudMap& clouds,
00182 const string& global_frame)
00183 {
00184 ROS_DEBUG_NAMED ("global_map", "Generating global cloud");
00185 pcl::PointCloud<pcl::PointXYZ> cloud;
00186 BOOST_FOREACH (const unsigned n, graph.allNodes()) {
00187
00188 if (clouds.hasData(n) && graph.hasOptimizedPose(n)) {
00189 tf::Transform trans = graph.getOptimizedPose(n);
00190 pcl::PointCloud<pcl::PointXYZ> node_cloud, transformed_cloud;
00191 pcl::fromROSMsg(*clouds.get(n), node_cloud);
00192 pcl_ros::transformPointCloud(node_cloud, transformed_cloud, trans);
00193 ROS_DEBUG_NAMED ("global_map",
00194 "Node cloud size is %zu and trans cloud size is %zu",
00195 node_cloud.points.size(),
00196 transformed_cloud.points.size());
00197 transformed_cloud.header.frame_id = global_frame;
00198 cloud.header.frame_id = global_frame;
00199 cloud += transformed_cloud;
00200 }
00201 ROS_INFO_STREAM ("Node " << n << " " << clouds.hasData(n) << " " <<
00202 graph.hasOptimizedPose(n));
00203 }
00204
00205 sm::PointCloud2::Ptr output(new sm::PointCloud2());
00206 pcl::toROSMsg(cloud, *output);
00207 ROS_DEBUG_NAMED ("global_map",
00208 "Done generating global cloud with frame %s and size %u",
00209 output->header.frame_id.c_str(),
00210 output->height*output->width);
00211 return output;
00212 }
00213
00214
00215 }