解读 Costmap2DROS 的构造函数

ROS源码里有个costmap_2d_node.cpp,编译成可执行文件costmap_2d_node,注意它的链接库:

1
2
3
4
5
6
target_link_libraries(costmap_2d_node
costmap_2d
${PCL_LIBRARIES}
${Boost_LIBRARIES}
${catkin_LIBRARIES}
)

它的main函数非常简单,实际就是Costmap2DROS的构造函数
1
2
3
4
5
6
7
8
9
10
11
#include <ros/ros.h>
#include <costmap_2d/costmap_2d_ros.h>

int main(int argc, char** argv)
{
ros::init(argc, argv, "costmap_node");
tf::TransformListener tf(ros::Duration(10));
costmap_2d::Costmap2DROS lcr("costmap", tf);
ros::spin();
return (0);
}

获取参数值和tf变换

首先是一些参数的获取。循环等待直到获得机器人底盘坐标系和global系之间的坐标转换。
并获取rolling_windowtrack_unknown_spacealways_send_full_costmap的参数,默认为false。

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
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
Costmap2DROS::Costmap2DROS(std::string name, tf::TransformListener& tf) :
layered_costmap_(NULL),
name_(name), // 局部还是全局代价地图
tf_(tf),
transform_tolerance_(0.3),
map_update_thread_shutdown_(false),
stop_updates_(false),
initialized_(true),
stopped_(false),
robot_stopped_(false),
map_update_thread_(NULL),
last_publish_(0),
plugin_loader_("costmap_2d", "costmap_2d::Layer"),
publisher_(NULL),
dsrv_(NULL),
footprint_padding_(0.0)
{
//初始化old pose
old_pose_.setIdentity();
old_pose_.setOrigin(tf::Vector3(1e30, 1e30, 1e30));
// 如果是全局代价地图,这里name是global_costmap
ros::NodeHandle private_nh("~/" + name);
ros::NodeHandle g_nh;

//获取tf前缀
ros::NodeHandle prefix_nh;
std::string tf_prefix = tf::getPrefixParam(prefix_nh);

//两个坐标系,全局和局部的参数是不同的
private_nh.param("global_frame", global_frame_, std::string("/map"));
private_nh.param("robot_base_frame", robot_base_frame_, std::string("base_link"));

//确保基于tf前缀正确设置了坐标系
//tf::resolve或者TransformListener::resolve的作用就是使用tf_prefix参数将frame_name解析为frame_id
global_frame_ = tf::resolve(tf_prefix, global_frame_);
robot_base_frame_ = tf::resolve(tf_prefix, robot_base_frame_);

ros::Time last_error = ros::Time::now();
std::string tf_error;

//确保机器人global_frame_和robot_base_frame_之间的有效转换, 否则一直停留在这里阻塞
// 这里已经写死为 0.1,有需要可以改变
while (ros::ok()
&& !tf_.waitForTransform(global_frame_, robot_base_frame_, ros::Time(),
ros::Duration(0.1), ros::Duration(0.01), &tf_error))
{
ros::spinOnce();
// 如果5秒内未成功tf转换,报警
if (last_error + ros::Duration(5.0) < ros::Time::now())
{
ROS_WARN("Timed out waiting for transform from %s to %s to become available before running costmap, tf error: %s",
robot_base_frame_.c_str(), global_frame_.c_str(), tf_error.c_str());
last_error = ros::Time::now();
}
// The error string will accumulate and errors will typically be the same, so the last
// will do for the warning above. Reset the string here to avoid accumulation.
tf_error.clear();
}
//检测是否需要“窗口滚动”,从参数服务器获取以下参数
bool rolling_window, track_unknown_space, always_send_full_costmap;
private_nh.param("rolling_window", rolling_window, false);
private_nh.param("track_unknown_space", track_unknown_space, false);
private_nh.param("always_send_full_costmap", always_send_full_costmap, false);

有时出现了下面的报错

这就是因为上面的0.1太小了

LayeredCostmap类的对象

layered_costmap_ = new LayeredCostmap(global_frame_, rolling_window, track_unknown_space);

接下来创建一个LayeredCostmap类实例layered_costmap_,作为规划器使用的master costmap,并通过它管理各层地图。

LayeredCostmap类是Costmap2DROS的类成员,它是master costmap,也能够管理各层地图,因为它 含有指向各层子地图的指针 std::vector<boost::shared_ptr<Layer> > plugins_,能够调用子地图的类方法,开启子地图的更新,各层子地图最后都会合并到master costmap,提供给规划器的使用。

它的构造函数只有:

1
2
3
4
5
6
7
8
9
10
11
// 如果追踪未知信息的cell,默认false
if (track_unknown)
costmap_.setDefaultValue(255);
else
costmap_.setDefaultValue(0);

// 枚举值的含义对应如下:
/* NO_INFORMATION = 255;
LETHAL_OBSTACLE = 254;
INSCRIBED_INFLATED_OBSTACLE = 253;
FREE_SPACE = 0; */

LayeredCostmap含有类成员Costmap2D costmap_,这个类就是底层地图,用于记录地图数据。

继续Costmap2DROS的构造函数代码:

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
// 查看参数服务器里的costmap是否有plugins参数,如果没有,则重置为旧参数
if (!private_nh.hasParam("plugins"))
{
resetOldParameters(private_nh);
}
// 如果加载了plugins,循环将每个plugin即每层子地图添加进layered_costmap_类的
// 指针组对象中,并对每层地图调用其 initialize 类方法,初始化各层地图。
if (private_nh.hasParam("plugins"))
{
XmlRpc::XmlRpcValue my_list;
private_nh.getParam("plugins", my_list);
for (int32_t i = 0; i < my_list.size(); ++i)
{
std::string pname = static_cast<std::string>(my_list[i]["name"]);
std::string type = static_cast<std::string>(my_list[i]["type"]);
ROS_INFO("Using plugin \"%s\"", pname.c_str());

// plugin_loader_类型是 pluginlib::ClassLoader<Layer>,ROS插件机制
boost::shared_ptr<Layer> plugin = plugin_loader_.createInstance(type);
// 添加到容器 plugins_
layered_costmap_->addPlugin(plugin);
// 执行 Layer::initialize, 它向各层地图通知主地图的存在,并调用
// oninitialize方法 (Layer类中的虚函数,被定义在各层地图中)
plugin->initialize(layered_costmap_, name + "/" + pname, &tf_);
}
}

这里得到的插件即为各层子地图。每层子地图使用Pluginlib(ROS插件机制)来实例化,各个层可以被独立的编译,且允许使用C++接口对Costmap做出任意的改变。

footprint话题

订阅footprint话题,回调函数为setUnpaddedRobotFootprintPolygon。当话题上收到footprint时,回调函数会将接收到的footprint根据参数footprint_padding_的值进行膨胀,得到“膨胀”后的padded_footprint_,传递给各级地图。

查看节点可知,/move_base/local_costmap/footprint/move_base/global_costmap/footprint两个话题的发布订阅者都是move_base

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
std::string topic_param, topic;
if (!private_nh.searchParam("footprint_topic", topic_param))
{
topic_param = "footprint_topic";
}
private_nh.param(topic_param, topic, std::string("footprint"));
footprint_sub_ = private_nh.subscribe(topic, 1, &Costmap2DROS::setUnpaddedRobotFootprintPolygon, this);

if (!private_nh.searchParam("published_footprint_topic", topic_param))
{
topic_param = "published_footprint";
}
private_nh.param(topic_param, topic, std::string("oriented_footprint"));
footprint_pub_ = private_nh.advertise<geometry_msgs::PolygonStamped>("footprint", 1);

setUnpaddedRobotFootprint(makeFootprintFromParams(private_nh));


发布代价地图

创建地图的发布器实例,Costmap2DPublisher类是用于地图发布的封装类,在函数mapUpdateLoop中调用

1
2
3
4
5
6
7
8
9
10
11
12
//发布Costmap2D
publisher_ = new Costmap2DPublisher(&private_nh, layered_costmap_->getCostmap(), global_frame_, "costmap", always_send_full_costmap);

//创建地图更新线程的控制量
stop_updates_ = false;
initialized_ = true;
stopped_ = false;

//创建一个timer去检测机器人是否在移动
robot_stopped_ = false;
//回调函数movementCB通过比较前后两个pose的差来判断机器人是否在移动
timer_ = private_nh.createTimer(ros::Duration(.1), &Costmap2DROS::movementCB, this);

开启动态参数配置,它的回调函数Costmap2DROS::reconfigureCB会在节点启动时运行一次,加载.cfg文件的配置参数。这个函数给对应参数赋值,并创建了一个Costmap2DROS::mapUpdateLoop函数的线程,即地图更新线程。

1
2
3
4
5
6
//开启参数动态配置
dsrv_ = new dynamic_reconfigure::Server<Costmap2DConfig>(ros::NodeHandle("~/" + name));
//回调函数reconfigureCB 除了对一些类成员的配置值做赋值以外,还会开启一个更新map的线程
dynamic_reconfigure::Server<Costmap2DConfig>::CallbackType cb = boost::bind(&Costmap2DROS::reconfigureCB, this, _1,_2);
dsrv_->setCallback(cb);
}

这里的代码有点复杂了,mapUpdateLoop函数循环调用UpdateMap函数,更新地图。并以publish_cycle为周期,发布更新后的地图。

UpdateMap首先调用类内getRobotPose函数,通过tf转换,将机器人底盘系的坐标转换到global系,得到机器人的位姿。然后通过layered_costmap_调用LayeredCostmap类的updateMap函数,更新地图。

流程如下
costmap的初始化流程.png

整个costmap初始化,最关键和复杂的就是各层的加载和更新地图