手持激光,并用cartographer建图,保存的地图是.pbstream格式
rosservice call /finish_trajectory 0
rosservice call /write_state "{filename: '${HOME}/Downloads/carto_map.pbstream'}"
再执行下一步保存:
rosrun cartographer_ros cartographer_pbstream_to_ros_map -map_filestem=${HOME}/Downloads/carto_map -pbstream_filename=${HOME}/Downloads/carto_map.pbstream -resolution=0.02
得到三个文件:carto_map.pbstream、ros_map.pgm、ros_map.yaml
保存过程中出错
F1026 14:24:18.092201 35231 image.cc:55] Check failed: cairo_image_surface_get_format(surface.get()) == kCairoFormat (-1 vs. 0) *** Check failure stack trace: *** @ 0x7f62aa5af1c3 google::LogMessage::Fail() @ 0x7f62aa5b425b google::LogMessage::SendToLog() @ 0x7f62aa5aeebf google::LogMessage::Flush() @ 0x7f62aa5af6ef google::LogMessageFatal::~LogMessageFatal() @ 0x560fd890c9a2 cartographer::io::Image::Image() @ 0x560fd890b636 cartographer_ros::(anonymous namespace)::Run() @ 0x560fd890a3cd main @ 0x7f62a9be70b3 __libc_start_main @ 0x560fd890b39e _start Aborted (core dumped)
这是因为还没有生成子地图,建议机器人再走动几步,生成子地图后再保存。
建图的过程
1、修改配置
参数文件:src/cartographer_ros/cartographer_ros/configuration_files/revo_lds.lua;其中修改的地方有: tracking_frame = "laser", published_frame = "laser", use_odometry = false
include "map_builder.lua" include "trajectory_builder.lua" options = { map_builder = MAP_BUILDER, trajectory_builder = TRAJECTORY_BUILDER, map_frame = "map", tracking_frame = "laser", published_frame = "laser", odom_frame = "odom", provide_odom_frame = true, publish_frame_projected_to_2d = false, use_pose_extrapolator = true, use_odometry = false, use_nav_sat = false, use_landmarks = 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., fixed_frame_pose_sampling_ratio = 1., imu_sampling_ratio = 1., landmarks_sampling_ratio = 1., } MAP_BUILDER.use_trajectory_builder_2d = true TRAJECTORY_BUILDER_2D.submaps.num_range_data = 35 TRAJECTORY_BUILDER_2D.min_range = 0.3 TRAJECTORY_BUILDER_2D.max_range = 8. 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
注意:修改完配置文件,需要重新编译;
catkin_make -DCATKIN_WHITELIST_PACKAGES=cartographer_ros
启动文件:src/cartographer_ros/cartographer_ros/launch/rplidar_demo_revo_lds.launch;这里要修改的是<param name="/use_sim_time" value="false" /> ,<remap from="scan" to="scan" />
<launch> <param name="/use_sim_time" value="false" /> <node name="cartographer_node" pkg="cartographer_ros" type="cartographer_node" args=" -configuration_directory $(find cartographer_ros)/configuration_files -configuration_basename revo_lds.lua" output="screen"> <remap from="scan" to="scan" /> </node> <node name="rviz" pkg="rviz" type="rviz" required="true" args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" /> </launch>