Rviz中的地图绘制使用了cairo
库。注意gflag的参数include_frozen_submaps
和 include_unfrozen_submaps
不能都为false,否则会报错
cartographerrviz的绘制方式,就是`submap_node 控制一个子图的绘制,每个子图有一个子图原点,这个是
submap_query中的
slice_pose。而每个子图之间是有微弱旋转的,而控制旋转的中心也是这个
slice_pose。而每个子图之间的旋转和平移可以通过
submap_list`的pose得到。
main
函数值得看的就一句::cartographer_ros::Node node(FLAGS_resolution, FLAGS_publish_period_sec);
,构造函数如下
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 Node::Node (const double resolution, const double publish_period_sec) : resolution_ (resolution), client_ (node_handle_.serviceClient<::cartographer_ros_msgs::SubmapQuery>( kSubmapQueryServiceName)), submap_list_subscriber_ (node_handle_.subscribe ( kSubmapListTopic, kLatestOnlyPublisherQueueSize, boost::function<void ( const cartographer_ros_msgs::SubmapList::ConstPtr&)>( [this ](const cartographer_ros_msgs::SubmapList::ConstPtr& msg) { HandleSubmapList (msg); }))), occupancy_grid_publisher_ ( node_handle_.advertise<::nav_msgs::OccupancyGrid>( kOccupancyGridTopic, kLatestOnlyPublisherQueueSize, true )), occupancy_grid_publisher_timer_ ( node_handle_.createWallTimer (::ros::WallDuration (publish_period_sec), &Node::DrawAndPublish, this )) {}
Node::DrawAndPublish
是画图和发布
map
,不是重点
HandleSubmapList
函数大部分都很简单,终点是下面这句:
1 2 auto fetched_textures = ::cartographer_ros::FetchSubmapTextures (id, &client_);
内部其实就是
submap_query
的客户端发起请求,服务端的注册在
Node
的构造函数里,回调是
Node::HandleSubmapQuery
代码调用顺序是: Node::HandleSubmapQuery
—— MapBuilderBridge::HandleSubmapQuery
—— MapBuilder::SubmapToProto
—— PoseGraph2D::GetSubmapData
和 Submap2D::ToResponseProto
—— ProbabilityGrid::DrawToSubmapTexture
重点:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 PoseGraphInterface::SubmapData PoseGraph2D::GetSubmapDataUnderLock ( const SubmapId& submap_id) const { const auto it = data_.submap_data.find (submap_id); if (it == data_.submap_data.end ()) return {}; auto submap = it->data.submap; if (data_.global_submap_poses_2d.Contains (submap_id) ) { return {submap, transform::Embed3D ( data_.global_submap_poses_2d.at (submap_id).global_pose) }; } return {submap, ComputeLocalToGlobalTransform (data_.global_submap_poses_2d, submap_id.trajectory_id) * submap->local_pose () }; } void Submap2D::ToResponseProto ( const transform::Rigid3d&, proto::SubmapQuery::Response* const response) const { if (!grid_) return ; response->set_submap_version ( num_range_data () ); proto::SubmapQuery::Response::SubmapTexture* const texture = response->add_textures (); grid ()->DrawToSubmapTexture (texture, local_pose ()); }
再看DrawToSubmapTexture
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 bool ProbabilityGrid::DrawToSubmapTexture ( proto::SubmapQuery::Response::SubmapTexture* const texture, transform::Rigid3d local_pose) const { Eigen::Array2i offset; CellLimits cell_limits; ComputeCroppedLimits (&offset, &cell_limits); std::string cells; for (const Eigen::Array2i& xy_index : XYIndexRangeIterator (cell_limits)) { if (!IsKnown (xy_index + offset)) { cells.push_back (0 ); cells.push_back (0 ); continue ; } const int delta = 128 - ProbabilityToLogOddsInteger (GetProbability (xy_index + offset)); const uint8 alpha = delta > 0 ? 0 : -delta; const uint8 value = delta > 0 ? delta : 0 ; cells.push_back (value); cells.push_back ((value || alpha) ? alpha : 1 ); } common::FastGzipString (cells, texture->mutable_cells ()); ...... *texture->mutable_slice_pose () = transform::ToProto ( local_pose.inverse () * transform::Rigid3d::Translation (Eigen::Vector3d (max_x, max_y, 0. )) ); return true ; }
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 struct SubmapTexture { struct Pixels { std::vector<char > intensity; std::vector<char > alpha; }; Pixels pixels; int width; int height; double resolution; ::cartographer::transform::Rigid3d slice_pose; }; struct SubmapTextures { int version; std::vector<SubmapTexture> textures; };