构造函数
ObstacleLayer()
{
costmap_ = NULL; // this is the unsigned char* member of parent class Costmap2D.这里指明了costmap_指针保存了Obstacle这一层的地图数据
}
对于ObstacleLater,首先分析其需要实现的Layer层的方法:
virtual void onInitialize();
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y,double* max_x, double* max_y);
virtual void updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
virtual void activate();
virtual void deactivate();
virtual void reset();
函数 onInitialize();
:
首先获取参数设定的值,然后新建observation buffer
:
// create an observation buffer
observation_buffers_.push_back(boost::shared_ptr < ObservationBuffer>
(new ObservationBuffer(topic, observation_keep_time, expected_update_rate, min_obstacle_height,max_obstacle_height, obstacle_range, raytrace_range, *tf_, global_frame_,sensor_frame, transform_tolerance)));
// check if we'll add this buffer to our marking observation buffers
if (marking)
marking_buffers_.push_back(observation_buffers_.back());
// check if we'll also add this buffer to our clearing observation buffers
if (clearing)
clearing_buffers_.push_back(observation_buffers_.back());
然后分别对不同的sensor类型如LaserScan PointCloud PointCloud2
,注册不同的回调函数。这里选LaserScan
分析其回调函数:
void ObstacleLayer::laserScanCallback(const sensor_msgs::LaserScanConstPtr& message,
const boost::shared_ptr<ObservationBuffer>& buffer)
{
// project the laser into a point cloud
sensor_msgs::PointCloud2 cloud;
cloud.header = message->