WUT Velma robot API
velma_core_ve_body.launch
Go to the documentation of this file.
1 <?xml version="1.0"?>
2 <launch>
3  <arg name="ORO_LOGLEVEL" default="3"/>
4  <arg name="debug" default="false"/>
5  <arg name="cset" default="false"/>
6  <arg name="valgrind" default="false"/>
7 
8  <arg unless="$(arg cset)" name="CSET_LAUNCH_PREFIX" value=""/>
9  <arg if="$(arg cset)" name="CSET_LAUNCH_PREFIX" value="cset proc -s user -e --"/>
10 
11  <arg unless="$(arg debug)" name="LAUNCH_PREFIX" value=""/>
12  <arg if="$(arg debug)" name="LAUNCH_PREFIX" value="gdb -ex run --args "/>
13 
14  <arg unless="$(arg valgrind)" name="LAUNCH_PREFIX_2" value=""/>
15  <arg if="$(arg valgrind)" name="LAUNCH_PREFIX_2" value="valgrind --leak-check=yes "/>
16 
17  <node
18  name="velma_core_ve_body"
19  pkg="subsystem_deployer"
20  type="deployer"
21  output="screen"
22  launch-prefix="$(arg CSET_LAUNCH_PREFIX) $(arg LAUNCH_PREFIX_2) $(arg LAUNCH_PREFIX)"
23  args="--DeployerName velma_core_ve_body -x $(find velma_core_ve_body)/config/velma_core_ve_body.xml -m velma_core_ve_body -p 30 -c 1 --"
24  >
25  <env name="ORO_LOGLEVEL" value="$(arg ORO_LOGLEVEL)"/>
26  <!-- <env name="LD_PRELOAD" value="librtt_malloc_hook.so" /> -->
27  </node>
28 
29  <group ns="velma_core_ve_body">
30  <rosparam>
31  safe:
32  l_arm_damping_factors: [10, 10, 5, 5, 2, 1, 1]
33  r_arm_damping_factors: [10, 10, 5, 5, 2, 1, 1]
34  torso_damping_factor: 20
35  arm_q_limits_lo: [-2.96, -2.09, -2.96, -2.09, -2.96, -2.09, -2.96]
36  arm_q_limits_hi: [2.96, 2.09, 2.96, 2.09, 2.96, 2.09, 2.96]
37  arm_dq_limits: [2, 2, 2, 2, 2, 2, 2]
38  arm_t_limits: [100.0, 100.0, 100.0, 100.0, 100.0, 60.0, 60.0]
39  safe_lwr_r:
40  damping_factors: [10, 10, 5, 5, 2, 1, 1]
41  safe_lwr_l:
42  damping_factors: [10, 10, 5, 5, 2, 1, 1]
43  safe_t:
44  control_mode: torque
45  damping_factor: 20
46  gear: 158.0
47  encoder_resolution: 131072.0
48  motor_constant: 0.00105
49  safe_hp:
50  control_mode: position
51  safe_ht:
52  control_mode: position
53  driver_t:
54  control_mode: torque
55  homing_done: true
56  driver_hp:
57  control_mode: position
58  homing_done: false
59  driver_ht:
60  control_mode: position
61  homing_done: false
62  TorsoPanTransmision:
63  motor_offset: 270119630
64  joint_offset: 0.0
65  gear: 158.0
66  encoder_res: 131072.0
67  enable_position: true
68  enable_velocity: true
69  TorsoPanTransmisionInv:
70  motor_offset: 270119630
71  joint_offset: 0.0
72  gear: 158.0
73  encoder_res: 131072.0
74  motor_constant: 0.00105
75  enable_torque: true
76  HeadPanTransmision:
77  motor_offset: 0.0
78  joint_offset: 0.0
79  gear: -100.0
80  encoder_res: 8000.0
81  enable_position: true
82  enable_velocity: true
83  HeadPanTransmisionInv:
84  motor_offset: 0.0
85  joint_offset: 0.0
86  gear: -100.0
87  encoder_res: 8000.0
88  motor_constant: 0.0
89  enable_position: true
90  enable_velocity: true
91  HeadTiltTransmision:
92  motor_offset: 0.0
93  joint_offset: 0.0
94  gear: 100.0
95  encoder_res: 8000.0
96  enable_position: true
97  enable_velocity: true
98  HeadTiltTransmisionInv:
99  motor_offset: 0.0
100  joint_offset: 0.0
101  gear: 100.0
102  encoder_res: 8000.0
103  motor_constant: 0.0
104  enable_position: true
105  enable_velocity: true
106  rHand:
107  device_name: TODO
108  prefix: right
109  can_id_base: 11
110  lHand:
111  device_name: TODO
112  prefix: left
113  can_id_base: 11
114  FtSensorRight:
115  scaling_factor: 0.000001
116  transform_xyz: [0, 0, 0]
117  transform_rpy: [-1.570796327, 0.5235987756, -1.570796327] <!-- rotations from wrist to sensor frame (trasform coordinates from sensor to wrist frame)-->
118  FtSensorLeft:
119  scaling_factor: 0.000001
120  transform_xyz: [0, 0, 0]
121  transform_rpy: [-1.570796327, 0.5235987756, 1.570796327] <!-- rotations from wrist to sensor frame -->
122  CameraTrigger:
123  skip_cycles: 24
124  bits: [16, 17, 18]
125  lwr_sync_r:
126  q0_offset: -0.0001
127  q1_offset: -0.0027
128  q2_offset: -0.0013
129  q3_offset: -0.0018
130  q4_offset: -0.0029
131  q5_offset: -0.0218
132  q6_offset: -0.0000
133  lwr_sync_l:
134  q0_offset: 0.0008
135  q1_offset: -0.0020
136  q2_offset: -0.0016
137  q3_offset: -0.0006
138  q4_offset: -0.0024
139  q5_offset: 0.0221
140  q6_offset: 0.0000
141  </rosparam>
142  </group>
143 </launch>