Cartographer学习系列之二: 使用 EAI YDLIDAR 实现 Cartographer 2d slam

内容目录
  1. 安装Cartographer

  2. 安装turtlebot_apps

$ cd   ~/slam_ws/src
# turtlebot建图依赖包
$ git clone https://github.com/turtlebot/turtlebot_apps 

#编译
$ cd  ~/slam_ws
$ catkin_make_isolated --install --use-ninja
  1. 安装YDLIDAR 驱动

  2. 修改YDLIDAR 驱动 中的lidar.lanch文件
    修改lidar.lanch文件为如下:

<launch>
  <node name="ydlidar_node"  pkg="ydlidar"  type="ydlidar_node" output="screen">
    <param name="port"         type="string" value="/dev/ydlidar"/>  
    <param name="baudrate"     type="int"    value="115200"/>
    <!--param name="frame_id"     type="string" value="base_laser"/> -->
    <param name="frame_id"     type="string" value="laser"/> 
    <param name="angle_fixed"  type="bool"   value="true"/>
    <param name="low_exposure"  type="bool"   value="false"/>
    <param name="heartbeat"    type="bool"   value="false"/>
    <param name="resolution_fixed"    type="bool"   value="true"/>
    <param name="angle_min"    type="double" value="-180" />
    <param name="angle_max"    type="double" value="180" />
    <param name="range_min"    type="double" value="0.08" />
    <param name="range_max"    type="double" value="16.0" />
    <param name="ignore_array" type="string" value="" />
    <param name="samp_rate"    type="int"    value="9"/>
    <param name="frequency"    type="double" value="15"/>
  </node>
  <node pkg="tf" type="static_transform_publisher" name="base_to_laser" args="0.0 0.0 0.18 0 0.0 0.0 base_link laser 100"/>
  <!--node pkg="tf" type="static_transform_publisher" name="base_link_to_laser4"
    args="0.2245 0.0 1.5 0.0 0.0  0.0 /base_link /laser_frame 40" /> -->
     <node pkg="tf" type="static_transform_publisher" name="base_link_to_laser4"
    args="0.2245 0.0 1.5 0.0 0.0  0.0 /base_link /base_laser 40" />  
</launch>

然后拷贝出来

$ roscd turtlebot_navigation
$ mkdir -p laser/driver
$ sudo cp ~/slam_ws/src/ydlidar/launch/lidar.launch laser/driver/lidar.launch

接着重新编译

$ cd ~/slam_ws
$ catkin_make_isolated --install --use-ninja
  1. 修改revo_lds_.lua
    修改位于/catkin_ws/src/cartographer_ros/cartographer_ros/configuration_files 文件夹下的第22 和 23 行。
-- Copyright 2016 The Cartographer Authors
--
-- Licensed under the Apache License, Version 2.0 (the "License");
-- you may not use this file except in compliance with the License.
-- You may obtain a copy of the License at
--
--      http://www.apache.org/licenses/LICENSE-2.0
--
-- Unless required by applicable law or agreed to in writing, software
-- distributed under the License is distributed on an "AS IS" BASIS,
-- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-- See the License for the specific language governing permissions and
-- limitations under the License.

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,
  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.submaps.num_range_data = 35
TRAJECTORY_BUILDER_2D.min_range = 0.08
TRAJECTORY_BUILDER_2D.max_range = 16.
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
  1. 修改demo_revo_lds.launch
    位于~/slam_ws/src/cartographer_ros/cartographer_ros/launch 文件夹下,注意 23 和 25 行。
    主要修改两个地方, 这一句后面的 horizontal_laser_2d 改成 scan ;最后的 playbag 节点删掉。
<!--
  Copyright 2016 The Cartographer Authors

  Licensed under the Apache License, Version 2.0 (the "License");
  you may not use this file except in compliance with the License.
  You may obtain a copy of the License at

       http://www.apache.org/licenses/LICENSE-2.0

  Unless required by applicable law or agreed to in writing, software
  distributed under the License is distributed on an "AS IS" BASIS,
  WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  See the License for the specific language governing permissions and
  limitations under the License.
-->

<launch>
  <param name="/use_sim_time" value="true" />

  <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="cartographer_occupancy_grid_node" pkg="cartographer_ros"
      type="cartographer_occupancy_grid_node" args="-resolution 0.05" />

  <node name="rviz" pkg="rviz" type="rviz" required="true"
      args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />

</launch>

7.重新编译

nvidia@nvidia:~$ cd ~/slam_ws/
nvidia@nvidia:~/slam_ws$ catkin_make_isolated --install --use-ninja

8.开启两个窗口,分别运行如下指令:

roslaunch ydlidar lidar.launch
 roslaunch cartographer_ros demo_revo_lds.launch

9.保存地图

#新建map文件夹用于保存地图
$ mkdir -p ~/map
#启动存图,并将名为lidar_2d的地图文件保存在map文件夹
$ rosrun map_server map_saver -f ~/map/lidar_2d
#查看内容,包含lidar_2d.pgm  lidar_2d.yaml
$ ls ~/map 

10.效果

11.参考链接
使用Turtlebot 2和Rplidar A2实现Cartographer

TX2使用Rplidar A2实现Cartographer

打赏作者