Tinymal-B感知教程3-基于Cartographer SLAM的2D雷达导航

本教程基于ROS Melodic自带的Cartographer SLAM算法完成2D雷达与四足机器人里程计结合的建图与导航

总体采用Cartographer相比Gmapping等具有更好的导航稳定性,但是需要自行增加启动的位置估计发布,修改代码!
基于hector SLAM如果机器人里程计够准同时不出现较大的摔倒或打滑现象时其可以建立角好的地图,但相比小车足式机器人本身机体扰动较大,由于我们没有建立地面相关感知信息,如踩踏到相关物体出现导航导致的里程计错误测量有可能会引起地图错误,特别是我们仅采用2D雷达其十分容易受到姿态倾斜的影响。Cartographer是Google开源的高性能导航算法,除了2D雷达外还可以支持3D雷达建图,同时引入GPS或二维码地标等信息,犹记得其刚开源的时候我仅用单一雷达进行建图测试其效果非常惊艳,不但能有效克服姿态倾斜带来的影响,同时地图效果和回环精度也非常不错。
默认的系统镜像中在安装ROS-Melodic时已经预装好了Cartographer SLAM算法,但是其版本较老这有利也有弊,好处是我们仅仅修改launch就可以直接运行,坏处是没法修改源码,例如想实现纯定位来说Cartographer 原始不支持向Hector一样发布2D位置估计来初始化,需要修改源码来实现,但对于简单的学习或应用来说,我们先尝试原始版本即可,首先在robot_navigation包中搜索Cartographer.launch,将使用仿真默认设置为false,其导航配置参数再同目录下的config文件夹中:
启动雷达和导航等节点:
roslaunch robot_navigation robot_lidar.launch roslaunch robot_navigation cartographer.launch roslaunch robot_vslam move_base.launch planner:=teb move_forward_only:=false roslaunch robot_navigation multi_navigation.launch

建立好地图后如果需要保存Cartographer可以载入的先验地图需要使用如下指令:

rosservice call /write_state "filename: '/home/bingda/catkin_ws/src/robot_navigation/maps/home1.pbstream'"
之后在节点启动下发加入对应文件名:
<!-- cartographer_node --> <node name="cartographer_node" pkg="cartographer_ros" type="cartographer_node" args=" -configuration_directory $(find robot_navigation)/config -configuration_basename revo_lds_$(arg version)_navigation.lua -load_state_filename /home/bingda/catkin_ws/src/robot_navigation/maps/home1.pbstream" output="screen"> </node>
同时,在配置文件中增加TRAJECTORY_BUILDER.pure_localization = true即可实现纯定位和增量地图建立,定位工作模式下,默认机器人的起点位姿位map坐标系原点位姿,如果机器人实际放置在一个固定的起始点,且此点不在map系原点,需要修改源码才可以像move_base中的amcl模块一样,通过订阅/initialpose话题达到修正定位结果,因此对于简单测试使用我建议可以在固定场景下建立一个机器人标准启动位置,用胶带标准,之后采用Cartographer进行建图,保存地图,然后每次使用是首先将机器人放置在起始位置再载入地图即可,如果觉得这样的方法比较麻烦那可以用map server保存Cartographer建立的地图,然后参考我们之前教程2所使用的方法使用amcl定位与发布初始位置估计结果,至于导航和任务下达与教程2一致。
机器人默认启动位置,载入地图后纯定位导航,这样才有多任务路点发布具有固定的map坐标系

则最后纯导航下的launch为:

<!-- 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> <arg name="simulation" default= "false"/> <arg name="version" default="$(env ROS_DISTRO)"/> <param name="/use_sim_time" value="$(arg simulation)" /> <arg name="map_file" default="$(find robot_navigation)/maps/home1.yaml"/> <!-- cartographer_node --> <node name="cartographer_node" pkg="cartographer_ros" type="cartographer_node" args=" -configuration_directory $(find robot_navigation)/config -configuration_basename revo_lds_$(arg version)_navigation.lua -load_state_filename /home/bingda/catkin_ws/src/robot_navigation/maps/home2.pbstream" output="screen"> </node> <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros" type="cartographer_occupancy_grid_node" args="-resolution 0.05" /> </launch>
配置文件为:
-- 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 = "base_laser_link", -- published_frame = "base_laser_link", -- odom_frame = "odom", -- provide_odom_frame = true, -- use_odometry = false, tracking_frame = "base_footprint", 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., } MAP_BUILDER.use_trajectory_builder_2d = true TRAJECTORY_BUILDER.pure_localization = true TRAJECTORY_BUILDER_2D.submaps.num_range_data = 35 TRAJECTORY_BUILDER_2D.min_range = 0.1 TRAJECTORY_BUILDER_2D.max_range = 4. 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 = 20 POSE_GRAPH.constraint_builder.min_score = 0.65 return options
则将机器人放置到初始为止后启动:
roslaunch robot_navigation robot_lidar.launch roslaunch robot_navigation cartographer_navigation.launch roslaunch robot_vslam move_base.launch planner:=teb move_forward_only:=false roslaunch robot_navigation multi_navigation.launch
2023-02-18