unitree_ros/robots/g1_description/launch/gazebo.launch

83 lines
3.3 KiB
XML
Executable File

<launch>
<arg name="wname" default="earth"/>
<arg name="rname" default="g1"/>
<arg name="robot_path" value="(find $(arg rname)_description)"/>
<arg name="dollar" value="$"/>
<arg name="paused" default="true"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
<arg name="user_debug" default="true"/>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find unitree_gazebo)/worlds/$(arg wname).world"/>
<arg name="debug" value="$(arg debug)"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include>
<!-- Load the URDF into the ROS Parameter Server -->
<param name="robot_description"
command="$(find xacro)/xacro --inorder '$(arg dollar)$(arg robot_path)/xacro/robot.xacro'
DEBUG:=$(arg user_debug)"/>
<!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
<!-- Set trunk and joint positions at startup -->
<node pkg="gazebo_ros" type="spawn_model" name="urdf_spawner" respawn="false" output="screen"
args="-urdf -z 0.6 -model $(arg rname)_gazebo -param robot_description -unpause"/>
<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(arg dollar)$(arg robot_path)/config/robot_control.yaml" command="load"/>
<!-- load the controllers -->
<node pkg="controller_manager" type="spawner" name="controller_spawner" respawn="false"
output="screen" ns="/$(arg rname)_gazebo" args="joint_state_controller
torso_controller
left_hip_pitch_controller
left_hip_roll_controller
left_hip_yaw_controller
left_knee_controller
left_ankle_pitch_controller
left_ankle_roll_controller
right_hip_pitch_controller
right_hip_roll_controller
right_hip_yaw_controller
right_knee_controller
right_ankle_pitch_controller
right_ankle_roll_controller
left_shoulder_pitch_controller
left_shoulder_roll_controller
left_shoulder_yaw_controller
left_elbow_pitch_controller
left_elbow_roll_controller
right_shoulder_pitch_controller
right_shoulder_roll_controller
right_shoulder_yaw_controller
right_elbow_pitch_controller
right_elbow_roll_controller
"/>
<!-- convert joint states to TF transforms for rviz, etc -->
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"
respawn="false" output="screen">
<remap from="/joint_states" to="/$(arg rname)_gazebo/joint_states"/>
</node>
<!-- <node pkg="unitree_gazebo" type="servo" name="servo" required="true" output="screen"/> -->
<!-- load the parameter unitree_controller -->
<include file="$(find unitree_controller)/launch/set_ctrl.launch">
<arg name="rname" value="$(arg rname)"/>
</include>
</launch>