Skip to content
Snippets Groups Projects
Commit 932ee131 authored by Robert Haschke's avatar Robert Haschke
Browse files

demo_gazebo.launch: Use franka_gazebo

parent 2f776d56
No related branches found
No related tags found
No related merge requests found
<launch> <launch>
<!-- specify the planning pipeline --> <!-- specify the planning pipeline -->
<arg name="pipeline" default="ompl" /> <arg name="pipeline" default="ompl" />
<!-- Panda specific options -->
<arg name="load_gripper" default="true" />
<arg name="transmission" default="effort" />
<!-- Gazebo specific options --> <!-- Gazebo specific options -->
<arg name="gazebo_gui" default="true"/> <arg name="gazebo_gui" default="true" />
<arg name="paused" default="false"/> <arg name="paused" default="false" />
<!-- launch the gazebo simulator and spawn the robot --> <!-- Launch the gazebo simulator and spawn the robot -->
<include file="$(dirname)/gazebo.launch" > <include file="$(find franka_gazebo)/launch/panda.launch" pass_all_args="true">
<arg name="paused" value="$(arg paused)"/> <arg name="headless" value="$(eval not arg('gazebo_gui'))" />
<arg name="gazebo_gui" value="$(arg gazebo_gui)"/> <arg name="use_gripper" default="$(arg load_gripper)" />
<arg name="controller" default="joint_trajectory_controller" />
</include> </include>
<include file="$(dirname)/demo.launch" pass_all_args="true"> <include file="$(dirname)/demo.launch" pass_all_args="true">
<!-- robot description is loaded by gazebo.launch, to enable Gazebo features --> <!-- robot description is loaded by gazebo.launch, to enable Gazebo features -->
<arg name="load_robot_description" value="false" /> <arg name="load_robot_description" value="false" />
<arg name="moveit_controller_manager" value="ros_control" /> <!-- MoveItSimpleControllerManager provides ros_control's JointTrajectory controllers
as well as GripperCommand actions -->
<arg name="moveit_controller_manager" value="simple" />
</include> </include>
</launch> </launch>
<?xml version="1.0"?>
<launch>
<arg name="paused" default="false"/>
<arg name="gazebo_gui" default="true"/>
<arg name="initial_joint_positions" doc="Initial joint configuration of the robot"
default=" -J panda_finger_joint1 0.035 -J panda_finger_joint2 0.035 -J panda_joint1 0 -J panda_joint2 -0.785 -J panda_joint3 0 -J panda_joint4 -2.356 -J panda_joint5 0 -J panda_joint6 1.571 -J panda_joint7 0.785"/>
<!-- startup simulated world -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" default="worlds/empty.world"/>
<arg name="paused" value="true"/>
<arg name="gui" value="$(arg gazebo_gui)"/>
</include>
<!-- send robot urdf to param server -->
<param name="robot_description" command="xacro hand:=true '$(find franka_description)/robots/panda_arm.urdf.xacro'" />
<!-- unpause only after loading robot model -->
<arg name="unpause" value="$(eval '' if arg('paused') else '-unpause')" />
<!-- push robot_description to factory and spawn robot in gazebo at the origin, change x,y,z arguments to spawn in a different position -->
<arg name="world_pose" value="-x 0 -y 0 -z 0" />
<node name="spawn_gazebo_model" pkg="gazebo_ros" type="spawn_model" args="-urdf -param robot_description -model robot $(arg unpause) $(arg world_pose) $(arg initial_joint_positions)"
respawn="false" output="screen" />
<!-- Load joint controller parameters for Gazebo -->
<rosparam file="$(find panda_moveit_config)/config/gazebo_controllers.yaml" />
<!-- Spawn Gazebo ROS controllers -->
<node name="gazebo_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="joint_state_controller" />
<!-- Load ROS controllers -->
<include file="$(dirname)/ros_controllers.launch"/>
</launch>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment