-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathsimulation.launch
67 lines (57 loc) · 2.77 KB
/
simulation.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
<!--
This launch file simulates UR-10 robot using Gazebo with
- an RGBD sensor attached to the end effector,
- the P72 part lying on a table.
After launching this file, the simulated robot should be in the same state
as the real robot when turned on.
-->
<launch>
<!-- Remap topic /camera/depth/image_raw -->
<remap from="/camera/depth/image_raw" to="/camera/depth/image_rect_raw" />
<arg name="limited" default="false" doc="If true, limits joint range [-PI, PI] on all joints." />
<arg name="paused" default="false" doc="Starts gazebo in paused mode" />
<arg name="gui" default="true" doc="Starts gazebo gui" />
<arg name="debug" default="false"/>
<arg name="part" default="plaque-tubes-with-table"/>
<!-- <arg name="part_pose" default="-x 1.6 -Y -1.57079632679"/> -->
<arg name="part_pose" default="-x 1.895 -y 8.008 -z 3.426 -Y -1.57079632679"/>
<arg name="slower" default="false"/>
<group if="$(arg slower)">
<!-- startup simulated world with gazebo 30 times slower -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" default="$(find agimus_demos)/worlds/empty.world"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="debug" value="$(arg debug)"/>
<arg name="verbose" value="true"/>
</include>
</group>
<group unless="$(arg slower)">
<!-- startup simulated world -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" default="worlds/empty.world"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="debug" value="$(arg debug)"/>
<arg name="verbose" value="true"/>
</include>
</group>
<!-- send robot urdf to param server -->
<include file="$(find agimus_demos)/launch/ur10_pointing_ur10_upload.launch">
</include>
<rosparam command="load"
file="$(find agimus_demos)/ur10/pointing/config/pid.yaml"/>
<!-- push robot_description to factory and spawn robot in gazebo -->
<node name="spawn_gazebo_model" pkg="gazebo_ros" type="spawn_model"
args="-urdf -param robot_description -model robot -z 0.0 -Y 0
-J shoulder_pan_joint 1.57 -J shoulder_lift_joint -1.57 -J elbow_joint 1.57" respawn="false" output="screen" />
<rosparam command="load" file="$(find ur_gazebo)/config/ur10e_controllers.yaml"/>
<!-- <rosparam command="load" file="$(find ur_gazebo)/controller/arm_controller_ur10.yaml"/> -->
<!-- <include file="$(find ur_gazebo)/launch/controller_utils.launch"/> -->
<!-- Part -->
<group ns="part">
<node name="spawn_part" pkg="gazebo_ros" type="spawn_model"
args="-file $(find agimus_demos)/ur10/pointing/urdf/$(arg part).urdf -urdf
-model part $(arg part_pose)" />
</group>
</launch>