1. 配置软件包
# 安装多机融合包及其它依赖包
sudo apt install ros-noetic-multirobot-map-merge ros-noetic-turtlebot3
# 创建新项目
cd ~/catkin_ws/src
catkin_create_pkg multi_robot rospy
cd multi_robot
mkdir launch
touch launch/robots_map.launch
mkdir config
touch config/multi_robot.rviz
2. 准备启动文件
2.1 编辑 robots_map.launch
为不同的机器人设置不同的命名空间,在各自的命名空间内,为各机器人配置仿真环境的初始位置后启动各自的建图(Gmapping)节点,最后通过新安装的multirobot_map_merge进行数据融合,在rviz中查看实时效果。
map_merged (静态) -> robotX/map (由gmapping发布的map->odom变换) -> robotX/odom (静态) -> robotX/base_footprint -> … -> base_scan
静态static_transform_publisher:launch发布world到map_merged的变换
静态static_transform_publisher:launch发布map_merged到robotX/map的变换
动态slam_gmapping:自动发布robotX/map→robotX/odom的变换
动态Gazebo插件:自动发布odom→base_footprint的动态变换
静态robot_state_publisher:launch发布base_footprint到base_link,以及base_link到其他各传感器连杆的变换
<launch>
<arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
<arg name="first_tb3" default="tb3_0"/>
<arg name="second_tb3" default="tb3_1"/>
<arg name="third_tb3" default="tb3_2"/>
<arg name="first_tb3_x_pos" default="-7.0"/>
<arg name="first_tb3_y_pos" default="-1.0"/>
<arg name="first_tb3_z_pos" default=" 0.0"/>
<arg name="first_tb3_yaw" default=" 1.57"/>
<arg name="second_tb3_x_pos" default=" 7.0"/>
<arg name="second_tb3_y_pos" default="-1.0"/>
<arg name="second_tb3_z_pos" default=" 0.0"/>
<arg name="second_tb3_yaw" default=" 1.57"/>
<arg name="third_tb3_x_pos" default=" 0.5"/>
<arg name="third_tb3_y_pos" default=" 3.0"/>
<arg name="third_tb3_z_pos" default=" 0.0"/>
<arg name="third_tb3_yaw" default=" 0.0"/>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find turtlebot3_gazebo)/worlds/turtlebot3_house.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>
<group ns = "$(arg first_tb3)">
<arg name="robot_name" default="$(arg first_tb3)"/>
<arg name="tf_prefix" value="$(arg robot_name)"/>
<param name="robot_description" command="$(find xacro)/xacro $(find turtlebot3_description)/urdf/turtlebot3_$(arg model).urdf.xacro tf_prefix:=$(arg robot_name)" />
<rosparam>
map_merge/init_pose_x: -7.0
map_merge/init_pose_y: -1.0
map_merge/init_pose_z: 0.0
map_merge/init_pose_yaw: 1.57
</rosparam>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
<param name="publish_frequency" type="double" value="50.0" />
<param name="tf_prefix" value="$(arg first_tb3)" />
</node>
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-urdf -model $(arg first_tb3) -x $(arg first_tb3_x_pos) -y $(arg first_tb3_y_pos) -z $(arg first_tb3_z_pos) -Y $(arg first_tb3_yaw) -param robot_description" />
<!-- TF 变换:从融合地图到机器人局部地图 -->
<node pkg="tf" type="static_transform_publisher" name="map_merged_to_robot1_map"
args="$0 0 0 0 0 0 map_merged $(arg tf_prefix)/map 100" />
<!-- 启动SLAM -->
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping">
<param name="base_frame" value="$(arg tf_prefix)/base_footprint"/>
<param name="odom_frame" value="$(arg tf_prefix)/odom"/>
<param name="map_frame" value="$(arg tf_prefix)/map"/>
<param name="use_sim_time" value="true"/>
<param name="delta" value="0.05"/>
<param name="pub_map_odom_transform" value="false"/>
<param name="tf_delay" value="0.05"/>
<param name="tf_broadcast" value="true"/>
<param name="transform_publish_period" value="0.05"/>
<remap from="scan" to="/$(arg tf_prefix)/scan"/>
</node>
</group>
<group ns = "$(arg second_tb3)">
<arg name="robot_name" default="$(arg second_tb3)"/>
<arg name="tf_prefix" value="$(arg robot_name)"/>
<param name="robot_description" command="$(find xacro)/xacro $(find turtlebot3_description)/urdf/turtlebot3_$(arg model).urdf.xacro tf_prefix:=$(arg robot_name)" />
<rosparam>
map_merge/init_pose_x: 7.0
map_merge/init_pose_y: -1.0
map_merge/init_pose_z: 0.0
map_merge/init_pose_yaw: 1.57
</rosparam>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
<param name="publish_frequency" type="double" value="50.0" />
<param name="tf_prefix" value="$(arg second_tb3)" />
</node>
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-urdf -model $(arg second_tb3) -x $(arg second_tb3_x_pos) -y $(arg second_tb3_y_pos) -z $(arg second_tb3_z_pos) -Y $(arg second_tb3_yaw) -param robot_description" />
<!-- TF 变换:从融合地图到机器人局部地图 -->
<node pkg="tf" type="static_transform_publisher" name="map_merged_to_robot2_map"
args="$0 0 0 0 0 0 map_merged $(arg tf_prefix)/map 100" />
<!-- 启动SLAM -->
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping">
<param name="base_frame" value="$(arg tf_prefix)/base_footprint"/>
<param name="odom_frame" value="$(arg tf_prefix)/odom"/>
<param name="map_frame" value="$(arg tf_prefix)/map"/>
<param name="use_sim_time" value="true"/>
<param name="delta" value="0.05"/>
<param name="pub_map_odom_transform" value="false"/>
<param name="tf_delay" value="0.05"/>
<param name="tf_broadcast" value="true"/>
<param name="transform_publish_period" value="0.05"/>
<remap from="scan" to="/$(arg tf_prefix)/scan"/>
</node>
</group>
<group ns = "$(arg third_tb3)">
<arg name="robot_name" default="$(arg third_tb3)"/>
<arg name="tf_prefix" value="$(arg robot_name)"/>
<param name="robot_description" command="$(find xacro)/xacro $(find turtlebot3_description)/urdf/turtlebot3_$(arg model).urdf.xacro tf_prefix:=$(arg robot_name)" />
<rosparam>
map_merge/init_pose_x: 0.5
map_merge/init_pose_y: 3.0
map_merge/init_pose_z: 0.0
map_merge/init_pose_yaw: 0.0
</rosparam>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
<param name="publish_frequency" type="double" value="50.0" />
<param name="tf_prefix" value="$(arg third_tb3)" />
</node>
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-urdf -model $(arg third_tb3) -x $(arg third_tb3_x_pos) -y $(arg third_tb3_y_pos) -z $(arg third_tb3_z_pos) -Y $(arg third_tb3_yaw) -param robot_description" />
<!-- TF 变换:从融合地图到机器人局部地图 -->
<node pkg="tf" type="static_transform_publisher" name="map_merged_to_robot3_map"
args="$0 0 0 0 0 0 map_merged $(arg tf_prefix)/map 100" />
<!-- 启动SLAM -->
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping">
<param name="base_frame" value="$(arg tf_prefix)/base_footprint"/>
<param name="odom_frame" value="$(arg tf_prefix)/odom"/>
<param name="map_frame" value="$(arg tf_prefix)/map"/>
<param name="use_sim_time" value="true"/>
<param name="delta" value="0.05"/>
<param name="pub_map_odom_transform" value="false"/>
<param name="tf_delay" value="0.05"/>
<param name="tf_broadcast" value="true"/>
<param name="transform_publish_period" value="0.05"/>
<remap from="scan" to="/$(arg tf_prefix)/scan"/>
</node>
</group>
<node pkg="tf" type="static_transform_publisher" name="world_to_map_merged" args="0 0 0 0 0 0 world map_merged 100" />
<!-- 启动地图融合 -->
<node pkg="multirobot_map_merge" type="map_merge" name="map_merge" output="screen">
<param name="known_init_poses" value="true"/>
<param name="world_frame" value="map_merged"/>
<param name="merging_rate" value="2.0"/>
<param name="discovery_rate" value="0.1"/>
<param name="estimation_confidence" value="0.9"/>
<param name="robot_names" value="$(arg first_tb3),$(arg second_tb3),$(arg third_tb3)"/>
<param name="robot_map_topics" value="/$(arg first_tb3)/map,/$(arg second_tb3)/map,/$(arg third_tb3)/map"/>
<param name="map_output_topic" value="/map_merged"/>
</node>
<!-- 启动RViz -->
<node pkg="rviz" type="rviz" name="rviz" required="true" args="-d $(find multi_robot)/config/multi_robot.rviz"/>
</launch>
2.2 配置Rviz节点(multi_robot.rviz)
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Robot11
- /TF1/Tree1
- /Map11
- /Map11/Status1
Splitter Ratio: 0.5111111402511597
Tree Height: 1195
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Name: Time
SyncMode: 0
SyncSource: LaserScan1
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 100
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 1
Class: rviz/RobotModel
Collision Enabled: false
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_footprint:
Alpha: 1
Show Axes: false
Show Trail: false
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
base_scan:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_rgb_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_rgb_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
caster_back_left_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
caster_back_right_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
imu_link:
Alpha: 1
Show Axes: false
Show Trail: false
wheel_left_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
wheel_right_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Name: Robot1
Robot Description: tb3_0/robot_description
TF Prefix: tb3_0
Update Interval: 0
Value: true
Visual Enabled: true
- Alpha: 1
Class: rviz/RobotModel
Collision Enabled: false
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_footprint:
Alpha: 1
Show Axes: false
Show Trail: false
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
base_scan:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_rgb_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_rgb_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
caster_back_left_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
caster_back_right_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
imu_link:
Alpha: 1
Show Axes: false
Show Trail: false
wheel_left_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
wheel_right_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Name: Robot2
Robot Description: tb3_1/robot_description
TF Prefix: tb3_1
Update Interval: 0
Value: true
Visual Enabled: true
- Alpha: 1
Class: rviz/RobotModel
Collision Enabled: false
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_footprint:
Alpha: 1
Show Axes: false
Show Trail: false
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
base_scan:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_rgb_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_rgb_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
caster_back_left_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
caster_back_right_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
imu_link:
Alpha: 1
Show Axes: false
Show Trail: false
wheel_left_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
wheel_right_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Name: Robot3
Robot Description: tb3_2/robot_description
TF Prefix: tb3_2
Update Interval: 0
Value: true
Visual Enabled: true
- Class: rviz/TF
Enabled: true
Filter (blacklist): ""
Filter (whitelist): ""
Frame Timeout: 15
Frames:
All Enabled: false
map_merged:
Value: true
tb3_0/base_footprint:
Value: true
tb3_0/base_link:
Value: true
tb3_0/base_scan:
Value: true
tb3_0/camera_link:
Value: true
tb3_0/camera_rgb_frame:
Value: true
tb3_0/camera_rgb_optical_frame:
Value: true
tb3_0/caster_back_left_link:
Value: true
tb3_0/caster_back_right_link:
Value: true
tb3_0/imu_link:
Value: true
tb3_0/map:
Value: true
tb3_0/odom:
Value: true
tb3_0/wheel_left_link:
Value: true
tb3_0/wheel_right_link:
Value: true
tb3_1/base_footprint:
Value: true
tb3_1/base_link:
Value: true
tb3_1/base_scan:
Value: true
tb3_1/camera_link:
Value: true
tb3_1/camera_rgb_frame:
Value: true
tb3_1/camera_rgb_optical_frame:
Value: true
tb3_1/caster_back_left_link:
Value: true
tb3_1/caster_back_right_link:
Value: true
tb3_1/imu_link:
Value: true
tb3_1/map:
Value: true
tb3_1/odom:
Value: true
tb3_1/wheel_left_link:
Value: true
tb3_1/wheel_right_link:
Value: true
tb3_2/base_footprint:
Value: true
tb3_2/base_link:
Value: true
tb3_2/base_scan:
Value: true
tb3_2/camera_link:
Value: true
tb3_2/camera_rgb_frame:
Value: true
tb3_2/camera_rgb_optical_frame:
Value: true
tb3_2/caster_back_left_link:
Value: true
tb3_2/caster_back_right_link:
Value: true
tb3_2/imu_link:
Value: true
tb3_2/map:
Value: true
tb3_2/odom:
Value: true
tb3_2/wheel_left_link:
Value: true
tb3_2/wheel_right_link:
Value: true
world:
Value: true
Marker Alpha: 1
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
world:
map_merged:
tb3_0/map:
tb3_0/odom:
tb3_0/base_footprint:
tb3_0/base_link:
tb3_0/base_scan:
{}
tb3_0/camera_link:
tb3_0/camera_rgb_frame:
tb3_0/camera_rgb_optical_frame:
{}
tb3_0/caster_back_left_link:
{}
tb3_0/caster_back_right_link:
{}
tb3_0/imu_link:
{}
tb3_0/wheel_left_link:
{}
tb3_0/wheel_right_link:
{}
tb3_1/map:
tb3_1/odom:
tb3_1/base_footprint:
tb3_1/base_link:
tb3_1/base_scan:
{}
tb3_1/camera_link:
tb3_1/camera_rgb_frame:
tb3_1/camera_rgb_optical_frame:
{}
tb3_1/caster_back_left_link:
{}
tb3_1/caster_back_right_link:
{}
tb3_1/imu_link:
{}
tb3_1/wheel_left_link:
{}
tb3_1/wheel_right_link:
{}
tb3_2/map:
tb3_2/odom:
tb3_2/base_footprint:
tb3_2/base_link:
tb3_2/base_scan:
{}
tb3_2/camera_link:
tb3_2/camera_rgb_frame:
tb3_2/camera_rgb_optical_frame:
{}
tb3_2/caster_back_left_link:
{}
tb3_2/caster_back_right_link:
{}
tb3_2/imu_link:
{}
tb3_2/wheel_left_link:
{}
tb3_2/wheel_right_link:
{}
Update Interval: 0
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/LaserScan
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Min Color: 0; 0; 0
Name: LaserScan1
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.009999999776482582
Style: Flat Squares
Topic: /tb3_0/scan
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/LaserScan
Color: 0; 255; 0
Color Transformer: FlatColor
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Min Color: 0; 0; 0
Name: LaserScan2
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.030000001192092896
Style: Flat Squares
Topic: tb3_1/scan
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/LaserScan
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Min Color: 0; 0; 0
Name: LaserScan3
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.009999999776482582
Style: Flat Squares
Topic: /tb3_2/scan
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
- Class: rviz/Image
Enabled: false
Image Topic: /raspicam_node/image
Max Value: 1
Median window: 5
Min Value: 0
Name: Image
Normalize Range: true
Queue Size: 2
Transport Hint: compressed
Unreliable: false
Value: false
- Alpha: 0.699999988079071
Class: rviz/Map
Color Scheme: map
Draw Behind: false
Enabled: true
Name: Map1
Topic: /tb3_0/map
Unreliable: false
Use Timestamp: false
Value: true
- Alpha: 0.699999988079071
Class: rviz/Map
Color Scheme: map
Draw Behind: false
Enabled: true
Name: Map2
Topic: /tb3_1/map
Unreliable: false
Use Timestamp: false
Value: true
- Alpha: 0.699999988079071
Class: rviz/Map
Color Scheme: map
Draw Behind: false
Enabled: true
Name: Map3
Topic: /tb3_2/map
Unreliable: false
Use Timestamp: false
Value: true
- Alpha: 1
Class: rviz/Axes
Enabled: false
Length: 1
Name: World Axes
Radius: 0.10000000149011612
Reference Frame: map_merged
Show Trail: false
Value: false
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: map_merged
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Angle: -1.6607967615127563
Class: rviz/TopDownOrtho
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Scale: 82.56507110595703
Target Frame: map
X: 0.07265345752239227
Y: 0.513627827167511
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1492
Hide Left Dock: false
Hide Right Dock: true
Image:
collapsed: false
QMainWindow State: 000000ff00000000fd0000000400000000000001bd00000536fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000536000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065000000020f000001900000001600ffffff000000010000010f0000035cfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000430000035c000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005790000003efc0100000002fb0000000800540069006d0065010000000000000579000003bc00fffffffb0000000800540069006d00650100000000000004500000000000000000000003b60000053600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: true
Width: 1401
X: 1473
Y: 27
2.3 项目编译
cd ~/catkin_ws
catkin_make --pkg multi_robot
source devel/setup.bash
3. 启动协同建图
# 终端1:启动主系统
roslaunch multi_robot robots_map.launch
# 终端2:机器人1控制端
ROS_NAMESPACE=tb3_0 rosrun turtlebot3_teleop turtlebot3_teleop_key
# 终端3:机器人2控制端
ROS_NAMESPACE=tb3_1 rosrun turtlebot3_teleop turtlebot3_teleop_key
# 终端4:机器人3控制端
ROS_NAMESPACE=tb3_2 rosrun turtlebot3_teleop turtlebot3_teleop_key
4. 保存融合地图
# 保存地图
rosrun map_server map_saver -f ~/merged_map
# 查看地图话题
rostopic info /map
# 查看融合节点
rosnode info /map_merge