单独启动costmap_2d生成代价地图

单独启动costmap_2d生成代价地图

要单独启动costmap_2d以生成代价地图,您需要创建一个自定义的ROS节点,将costmap_2d::Costmap2DROS类实例化,并加载适当的参数。以下是一个简单示例:

  1. 首先,在您的工作空间中创建一个名为standalone_costmap的ROS包。确保您已安装costmap_2d及其依赖项:
1
2
3
cd ~/catkin_ws/src
catkin_create_pkg standalone_costmap roscpp costmap_2d

  1. 在standalone_costmap包中创建一个名为costmap_node.cpp的C++源文件,并添加以下代码:
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
#include <ros/ros.h>
#include <costmap_2d/costmap_2d_ros.h>

int main(int argc, char** argv) {
ros::init(argc, argv, "standalone_costmap_node");
ros::NodeHandle nh;

tf2_ros::Buffer tf_buffer;
tf2_ros::TransformListener tf_listener(tf_buffer);

costmap_2d::Costmap2DROS costmap("standalone_costmap", tf_buffer);

ros::spin();

return 0;
}

  1. 修改CMakeLists.txt以添加可执行文件,并将其链接到相应的库:
1
2
3
4
# ...
add_executable(standalone_costmap_node src/costmap_node.cpp)
target_link_libraries(standalone_costmap_node ${catkin_LIBRARIES})

  1. 创建一个名为config的目录,并在其中创建一个名为costmap_params.yaml的配置文件。在此文件中,定义costmap_2d所需的参数,例如:
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
standalone_costmap:
global_frame: /map
robot_base_frame: /base_link
update_frequency: 5.0
publish_frequency: 1.0
static_map: true
rolling_window: false
width: 10.0
height: 10.0
resolution: 0.05

plugins:
- {name: static_layer, type: "costmap_2d::StaticLayer"}
- {name: obstacle_layer, type: "costmap_2d::VoxelLayer"}
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}

static_layer:
map_topic: /map
subscribe_to_updates: true

obstacle_layer:
observation_sources: laser_scan_sensor
laser_scan_sensor: {sensor_frame: base_link, data_type: LaserScan, topic: /scan, marking: true, clearing: true}

inflation_layer:
inflation_radius: 0.55

这里,我们定义了一个名为standalone_costmap的代价地图配置,其中包括static_layer(静态层)、obstacle_layer(障碍物层)和inflation_layer(膨胀层)。

  1. 创建一个名为launch的目录,并在其中创建一个名为costmap.launch的启动文件。在此文件中,包含costmap_node.cpp可执行文件并加载costmap_params.yaml配置文件:
1
2
3
4
5
6
<launch>
<node name="standalone_costmap_node" pkg="standalone_costmap"type="standalone_costmap_node" output="screen">
<rosparam command="load" file="$(find standalone_costmap)/config/costmap_params.yaml" />
</node>
</launch>

  1. 在您的工作空间中构建和运行新创建的standalone_costmap包:
1
2
3
4
cd ~/catkin_ws
catkin_make
source devel/setup.bash
roslaunch standalone_costmap costmap.launch

此时,standalone_costmap节点应启动并生成代价地图。确保您提供了地图和传感器数据,例如激光扫描。现在,您可以将此代价地图与其他ROS节点一起使用,例如导航和路径规划。

要在RViz中可视化代价地图,请添加一个Map显示类型并将其指向standalone_costmap发布的nav_msgs/OccupancyGrid消息。默认情况下,代价地图发布在/standalone_costmap/costmap话题上。在RViz中,您应该能够看到代价地图,其中不同的颜色表示不同的代价值,例如,黑色表示障碍物,蓝色表示未知区域,白色表示可通行区域。


单独启动costmap_2d生成代价地图
https://qiangsun89.github.io/2023/04/27/单独启动costmap-2d生成代价地图/
作者
Qiang Sun
发布于
2023年4月27日
许可协议