< >
Home » ROS2与Turbot3-Multi多机协同教程 » ROS2与Turbot3-Multi多机协同教程-确定机器人的初始位置

ROS2与Turbot3-Multi多机协同教程-确定机器人的初始位置

文章说明

  • 本教程介绍如何确定Turbot3-Multi套件中在多机建图时的初始位置
  • 测试环境:Ubuntu 24.04 + ROS2 Jazzy

相关设备

方法介绍

1. 确定机器人的摆放位置及方向
  • 通常情况下,所有机器人的方向设置成一致,这样会方便计算位姿
  • 第一台和第二台机器人应放在同一水平的位置
2. 机器人位置的计算
  • 地图合并后的坐标系是以第一台机器人与第二台机器人水平距离的中点作为其坐标原点
  • 机器人位置计算首先需要确定其在地图合并后的坐标系的位置
  • 比如在下图中机器人tb3_0与机器人tb3_1实际相距两米,那么以两者距离中点作为其坐标原点得出其坐标应为(0,-1)(0,1)
  • 根据multirobot_map_merge包的设定,机器人xy位姿应为其在地图合并后坐标系的坐标值的20倍,即机器人tb3_0与机器人tb3_1应设置为(0,-20)(0,20)
  • 以此可推出其他机器人的xy位姿
  • 同一水平放置

请输入图片描述

  • 不规则放置

请输入图片描述

  • 在上面两图中,机器人的实际的x方向时与地图合并后坐标系的x方向相反

实例测试1

1.1. 实际机器人布局
  • 机器人tb3_0与机器人tb3_1处于同一水平线上且两者相隔两米,机器人tb2_0与机器人tb3_2处于同一垂直线上且两者相隔两米
  • 三台机器人的朝向均一致

请输入图片描述

  • 可视化图

请输入图片描述

1.2. 机器人位置的计算
  • 根据文章上半部的初始化位姿方法以及上面的可视化图,可以得出三台机器人在地图合并后的坐标系的坐标依次为(0,-1)(0,1)(-2,1)
  • 由于机器人位姿应为其在地图合并后坐标系的坐标值的20倍,所以三台机器人的xy位姿依次为(0,-20)(0,20)(-40,20)
  1. 修改对应的初始化位置
  • 用vim打开对应的配置文件且修改每台机器人对应的xy位姿
$ vim /home/ubuntu/ros2_t3_ws/src/turbot3/turbot3_multi/config/map_merge_params.yaml
...
    /tb3_0/map_merge/init_pose_x: 0.0
    /tb3_0/map_merge/init_pose_y: -20.0
    /tb3_0/map_merge/init_pose_z: 0.0
    /tb3_0/map_merge/init_pose_yaw: 0.0

    /tb3_1/map_merge/init_pose_x: 0.0
    /tb3_1/map_merge/init_pose_y: 20.0
    /tb3_1/map_merge/init_pose_z: 0.0
    /tb3_1/map_merge/init_pose_yaw: 0.0

    /tb3_2/map_merge/init_pose_x: -40.0
    /tb3_2/map_merge/init_pose_y: 20.0
    /tb3_2/map_merge/init_pose_z: 0.0
    /tb3_2/map_merge/init_pose_yaw: 0.0

注意:由于所有机器人的朝向都一致且都与地图合并后坐标系的x方向相反,故robot_yaw值都应一致为0

实例测试2

2.1. 实际机器人布局

TIP:可以基于地板瓷砖来摆放机器人,这样方便布局的同时也方便计算距离

  • 机器人tb3_0与机器人tb3_1处于同一水平线上且两者相隔3格瓷砖即2.4米,机器人tb2_0与机器人tb3_2处于同一垂直线上且两者相隔3格瓷砖即3.2米
  • 三台机器人的朝向均一致

请输入图片描述

1.2. 机器人位置的计算
  • 根据文章上半部的初始化位姿方法以及上面的可视化图,可以得出三台机器人在地图合并后的坐标系的坐标依次为(0,-1.2)(0,1.2)(-3.2,1.2)
  • 由于机器人位姿应为其在地图合并后坐标系的坐标值的20倍,所以三台机器人的xy位姿依次为(0,-24)(0,24)(-64,24)
  1. 修改对应的初始化位置
  • 用vim打开对应的配置文件且修改每台机器人对应的xy位姿
$ vim /home/ubuntu/ros2_t3_ws/src/turbot3/turbot3_multi/config/map_merge_params.yaml
...
    /tb3_0/map_merge/init_pose_x: 0.0
    /tb3_0/map_merge/init_pose_y: -24.0
    /tb3_0/map_merge/init_pose_z: 0.0
    /tb3_0/map_merge/init_pose_yaw: 0.0

    /tb3_1/map_merge/init_pose_x: 0.0
    /tb3_1/map_merge/init_pose_y: 24.0
    /tb3_1/map_merge/init_pose_z: 0.0
    /tb3_1/map_merge/init_pose_yaw: 0.0

    /tb3_2/map_merge/init_pose_x: -64.0
    /tb3_2/map_merge/init_pose_y: 24.0
    /tb3_2/map_merge/init_pose_z: 0.0
    /tb3_2/map_merge/init_pose_yaw: 0.0
  • 最终效果

请输入图片描述

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: ros2与turbot3-multi多机协同教程