多 turtlebot 仿真
這裏實現了三個turtlebot 在gazebo下的仿真
<launch>
<arg name="gui" default="true"/>
<arg name="world_file" default="$(env TURTLEBOT_GAZEBO_WORLD_FILE)"/>
<arg name="base" value="$(optenv TURTLEBOT_BASE kobuki)"/> <!-- create, roomba -->
<arg name="battery" value="$(optenv TURTLEBOT_BATTERY /proc/acpi/battery/BAT0)"/> <!-- /proc/acpi/battery/BAT0 -->
<arg name="stacks" value="$(optenv TURTLEBOT_STACKS hexagons)"/> <!-- circles, hexagons -->
<arg name="3d_sensor" value="$(optenv TURTLEBOT_3D_SENSOR kinect)"/> <!-- kinect, asus_xtion_pro -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="use_sim_time" value="true"/>
<arg name="debug" value="false"/>
<arg name="gui" value="$(arg gui)" />
<arg name="world_name" value="$(arg world_file)"/>
</include>
<!-- BEGIN ROBOT 1-->
<group ns="robot1">
<param name="tf_prefix" value="robot1_tf" />
<arg name="init_pose" value="-x 1 -y 1 -z 0" />
<!-- <arg name="robot_name" value="Robot1" /> -->
<arg name="urdf_file" default="$(find xacro)/xacro --inorder '$(find turtlebot_description)/robots/$(arg base)_$(arg stacks)_$(arg 3d_sensor).urdf.xacro'"/>
<param name="robot_description" command="$(arg urdf_file)"/>
<!-- Gazebo model spawner -->
<node name="spawn_turtlebot_model_1" pkg="gazebo_ros" type="spawn_model"
args="$(arg init_pose) -unpause -urdf -param robot_description -model mobile_base1"/>
<!-- Velocity muxer -->
<node pkg="nodelet" type="nodelet" name="mobile_base_nodelet_manager_1" args="manager"/>
<node pkg="nodelet" type="nodelet" name="cmd_vel_mux_1"
args="load yocs_cmd_vel_mux/CmdVelMuxNodelet mobile_base_nodelet_manager">
<param name="yaml_cfg_file" value="$(find turtlebot_bringup)/param/mux.yaml"/>
<remap from="cmd_vel_mux/output" to="mobile_base/commands/velocity"/>
</node>
<!-- Bumper/cliff to pointcloud (not working, as it needs sensors/core messages) -->
<!-- <include file="$(find turtlebot_bringup)/launch/includes/kobuki/bumper2pc.launch.xml"/> -->
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher_1">
<param name="publish_frequency" type="double" value="30.0" />
</node>
<!-- Fake laser -->
<node pkg="nodelet" type="nodelet" name="laserscan_nodelet_manager_1" args="manager"/>
<node pkg="nodelet" type="nodelet" name="depthimage_to_laserscan_1"
args="load depthimage_to_laserscan/DepthImageToLaserScanNodelet laserscan_nodelet_manager_1">
<param name="scan_height" value="10"/>
<param name="output_frame_id" value="/robot1/camera_depth_frame"/>
<param name="range_min" value="0.45"/>
<remap from="image" to="/robot1/camera/depth/image_raw"/>
<remap from="scan" to="/robot1/scan"/>
</node>
</group>
<!-- BEGIN ROBOT 3 -->
<group ns="robot3">
<param name="tf_prefix" value="robot3_tf" />
<arg name="init_pose" value="-x 1 -y 2 -z 0" />
<!-- <arg name="robot_name" value="Robot1" /> -->
<arg name="urdf_file" default="$(find xacro)/xacro --inorder '$(find turtlebot_description)/robots/$(arg base)_$(arg stacks)_$(arg 3d_sensor).urdf.xacro'"/>
<param name="robot_description" command="$(arg urdf_file)"/>
<!-- Gazebo model spawner -->
<node name="spawn_turtlebot_model_3" pkg="gazebo_ros" type="spawn_model"
args="$(arg init_pose) -unpause -urdf -param robot_description -model mobile_base3"/>
<!-- Velocity muxer -->
<node pkg="nodelet" type="nodelet" name="mobile_base_nodelet_manager_3" args="manager"/>
<node pkg="nodelet" type="nodelet" name="cmd_vel_mux_3"
args="load yocs_cmd_vel_mux/CmdVelMuxNodelet mobile_base_nodelet_manager">
<param name="yaml_cfg_file" value="$(find turtlebot_bringup)/param/mux.yaml"/>
<remap from="cmd_vel_mux/output" to="mobile_base/commands/velocity"/>
</node>
<!-- Bumper/cliff to pointcloud (not working, as it needs sensors/core messages) -->
<include file="$(find turtlebot_bringup)/launch/includes/kobuki/bumper2pc.launch.xml"/>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher_3">
<param name="publish_frequency" type="double" value="30.0" />
</node>
<!-- Fake laser -->
<node pkg="nodelet" type="nodelet" name="laserscan_nodelet_manager_3" args="manager"/>
<node pkg="nodelet" type="nodelet" name="depthimage_to_laserscan_3"
args="load depthimage_to_laserscan/DepthImageToLaserScanNodelet laserscan_nodelet_manager_3">
<param name="scan_height" value="10"/>
<param name="output_frame_id" value="/robot3/camera_depth_frame"/>
<param name="range_min" value="0.45"/>
<remap from="image" to="/robot3/camera/depth/image_raw"/>
<remap from="scan" to="/robot3/scan"/>
</node>
</group>
<!-- BEGIN ROBOT 2-->
<group ns="robot2">
<param name="tf_prefix" value="robot2_tf" />
<include file="$(find turtlebot_gazebo)/launch/includes/$(arg base).launch.xml">
<arg name="base" value="$(arg base)"/>
<arg name="stacks" value="$(arg stacks)"/>
<arg name="3d_sensor" value="$(arg 3d_sensor)"/>
<!-- <arg name="init_pose" value="-x -1 -y 1 -z 0" />
<arg name="robot_name" value="Robot2" /> -->
</include>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher_2">
<param name="publish_frequency" type="double" value="30.0" />
</node>
<!-- Fake laser -->
<node pkg="nodelet" type="nodelet" name="laserscan_nodelet_manager" args="manager"/>
<node pkg="nodelet" type="nodelet" name="depthimage_to_laserscan"
args="load depthimage_to_laserscan/DepthImageToLaserScanNodelet laserscan_nodelet_manager">
<param name="scan_height" value="10"/>
<param name="output_frame_id" value="/robot2/camera_depth_frame"/>
<param name="range_min" value="0.45"/>
<remap from="image" to="/robot2/camera/depth/image_raw"/>
<remap from="scan" to="/robot2/scan"/>
</node>
</group>
</launch>
- 實現完長這樣
- tf_tree 長這樣:
rosrun rqt_tf_tree rqt_tf_tree
- 控制移動:
rostopic pub /robot1/mobile_base/commands/velocity geometry_msgs/Twist "linear:
x: 1.0
y: 0.0
z: 0.0
angular:
x: 0.0
y: 0.0
z: 0.0"
gazebo 中的機器人就會成功移動.
參考:
GAZEBO仿真學習筆記(1) urdf 編寫 及rviz 可視化: https://blog.csdn.net/Fourier_Legend/article/details/98496266
Multiple robots simulation and navigation
https://answers.ros.org/question/41433/multiple-robots-simulation-and-navigation/
ROS nodelet的使用
https://www.cnblogs.com/21207-iHome/p/8213411.html