mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 11:20:02 +08:00
40 lines
1.7 KiB
XML
40 lines
1.7 KiB
XML
<launch>
|
|
<!-- initial pose -->
|
|
<arg name="x" default="0.0"/>
|
|
<arg name="y" default="0.0"/>
|
|
<arg name="z" default="0.0"/>
|
|
<arg name="yaw" default="0.0"/>
|
|
|
|
<arg name="robot_namespace" default="/"/>
|
|
|
|
<!-- these are the arguments you can pass this launch file, for example paused:=true -->
|
|
<arg name="paused" default="true" />
|
|
<arg name="use_sim_time" default="false" />
|
|
<arg name="gui" default="true" />
|
|
<arg name="headless" default="false" />
|
|
<arg name="debug" default="true" />
|
|
|
|
<include file="$(find scout_description)/launch/scout_v2_stock.launch">
|
|
<arg name="robot_namespace" value="$(arg robot_namespace)" />
|
|
</include>
|
|
|
|
<node name="spawn_scout_model" pkg="gazebo_ros" type="spawn_model" args="-x $(arg x)
|
|
-y $(arg y)
|
|
-z $(arg z)
|
|
-Y $(arg yaw)
|
|
-unpause
|
|
-urdf
|
|
-param robot_description
|
|
-model 'scout$(arg robot_namespace)'" />
|
|
|
|
<!-- Load joint controller configurations from YAML file to parameter server -->
|
|
<rosparam file="$(find scout_gazebo_sim)/config/scout_v2_control.yaml" command="load"/>
|
|
|
|
<!-- load the controllers -->
|
|
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="scout_state_controller scout_motor_fr_controller scout_motor_fl_controller scout_motor_rl_controller scout_motor_rr_controller"/>
|
|
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
|
|
|
|
<node name="scout_skid_steer_controller" pkg="scout_gazebo_sim" type="scout_skid_steer_controller">
|
|
<param name="robot_namespace" type="string" value="$(arg robot_namespace)" />
|
|
</node>
|
|
</launch> |