-
Notifications
You must be signed in to change notification settings - Fork 0
/
demo.launch
39 lines (34 loc) · 1.56 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
<launch>
<arg name="simulation" default="false"
doc="whether the demo is run in Gazebo"/>
<param name="robot_initial_pose"
value="0. 0. 1.0192720229567027 0 0 0 1"/>
<!-- Start the Stack of Tasks -->
<include file="$(find roscontrol_sot_talos)/launch/sot_talos_controller_gazebo.launch" if="$(arg simulation)">
</include>
<include file="$(find roscontrol_sot_talos)/launch/sot_talos_controller.launch" unless="$(arg simulation)">
</include>
<include file="$(find agimus_demos)/launch/talos_calibration_contact_world_setup.launch">
<arg name="simulation" value="$(arg simulation)" />
</include>
<arg name="script_file" doc="Full path to the script which initialize the supervisor"
default="$(find agimus_demos)/talos/calibration/contact/supervisor.py" />
<!--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="talos/"/>
<arg name="simulate_torque_feedback" value="true"/>
<arg name="required" value="false"/>
</include>
<rosparam command="load"
file="$(find agimus_demos)/talos/calibration/contact/demo.yaml"/>
<include file="$(find agimus)/launch/path_execution.launch">
<arg name="gui" value="false"/>
</include>
</launch>