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"/>
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 --"/>
11 <arg unless="$(arg debug)" name="LAUNCH_PREFIX" value=""/>
12 <arg if="$(arg debug)" name="LAUNCH_PREFIX" value="gdb -ex run --args "/>
14 <arg unless="$(arg valgrind)" name="LAUNCH_PREFIX_2" value=""/>
15 <arg if="$(arg valgrind)" name="LAUNCH_PREFIX_2" value="valgrind --leak-check=yes "/>
18 name="velma_core_ve_body"
19 pkg="subsystem_deployer"
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 --"
25 <env name="ORO_LOGLEVEL" value="$(arg ORO_LOGLEVEL)"/>
26 <!-- <env name="LD_PRELOAD" value="librtt_malloc_hook.so" /> -->
29 <group ns="velma_core_ve_body">
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]
40 damping_factors: [10, 10, 5, 5, 2, 1, 1]
42 damping_factors: [10, 10, 5, 5, 2, 1, 1]
47 encoder_resolution: 131072.0
48 motor_constant: 0.00105
50 control_mode: position
52 control_mode: position
57 control_mode: position
60 control_mode: position
63 motor_offset: 270119630
69 TorsoPanTransmisionInv:
70 motor_offset: 270119630
74 motor_constant: 0.00105
83 HeadPanTransmisionInv:
98 HeadTiltTransmisionInv:
104 enable_position: true
105 enable_velocity: true
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)-->
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 -->