1. 配置Cartographer
1. 源码下载编译
sudo apt-get updatesudo apt-get install -y libceres-dev libprotobuf-dev protobuf-compiler python3-wstool python3-rosdep ninja-build stow liblua5.2-dev python3-sphinx libgtest-dev libgoogle-glog-dev libgflags-dev libatlas-base-dev libeigen3-dev libsuitesparse-dev build-essential clang cmake g++ google-mock libboost-all-dev libcairo2-dev libcurl4-openssl-dev lsb-release stow libgmock-dev libmetis-devwstool init srcwstool merge -t src https://raw.githubusercontent.com/cartographer-project/cartographer_ros/master/cartographer_ros.rosinstallwstool update -t srcsudo nano /etc/ros/rosdep/sources.list.d/20-default.listrosdep updatenano src/cartographer/package.xml rosdep install --from-paths src --ignore-src --rosdistro=noetic -ysrc/cartographer/scripts/install_abseil.sh src/cartographer/scripts/install_proto3.shcatkin_make_isolated --install --use-ninjasource devel_isolated/setup.bashecho \"source ~/catkin_ws/devel_isolated/setup.bash\" >> ~/.bashrc







2. 启动建图
2.1 配置文件
touch ~/catkin_ws/src/cartographer_ros/cartographer_ros/configuration_files/turtlebot3_lds_2d.luanano ~/catkin_ws/src/cartographer_ros/cartographer_ros/configuration_files/turtlebot3_lds_2d.luacp ~/catkin_ws/src/cartographer_ros/cartographer_ros/configuration_files/turtlebot3_lds_2d.lua ~/catkin_ws/install_isolated/share/cartographer_ros/configuration_files/nano ~/catkin_ws/src/cartographer/configuration_files/map_builder.luacp ~/catkin_ws/src/cartographer/configuration_files/map_builder.lua ~/catkin_ws/install_isolated/share/cartographer/configuration_files
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 = \"odom\", odom_frame = \"odom\", provide_odom_frame = false, publish_frame_projected_to_2d = false, use_odometry = true, 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.,}TRAJECTORY_BUILDER_2D.min_range = 0.1TRAJECTORY_BUILDER_2D.max_range = 3.5TRAJECTORY_BUILDER_2D.missing_data_ray_length = 3.5TRAJECTORY_BUILDER_2D.use_imu_data = falseTRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = truePOSE_GRAPH.optimization_problem.huber_scale = 1e2POSE_GRAPH.optimize_every_n_nodes = 35return options

2.2 cartographer启动launch
touch ~/catkin_ws/src/cartographer_ros/cartographer_ros/launch/turtlebot3_cartographer.launchnano ~/catkin_ws/src/cartographer_ros/cartographer_ros/launch/turtlebot3_cartographer.launchcp ~/catkin_ws/src/cartographer_ros/cartographer_ros/launch/turtlebot3_cartographer.launch ~/catkin_ws/install_isolated/share/cartographer_ros/launch
<launch> <param name=\"/use_sim_time\" value=\"true\" /> <env name=\"CARTOGRAPHER_CONFIGURATION_DIRECTORY\" value=\"$(find cartographer_ros)/configuration_files;$(find cartographer)/configuration_files\" /> <node name=\"cartographer_node\" pkg=\"cartographer_ros\" type=\"cartographer_node\" args=\" -configuration_directory $(find cartographer_ros)/configuration_files -configuration_basename turtlebot3_lds_2d.lua\" output=\"screen\"> <remap from=\"scan\" to=\"/scan\" /> <remap from=\"odom\" to=\"/odom\" /> </node> <node name=\"cartographer_occupancy_grid_node\" pkg=\"cartographer_ros\" type=\"cartographer_occupancy_grid_node\" args=\"-resolution 0.05\" /> <node pkg=\"tf\" type=\"static_transform_publisher\" name=\"base_link_to_base_scan\" args=\"0.0 0.0 0.0 0.0 0.0 0.0 base_link base_scan 100\" /> <node pkg=\"tf\" type=\"static_transform_publisher\" name=\"map_to_odom\" args=\"0.0 0.0 0.0 0.0 0.0 0.0 map odom 100\" /> <node pkg=\"tf\" type=\"static_transform_publisher\" name=\"base_footprint_to_base\" args=\"0.0 0.0 0.0 0.0 0.0 0.0 base_footprint base_link 100\" /></launch>
2.3 Turtlebot3启动launch
touch ~/catkin_ws/src/turtlebot3/turtlebot3_slam/launch/turtlebot3_carto_demo.launchnano ~/catkin_ws/src/turtlebot3/turtlebot3_slam/launch/turtlebot3_carto_demo.launchcp ~/catkin_ws/src/turtlebot3/turtlebot3_slam/launch/turtlebot3_carto_demo.launch ~/catkin_ws/install_isolated/share/turtlebot3_slam/launch
<launch> <include file=\"$(find turtlebot3_gazebo)/launch/turtlebot3_house.launch\" /> <include file=\"$(find cartographer_ros)/launch/turtlebot3_cartographer.launch\" /> <node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find turtlebot3_slam)/rviz/turtlebot3_cartographer.rviz\"/></launch>


2.4 执行建图
source ~/catkin_ws/devel_isolated/setup.bashexport TURTLEBOT3_MODEL=waffle_piroslaunch turtlebot3_slam turtlebot3_carto_demo.launchrosrun turtlebot3_teleop turtlebot3_teleop_key





3. 保存地图
rosrun map_server map_saver -f ./maps/carto_map


image: ./maps/carto_map.pgmresolution: 0.050000origin: [-4.767262, -5.126551, 0.000000]negate: 0occupied_thresh: 0.65free_thresh: 0.196
4. 调试
rostopic echo /odom

rostopic echo /map

rosrun tf tf_echo map base_link
