cartographer建图配置,使用自己2d数据,正常tf显示
安装cartographer
一、播放bag需要加 --clock
rosbag play --clock XXX.bag
二、配置launch文件
2.1、官方demo_backpack_2d.launch文件
<launch>
<param name="/use_sim_time" value="true" /> <!-- 运行播放bag包 变量为true -->
<!-- 运行数据是实时传感器发布的, 变量为false -->
<include file="$(find cartographer_ros)/launch/backpack_2d.launch" />
<node name="rviz" pkg="rviz" type="rviz" required="true"
args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
<!-- <node name="playbag" pkg="rosbag" type="play"
args="clock $(arg bag_filename)" /> --><!-- 我运行其它终端来播放数据 -->
</launch>
2.2、修改backpack_2d.launch
<launch>
<param name="robot_description"
textfile="$(find cartographer_ros)/urdf/backpack_2d.urdf" />
<!-- 下面这句不能删除 -->
<node name="robot_state_publisher" pkg="robot_state_publisher"
type="robot_state_publisher" />
<node name="cartographer_node" pkg="cartographer_ros"
type="cartographer_node" args="
-configuration_directory $(find cartographer_ros)/configuration_files
-configuration_basename backpack_2d.lua"
output="screen">
<!-- <remap from="echoes" to="horizontal_laser_2d" /> -->
<remap from="echoes" to="scan" /> <!-- 修改这句 scan为自己的2D激光话题 -->
</node>
<node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
</launch>
三、lua文件有两处修改
3.1、传感器设置
num_laser_scans = 1,
num_multi_echo_laser_scans = 0,
num_subdivisions_per_laser_scan = 1,
3.2、匹配器设置
TRAJECTORY_BUILDER_2D.min_range = 0.3
TRAJECTORY_BUILDER_2D.max_range = 20. ///这个是激光实际测量距离
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 1.
TRAJECTORY_BUILDER_2D.use_imu_data = false ///是否使用imu
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10.
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1
POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 35
POSE_GRAPH.constraint_builder.min_score = 0.65
3.3、lua文件最后效果
官方/cartographer_ros/cartographer_ros/configuration_files/backpack_2d.lua文件
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
tracking_frame = "base_link",
published_frame = "base_link",
odom_frame = "odom",
provide_odom_frame = false,
use_odometry = false,
num_laser_scans = 1,
num_multi_echo_laser_scans = 0,
num_subdivisions_per_laser_scan = 1,
num_point_clouds = 0,
lookup_transform_timeout_sec = 0.2,
submap_publish_period_sec = 0.3,
pose_publish_period_sec = 5e-3,
trajectory_publish_period_sec = 30e-3,
rangefinder_sampling_ratio = 1.,
odometry_sampling_ratio = 1.,
imu_sampling_ratio = 1.,
}
MAP_BUILDER.use_trajectory_builder_2d = true
-- TRAJECTORY_BUILDER_2D.use_imu_data = false
-- TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 10
TRAJECTORY_BUILDER_2D.min_range = 0.3
TRAJECTORY_BUILDER_2D.max_range = 20.
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 1.
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10.
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1
POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 35
POSE_GRAPH.constraint_builder.min_score = 0.65
return options
四、urdf文件修改
官方cartographer_ros/cartographer_ros/urdf/backpack_2d.urdf文件
<robot name="cartographer_backpack_2d">
<material name="orange">
<color rgba="1.0 0.5 0.2 1" />
</material>
<material name="gray">
<color rgba="0.2 0.2 0.2 1" />
</material>
<link name="imu_link">
<visual>
<origin xyz="0 0 0" />
<geometry>
<box size="0.06 0.04 0.02" />
</geometry>
<material name="orange" />
</visual>
</link>
<!-- <link name="horizontal_laser_link"> --> <!-- 第一处 -->
<link name="scan"><!-- 改成自己的激光frame_id 可以通过命令(rostopic echo /激光话题 | grep frame_id )查询播放bag中的激光frame_id -->
<visual>
<origin xyz="0 0 0" />
<geometry>
<cylinder length="0.05" radius="0.03" />
</geometry>
<material name="gray" />
</visual>
</link>
<link name="vertical_laser_link">
<visual>
<origin xyz="0 0 0" />
<geometry>
<cylinder length="0.05" radius="0.03" />
</geometry>
<material name="gray" />
</visual>
</link>
<link name="base_link" />
<joint name="imu_link_joint" type="fixed">
<parent link="base_link" />
<child link="imu_link" />
<origin xyz="0 0 0" />
</joint>
<!-- <joint name="horizontal_laser_link_joint" type="fixed"> --> <!-- 第2处 -->
<joint name="scan_joint" type="fixed">
<parent link="base_link" />
<!-- <child link="horizontal_laser_link" /> --> <!-- 第3处 -->
<child link="scan" />
<origin xyz="0.1007 0 0.0558" />
</joint>
<joint name="vertical_laser_link_joint" type="fixed">
<parent link="base_link" />
<child link="vertical_laser_link" />
<origin rpy="0 -1.570796 3.141593" xyz="0.1007 0 0.1814" />
</joint>
</robot>
五、效果,能正常显示tf的变化
运行命令
cd 自己工作空间
catkin_make_isolated --install --use-ninja//修改配置需要编译一次
source install_isolated/setup.bash
roslaunch cartographer_ros demo_backpack_2d.launch
rosbag play --clock XXX.bag
