1. APT安装功能包
1、大部分的功能包是可以通过apt安装的,局部的采用源码克隆
# 四种 SLAM
sudo apt install ros-noetic-gmapping -y
sudo apt install ros-noetic-hector-slam -y
sudo apt install ros-noetic-cartographer-ros -y
# 试试 Karto 是否能 apt 装
sudo apt install ros-noetic-slam-karto ros-noetic-open-karto -y
# 安装导航的功能包
sudo apt install ros-noetic-navigation -y
# 这个包里包含了你需要的一切:move_base、amcl、map_server、global_planner(包含 Dijkstra 和 A*)、costmap_2d 等。
2、这里ros-noetic-cartographer-ros是安装不成功的,ros-noetic-cartographer-ros没有官方的deb功能包,Google 停止维护后,Cartographer 没有被编译进 Noetic 的官方仓库。你搜 apt-cache search cartographer 为空也证实了这一点。
3、源码编译ros-noetic-cartographer-ros:
# 安装 Cartographer 的系统依赖
# 编译工具
sudo apt install ninja-build -y
# Cartographer 的核心依赖
sudo apt install libceres-dev libprotobuf-dev protobuf-compiler \
libgflags-dev libgoogle-glog-dev liblua5.3-dev \
libboost-dev -y
# 记住这个版本号,后面如果有版本冲突会用到
protoc --version
# 安装 abseil-cpp
# Cartographer 依赖 abseil-cpp,Ubuntu 20.04 没有这个库,必须源码安装:
cd /tmp
git clone https://github.com/abseil/abseil-cpp.git
cd abseil-cpp
git checkout 20210324.2 # 选一个稳定的 tag,和 Noetic 时代匹配
mkdir build && cd build
cmake -G Ninja \
-DCMAKE_BUILD_TYPE=Release \
-DCMAKE_POSITION_INDEPENDENT_CODE=ON \
-DCMAKE_INSTALL_PREFIX=/usr/local ..
sudo ninja install
ls /usr/local/include/absl
# 应该看到 base, container, hash, strings, types 等子目录
# 克隆 Cartographer 源码
cd ~/slam_compare_ws/src
# Cartographer 核心 C++ 库
git clone --depth 1 https://github.com/cartographer-project/cartographer.git
# Cartographer 的 ROS 封装
git clone --depth 1 https://github.com/cartographer-project/cartographer_ros.git
# 确定目录结构
ls -d */ | sort
# 如下所示:
cartographer/
cartographer_ros/
slam_compare/
# 清理旧的编译产物 + 重新编译
# 先清理之前 catkin_make 生成的 build 和 devel 目录
cd ~/slam_compare_ws
rm -rf build devel
# 用隔离模式重新编译(兼容 Cartographer 的纯 CMake 构建)
catkin_make_isolated --install --use-ninja
编译 Cartographer 比较耗时,可能需要 3~10 分钟,取决于你的机器。中途如果出现编译错误,不要中断,等它全部跑完再看哪些包失败了。
# 更新环境变量
之前 catkin_make 生成的是 devel/setup.bash,现在 catkin_make_isolated 生成的是 devel_isolated/setup.bash,需要更新:
# 旧的(删掉或注释掉)
# source ~/slam_compare_ws/devel/setup.bash
# 改成:
source ~/slam_compare_ws/devel_isolated/setup.bash
# 最终验证:
xk@ubuntu:~$ echo "=== SLAM 四件套 ==="
=== SLAM 四件套 ===
xk@ubuntu:~$ rospack find gmapping
/opt/ros/noetic/share/gmapping
xk@ubuntu:~$ rospack find hector_mapping
/opt/ros/noetic/share/hector_mapping
xk@ubuntu:~$ rospack find slam_karto
/opt/ros/noetic/share/slam_karto
xk@ubuntu:~$ rospack find cartographer_ros
/home/xk/slam_compare_ws/install_isolated/share/cartographer_ros
xk@ubuntu:~$ echo "=== 导航 ==="
=== 导航 ===
xk@ubuntu:~$ rospack find move_base
/opt/ros/noetic/share/move_base
xk@ubuntu:~$ rospack find global_planner
/opt/ros/noetic/share/global_planner
xk@ubuntu:~$ rospack find amcl
/opt/ros/noetic/share/amcl
xk@ubuntu:~$ rospack find map_server
/opt/ros/noetic/share/map_server
xk@ubuntu:~$ echo "=== 你自己的包 ==="
=== 你自己的包 ===
xk@ubuntu:~$ rospack find slam_compare
/home/xk/slam_compare_ws/src/slam_compare
xk@ubuntu:~$
全部输出路径就是正常的了
2、创建自己的工作区间
1、创建一个自己的功能包用来集成仿真和启动及参数文件
# 创建工作空间骨架
mkdir -p ~/slam_compare_ws/src
cd ~/slam_compare_ws/src
# 初始化工作空间并创建自己的功能包
catkin_create_pkg slam_compare rospy std_msgs nav_msgs geometry_msgs sensor_msgs
以下是对功能包的目录结构进行解读
slam_compare/
├── CMakeLists.txt # 已自动生成
├── package.xml # 已自动生成
├── launch/ # 后续放 launch 文件
│ ├── env_world.launch # Gazebo 加载你的场景
│ ├── karto.launch # Karto 建图(因为 turtlebot3_slam 没集成 karto)
│ ├── nav_dijkstra.launch # Dijkstra 导航
│ └── nav_astar.launch # A* 导航
├── config/ # 后续放配置文件
│ ├── dwa_local_planner_params.yaml
│ ├── costmap_common_params.yaml
│ └── ...
├── maps/ # 存储建图结果
└── scripts/ # 后续放脚本
3、Gazebo仿真Burger小车实验
1、创建启动文件
# 在你的包里建 worlds 和 launch 目录
mkdir -p ~/slam_compare_ws/src/slam_compare/worlds
mkdir -p ~/slam_compare_ws/src/slam_compare/launch
# 把你的场景复制进来(用绝对路径确保找到你的文件)
cp ~/env.world ~/slam_compare_ws/src/slam_compare/worlds/
# 编写 launch 文件
gedit slam_compare_ws/src/slam_compare/launch/env_world.launch
# 然后填写以下文件内容
<launch>
<!-- TurtleBot3 模型:从环境变量读取,默认 burger -->
<arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
<arg name="x_pos" default="0.0"/>
<arg name="y_pos" default="0.0"/>
<arg name="z_pos" default="0.0"/>
<arg name="yaw" default="1.5708"/>
<!-- 使用仿真时间(Gazebo 的时钟,不是系统时钟) -->
<param name="/use_sim_time" value="true"/>
<!-- 启动 Gazebo,加载你的 env.world -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find slam_compare)/worlds/env.world"/>
<arg name="paused" value="false"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="true"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
</include>
<!-- 加载 URDF 参数(xacro 解析) -->
<param name="robot_description"
command="$(find xacro)/xacro '$(find turtlebot3_description)/urdf/turtlebot3_$(arg model).urdf.xacro'"/>
<!-- 在 Gazebo 中生成小车模型 -->
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model"
args="-x $(arg x_pos) -y $(arg y_pos) -z $(arg z_pos) -Y $(arg yaw)
-urdf -model turtlebot3_$(arg model) -param robot_description"
output="screen"/>
<!-- 发布 TF:base_link 等各关节的坐标变换 -->
<node pkg="robot_state_publisher" type="robot_state_publisher"
name="robot_state_publisher" output="screen">
<param name="publish_frequency" type="double" value="50.0"/>
</node>
</launch>

4、RViz 联调,验证激光数据和 TF
1、保持Gazebo运行,直接在终端输入rviz来运行
2、在RVIZ中,添加可视化插件:
1>现将正上方的Fix全局坐标改成odom,这样不会出错,map目前还没有
2>在左下角add点击添加robot model、odom、scan等等

这里我进行了左上角的file选项里的另存为,在当前工作去world统计目录下创建rviz文件,然后保存到这里,接着在env_world.launch文件中添加rviz的启动项,如下所示:

位置在结尾上方就行,内容如图片所示。
5、四种SLAM算法建图实验
5.1 Gmapping
启动建图程序:
bash
roslaunch slam_compare slam_gmapping.launch
# 后续三个算法启动流程一样,仅仅更换文件名字,自动运行Gazebo和rviz


bash
# 创建文件夹并保存地图文件
mkdir -p ~/slam_compare_ws/maps
rosrun map_server map_saver -f ~/slam_compare_ws/maps/gmapping_map
查看.npm文件

5.2 Hector

5.3 Cartographer


5.4 Karto
1、Karto官方的apt安装时没有可执行文件,所以也不会有map话题,无法直接进行建图,需要进行从源码编译,这里可参考https://github.com/ros-perception/slam_karto.git源码
2、安装依赖与验证
bash
# 安装缺少的依赖
sudo apt install ros-noetic-open-karto ros-noetic-sparse-bundle-adjustment
# 创建工作空间
mkdir -p ~/slam_karto_ws/src
cd ~/slam_karto_ws/src
# 先把现有的 slam_karto apt 包移除,避免冲突
sudo apt remove ros-noetic-slam-karto
# 下载源码
git clone https://github.com/ros-perception/slam_karto.git -b melodic-devel
# 编译
cd ~/slam_karto_ws
catkin_make
# source 环境
echo "source ~/slam_karto_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc
# 验证
rospack find slam_karto
ls /home/xk/slam_karto_ws/devel/lib/slam_karto/
# 会发现一个绿色的可执行文件
3、启动仿真

4、查看.npm文件

总结:
xk@ubuntu:~$ ls -lh ~/slam_compare_ws/src/slam_compare/maps/
总用量 4.3M
-rw-rw-r-- 1 xk xk 29K 5月 20 20:18 cartographer_map.pgm
-rw-rw-r-- 1 xk xk 189 5月 20 20:18 cartographer_map.yaml
-rw-rw-r-- 1 xk xk 145K 5月 20 08:09 gmapping_map.pgm
-rw-rw-r-- 1 xk xk 187 5月 20 08:09 gmapping_map.yaml
-rw-rw-r-- 1 xk xk 4.1M 5月 20 19:52 hector_map.pgm
-rw-rw-r-- 1 xk xk 185 5月 20 19:52 hector_map.yaml
-rw-rw-r-- 1 xk xk 25K 5月 20 21:24 karto_map.pgm
-rw-rw-r-- 1 xk xk 181 5月 20 21:28 karto_map.yaml
xk@ubuntu:~$

6. Dijkstra与A*导航对比试验
6.1 全局参数的配置
bash
# TurtleBot3 burger 的代价地图通用参数
obstacle_range: 3.0
raytrace_range: 3.5
# burger 的外形尺寸(正方形近似,单位:米)
footprint: [[-0.105, -0.105], [-0.105, 0.105], [0.105, 0.105], [0.105, -0.105]]
# 膨胀层:障碍物周围的代价衰减区域
inflation:
inflation_radius: 0.4 # 膨胀半径,比机器人大一圈
cost_scaling_factor: 5.0 # 代价衰减速率
# 障碍物数据来源
observation_sources: scan
scan:
sensor_frame: base_scan
data_type: LaserScan
topic: scan
marking: true
clearing: true
min_obstacle_height: 0.05
max_obstacle_height: 0.35
bash
# 这个是全局代价地图的参数配置文件
global_costmap:
global_frame: map
robot_base_frame: base_footprint
update_frequency: 2.0
publish_frequency: 1.0
static_map: true
rolling_window: false
resolution: 0.05
transform_tolerance: 0.5
6.2 Dijkstra导航配置
1、Dijkstra的全局规划器的配置参数
bash
# GlobalPlanner 参数:Dijkstra 模式
GlobalPlanner:
use_dijkstra: true
use_grid_path: false
visualize_potential: false
allow_unknown: false
default_tolerance: 0.5
lethal_cost: 253
2、Dijkstra的导航启动仿真文件
bash
<launch>
<!-- ========== 加载地图 ========== -->
<node name="map_server" pkg="map_server" type="map_server"
args="/home/xk/slam_compare_ws/src/slam_compare/maps/cartographer_map.yaml" output="screen"/>
<!-- ========== AMCL 定位 ========== -->
<node pkg="amcl" type="amcl" name="amcl" output="screen">
<param name="use_map_topic" value="true"/>
<param name="odom_model_type" value="diff"/>
<param name="odom_alpha1" value="0.2"/>
<param name="odom_alpha2" value="0.2"/>
<param name="odom_alpha3" value="0.2"/>
<param name="odom_alpha4" value="0.2"/>
<param name="base_frame_id" value="base_footprint"/>
<param name="odom_frame_id" value="odom"/>
<param name="global_frame_id" value="map"/>
<param name="laser_max_beams" value="60"/>
<param name="laser_max_range" value="3.5"/>
<param name="min_particles" value="500"/>
<param name="max_particles" value="5000"/>
<param name="kld_err" value="0.02"/>
<param name="kld_z" value="0.99"/>
<param name="laser_z_hit" value="0.95"/>
<param name="laser_z_short" value="0.05"/>
<param name="laser_z_max" value="0.05"/>
<param name="laser_z_rand" value="0.05"/>
<param name="laser_sigma_hit" value="0.2"/>
<param name="laser_lambda_short" value="0.1"/>
<param name="laser_model_type" value="likelihood_field"/>
<param name="laser_likelihood_max_dist" value="2.0"/>
<param name="update_min_d" value="0.1"/>
<param name="update_min_a" value="0.5"/>
<param name="resample_interval" value="1"/>
<param name="transform_tolerance" value="0.5"/>
<param name="recovery_alpha_slow" value="0.0"/>
<param name="recovery_alpha_fast" value="0.0"/>
<param name="initial_pose_x" value="0.0"/>
<param name="initial_pose_y" value="0.0"/>
<param name="initial_pose_a" value="0.0"/>
</node>
<!-- ========== move_base ========== -->
<node pkg="move_base" type="move_base" name="move_base" output="screen" respawn="false">
<!-- 关闭恢复行为 -->
<param name="recovery_behavior_enabled" value="false"/>
<!-- 全局代价地图 -->
<rosparam file="$(find slam_compare)/config/costmap_common_params.yaml" command="load" ns="global_costmap"/>
<rosparam file="$(find slam_compare)/config/global_costmap_params.yaml" command="load"/>
<!-- 全局规划器:Dijkstra -->
<param name="base_global_planner" value="global_planner/GlobalPlanner"/>
<rosparam file="$(find slam_compare)/config/global_planner_dijkstra.yaml" command="load"/>
<!-- 局部规划器:用最简单的,纯跟随路径,不做避障 -->
<param name="base_local_planner" value="base_local_planner/TrajectoryPlannerROS"/>
<param name="TrajectoryPlannerROS/max_vel_x" value="0.22"/>
<param name="TrajectoryPlannerROS/min_vel_x" value="0.05"/>
<param name="TrajectoryPlannerROS/max_vel_theta" value="1.5"/>
<param name="TrajectoryPlannerROS/min_vel_theta" value="-1.5"/>
<param name="TrajectoryPlannerROS/min_in_place_vel_theta" value="0.3"/>
<param name="TrajectoryPlannerROS/acc_lim_x" value="2.0"/>
<param name="TrajectoryPlannerROS/acc_lim_theta" value="2.5"/>
<param name="TrajectoryPlannerROS/xy_goal_tolerance" value="0.15"/>
<param name="TrajectoryPlannerROS/yaw_goal_tolerance" value="0.1"/>
<param name="TrajectoryPlannerROS/path_distance_bias" value="0.8"/>
<param name="TrajectoryPlannerROS/goal_distance_bias" value="0.4"/>
<param name="TrajectoryPlannerROS/occdist_scale" value="0.0"/>
<!-- 局部代价地图:最小化 -->
<param name="local_costmap/global_frame" value="odom"/>
<param name="local_costmap/robot_base_frame" value="base_footprint"/>
<param name="local_costmap/update_frequency" value="2.0"/>
<param name="local_costmap/static_map" value="false"/>
<param name="local_costmap/rolling_window" value="true"/>
<param name="local_costmap/width" value="3.0"/>
<param name="local_costmap/height" value="3.0"/>
<param name="local_costmap/resolution" value="0.05"/>
</node>
<!-- ========== RViz ========== -->
<node pkg="rviz" type="rviz" name="rviz"
args="-d $(find turtlebot3_navigation)/rviz/turtlebot3_navigation.rviz"/>
</launch>
6.3 A*导航配置
1、A*的导航参数配置文件:
bash
# GlobalPlanner 参数:A* 模式
GlobalPlanner:
use_dijkstra: false
use_grid_path: false
visualize_potential: false
allow_unknown: false
default_tolerance: 0.5
lethal_cost: 253
2、启动文件:
bash
<launch>
<!-- ========== 加载地图 ========== -->
<node name="map_server" pkg="map_server" type="map_server"
args="/home/xk/slam_compare_ws/src/slam_compare/maps/cartographer_map.yaml" output="screen"/>
<!-- ========== AMCL 定位 ========== -->
<node pkg="amcl" type="amcl" name="amcl" output="screen">
<param name="use_map_topic" value="true"/>
<param name="odom_model_type" value="diff"/>
<param name="odom_alpha1" value="0.2"/>
<param name="odom_alpha2" value="0.2"/>
<param name="odom_alpha3" value="0.2"/>
<param name="odom_alpha4" value="0.2"/>
<param name="base_frame_id" value="base_footprint"/>
<param name="odom_frame_id" value="odom"/>
<param name="global_frame_id" value="map"/>
<param name="laser_max_beams" value="60"/>
<param name="laser_max_range" value="3.5"/>
<param name="min_particles" value="500"/>
<param name="max_particles" value="5000"/>
<param name="kld_err" value="0.02"/>
<param name="kld_z" value="0.99"/>
<param name="laser_z_hit" value="0.95"/>
<param name="laser_z_short" value="0.05"/>
<param name="laser_z_max" value="0.05"/>
<param name="laser_z_rand" value="0.05"/>
<param name="laser_sigma_hit" value="0.2"/>
<param name="laser_lambda_short" value="0.1"/>
<param name="laser_model_type" value="likelihood_field"/>
<param name="laser_likelihood_max_dist" value="2.0"/>
<param name="update_min_d" value="0.1"/>
<param name="update_min_a" value="0.5"/>
<param name="resample_interval" value="1"/>
<param name="transform_tolerance" value="0.5"/>
<param name="recovery_alpha_slow" value="0.0"/>
<param name="recovery_alpha_fast" value="0.0"/>
<param name="initial_pose_x" value="0.0"/>
<param name="initial_pose_y" value="0.0"/>
<param name="initial_pose_a" value="0.0"/>
</node>
<!-- ========== move_base ========== -->
<node pkg="move_base" type="move_base" name="move_base" output="screen" respawn="false">
<!-- 关闭恢复行为 -->
<param name="recovery_behavior_enabled" value="false"/>
<!-- 全局代价地图 -->
<rosparam file="$(find slam_compare)/config/costmap_common_params.yaml" command="load" ns="global_costmap"/>
<rosparam file="$(find slam_compare)/config/global_costmap_params.yaml" command="load"/>
<!-- 全局规划器:Dijkstra -->
<param name="base_global_planner" value="global_planner/GlobalPlanner"/>
<rosparam file="$(find slam_compare)/config/global_planner_dijkstra.yaml" command="load"/>
<!-- 局部规划器:用最简单的,纯跟随路径,不做避障 -->
<param name="base_local_planner" value="base_local_planner/TrajectoryPlannerROS"/>
<param name="TrajectoryPlannerROS/max_vel_x" value="0.22"/>
<param name="TrajectoryPlannerROS/min_vel_x" value="0.05"/>
<param name="TrajectoryPlannerROS/max_vel_theta" value="1.5"/>
<param name="TrajectoryPlannerROS/min_vel_theta" value="-1.5"/>
<param name="TrajectoryPlannerROS/min_in_place_vel_theta" value="0.3"/>
<param name="TrajectoryPlannerROS/acc_lim_x" value="2.0"/>
<param name="TrajectoryPlannerROS/acc_lim_theta" value="2.5"/>
<param name="TrajectoryPlannerROS/xy_goal_tolerance" value="0.15"/>
<param name="TrajectoryPlannerROS/yaw_goal_tolerance" value="0.1"/>
<param name="TrajectoryPlannerROS/path_distance_bias" value="0.8"/>
<param name="TrajectoryPlannerROS/goal_distance_bias" value="0.4"/>
<param name="TrajectoryPlannerROS/occdist_scale" value="0.0"/>
<!-- 局部代价地图:最小化 -->
<param name="local_costmap/global_frame" value="odom"/>
<param name="local_costmap/robot_base_frame" value="base_footprint"/>
<param name="local_costmap/update_frequency" value="2.0"/>
<param name="local_costmap/static_map" value="false"/>
<param name="local_costmap/rolling_window" value="true"/>
<param name="local_costmap/width" value="3.0"/>
<param name="local_costmap/height" value="3.0"/>
<param name="local_costmap/resolution" value="0.05"/>
</node>
<!-- ========== RViz ========== -->
<node pkg="rviz" type="rviz" name="rviz"
args="-d $(find turtlebot3_navigation)/rviz/turtlebot3_navigation.rviz"/>
</launch>
6.4 启动导航
6.4.1 Dijkstra导航
bash
# 终端1:启动 Gazebo + burger(用之前的 env_world.launch)
roslaunch slam_compare env_world.launch
# 终端2:启动导航(Dijkstra 模式)
roslaunch slam_compare nav_dijkstra.launch
6.4.2 A*导航
bash
# 终端1:启动 Gazebo + burger(用之前的 env_world.launch)
roslaunch slam_compare env_world.launch
# 终端2:启动导航(Dijkstra 模式)
roslaunch slam_compare nav_astra.launch
7. 总结
xk@ubuntu:~/slam_compare_ws$ ls src/
cartographer cartographer_ros CMakeLists.txt slam_compare
xk@ubuntu:~/slam_compare_ws$ tree src/slam_compare/
src/slam_compare/
├── CMakeLists.txt
├── config
│ ├── costmap_common_params.yaml
│ ├── global_costmap_params.yaml
│ ├── global_planner_astar.yaml
│ ├── global_planner_dijkstra.yaml
│ └── turtlebot3_2d.lua
├── launch
│ ├── env_world.launch
│ ├── nav_astar.launch
│ ├── nav_dijkstra.launch
│ ├── slam_cartographer.launch
│ ├── slam_gmapping.launch
│ ├── slam_hector.launch
│ └── slam_karto.launch
├── maps
│ ├── cartographer_map.pgm
│ ├── cartographer_map.yaml
│ ├── gmapping_map.pgm
│ ├── gmapping_map.yaml
│ ├── hector_map.pgm
│ ├── hector_map.yaml
│ ├── karto_map.pgm
│ └── karto_map.yaml
├── package.xml
├── rviz
│ └── demo.rviz
├── src
└── worlds
└── env.world
6 directories, 24 files
xk@ubuntu:~/slam_compare_ws$
文件名字与功能一一对应,可以直接参考对应的launch文件内容,但是需要做以下准备工作:
1、编译依赖安装
2、功能包安装(注意版本)
3、参数路径:如地图文件加载等
以上内容可在上述目录章节中找到,但是不局限于以上内容,可以结合AI来进行完善补充