turtlebot3-burger_150.png
turtlebot3-waffle-pi_150.png
turtlebot3-arm_150.png
walking-y2_150.png
turbot3-multi_150.png
turbot3-dl-ros1_150.png
turbot3-ai.png
turbot3-dl-ros2_150.png
turbot3-slam_150.png
turbot3-arm_150.png
turtlebot4-lite_150.png
turtlebot4-pro_150.png
turbot4-dl_150.png
turbot4-ai_150.png
aidriving-racebot_150.png
aidriving-autodrive_150.png
turtlebot-arm_150.png
openmanipulator-x_150.png
Home » ROS2与Turtlebot3仿真 » ros2与turtlebot3仿真教程-使用rtabmap建图

ros2与turtlebot3仿真教程-使用rtabmap建图

纠错,疑问,交流: 请进入讨论区请点击进入页面,扫码加入微信群或Q群进行交流

获取最新文章: 扫一扫加入“创客智造”公众号

说明

  • 介绍如何利用turtlebot3的gazebo仿真实现rtabmap建图
  • 测试环境: ros2 humble + rtabmap

步骤

sudo apt install ros-$ROS_DISTRO-rtabmap-ros
  • 复制命令到终端即可安装

配置

  • 安装完成后,还需要配置使用深度相机,更改模型,地址位于
~/ros2_tb3_sim_ws/src/turtlebot3_gazebo/models/turtlebot3_waffle/model.sdf
  • 修改内容步骤为:
#   Modify turtlebot3_waffle SDF:
#     1) Edit /opt/ros/$ROS_DISTRO/share/turtlebot3_gazebo/models/turtlebot3_waffle/model.sdf
#     2) Add
#          <joint name="camera_rgb_optical_joint" type="fixed">
#            <parent>camera_rgb_frame</parent>
#            <child>camera_rgb_optical_frame</child>
#            <pose>0 0 0 -1.57079632679 0 -1.57079632679</pose>
#            <axis>
#              <xyz>0 0 1</xyz>
#            </axis>
#          </joint> 
#     3) Rename <link name="camera_rgb_frame"> to <link name="camera_rgb_optical_frame">
#     4) Add <link name="camera_rgb_frame"/>
#     5) Change <sensor name="camera" type="camera"> to <sensor name="camera" type="depth">
#     6) Change image width/height from 1920x1080 to 640x480
#     7) Note that we can increase min scan range from 0.12 to 0.2 to avoid having scans 
#        hitting the robot itself
  • 已经修改的内容如下,可以对比之前的model.sdf
<link name="camera_link"/>
0.069 -0.047 0.107 0 0 0 0.001 0.000 0.000 0.001 0.000 0.001 0.035

0.069 -0.047 0.107 0 0 0

true true 30 1.02974 640 480 R8G8B8 0.02 300 gaussian 0.0 0.007 camera_rgb_frame camera_rgb_optical_frame 0 0 0 -1.57079632679 0 -1.57079632679 0 0 1 base_footprint base_link 0.0 0.0 0.010 0 0 0 base_link wheel_left_link 0.0 0.144 0.023 -1.57 0 0 0 0 1 base_link wheel_right_link 0.0 -0.144 0.023 -1.57 0 0 0 0 1 base_link caster_back_right_link base_link caster_back_left_link base_link imu_link -0.032 0 0.068 0 0 0 0 0 1 base_link base_scan -0.064 0 0.121 0 0 0 0 0 1 base_link camera_link 0.064 -0.065 0.094 0 0 0 0 0 1 camera_link camera_rgb_optical_frame 0.005 0.018 0.013 0 0 0 0 0 1 `` ``

测试

  • 启动gazebo
ros2 launch turtlebot3_gazebo turtlebot3_world.launch.py
  • 效果图

请输入图片描述

  • 启动rtabmap
ros2 launch rtabmap_demos turtlebot3_rgbd.launch.py

或分步执行

$ ros2 launch rtabmap_launch rtabmap.launch.py visual_odometry:=false frame_id:=base_footprint odom_topic:=/odom args:="-d" use_sim_time:=true rgb_topic:=/camera/image_raw depth_topic:=/camera/depth/image_raw camera_info_topic:=/camera/camera_info approx_sync:=true qos:=2

$ ros2 run topic_tools relay /rtabmap/map /map
  • 效果图

请输入图片描述

  • 启动导航
#新开终端
ros2 launch nav2_bringup navigation_launch.py use_sim_time:=True
  • 启动rviz
#新开终端启动rviz
ros2 launch nav2_bringup rviz_launch.py
  • 效果图

请输入图片描述

  • 启动遥控
ros2 run turtlebot3_teleop teleop_keyboard
  • 利用遥控或通过rviz上指定目标点,可以移动小车进行建图

参考:

纠错,疑问,交流: 请进入讨论区请点击进入页面,扫码加入微信群或Q群进行交流

获取最新文章: 扫一扫加入“创客智造”公众号


标签: ros2与turtlebot3仿真教程