diff --git a/launch/simulation.launch b/launch/simulation.launch index 3678504d36121118c5ae12f4d9d14ab77303f31d..99ff2cffeaa77772168a8fec581deb5bc6cfb35e 100644 --- a/launch/simulation.launch +++ b/launch/simulation.launch @@ -7,6 +7,7 @@ <arg name="headless" default="false" /> <arg name="debug" default="false" /> <arg name="load_gripper" default="true" /> + <arg name="slow_simulation" default="true" /> <!-- don't include franka_control, but include the controller stuff from there --> <param name="robot_description" command="$(find xacro)/xacro '$(find franka_description)/robots/panda_arm_hand.urdf.xacro'" if="$(arg load_gripper)" /> @@ -15,6 +16,7 @@ <!--launch GAZEBO with own world configuration --> <include file="$(find gazebo_ros)/launch/empty_world.launch"> <!-- <arg name="world_name" value="$(find robotics_assisted_tomography)/worlds/tomography.world"/> --> + <arg name="world_name" if="$(arg slow_simulation)" value="$(find panda_simulation)/worlds/simulator.world"/> <arg name="debug" value="$(arg debug)" /> <arg name="gui" value="$(arg gui)" /> <arg name="paused" value="$(arg paused)" /> diff --git a/worlds/simulator.world b/worlds/simulator.world new file mode 100644 index 0000000000000000000000000000000000000000..4ee170e5e83221f06b0d95daf5c791511a51af20 --- /dev/null +++ b/worlds/simulator.world @@ -0,0 +1,21 @@ +<?xml version="1.0" ?> +<sdf version="1.5"> + <world name="default"> + <!-- A global light source --> + <include> + <uri>model://sun</uri> + </include> + <!-- A ground plane --> + <include> + <uri>model://ground_plane</uri> + </include> + <physics name='default_physics' default='0' type='ode'> + <!-- the max step size is set to 0.001 by default. --> + <!-- When increasing it, the simulation quality may suffer. --> + <max_step_size>0.002</max_step_size> + <!-- this factor actually is computed by multiplying the other two --> + <real_time_factor>0.2</real_time_factor> + <real_time_update_rate>100</real_time_update_rate> + </physics> + </world> +</sdf>