-
Notifications
You must be signed in to change notification settings - Fork 0
/
demo.launch
43 lines (38 loc) · 1.73 KB
/
demo.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
<launch>
<arg name="script_file"
doc="Full path to the script which initialize the supervisor"
default="$(find agimus_demos)/ur10/pointing/supervisor.py" />
<!-- whether to launch estimation.launch -->
<arg name="estimation" default="false"/>
<!-- whether the demonstration is run in simulation or on the real robot -->
<arg name="simulation" default="false"/>
<!-- YAML file that describes the demonstration: robots, objects-->
<arg name="part" default="plaque-tubes-with-table"/>
<include file="$(find agimus_demos)/launch/ur10_pointing_world_setup.launch">
<arg name="part" value="$(arg part)"/>
</include>
<!-- start ros controller running the SoT -->
<include file="$(find sot_universal_robot)/launch/controller.launch">
<arg name="simulation" value="$(arg simulation)"/>
<arg name="robot" value="ur"/>
</include>
<!--This starts the HPP interface in namespace agimus/hpp-->
<group ns="agimus/hpp">
<node name="hpp_node" pkg="agimus-hpp" type="hpp_node.py"
args="hpp-manipulation-server" respawn="true"
output="screen" />
</group>
<!--This starts sot supervisor in namespace agimus/sot-->
<include file="$(find agimus-sot)/launch/supervisor.launch" >
<arg name="script_file" value="$(arg script_file)"/>
<arg name="robot_prefix" value="ur10/"/>
<arg name="simulate_torque_feedback" value="false"/>
<arg name="required" value="false"/>
</include>
<rosparam command="load"
file="$(find agimus_demos)/ur10/pointing/demo-$(arg part).yaml"/>
<include file="$(find agimus)/launch/path_execution.launch">
<arg name="gui" value="false"/>
</include>
<include if="$(arg estimation)" file="$(find agimus_demos)/launch/ur10_pointing_estimation.launch"/>
</launch>