WUT Velma robot API
velma_sim_re.launch
Go to the documentation of this file.
1 <?xml version="1.0"?>
2 <launch>
3  <arg name="LOG_LEVEL" default="Info"/>
4  <arg name="debug" default="false"/>
5  <arg name="cset" default="false"/>
6 
7  <arg unless="$(arg cset)" name="CSET_LAUNCH_PREFIX" value=""/>
8  <arg if="$(arg cset)" name="CSET_LAUNCH_PREFIX" value="cset proc -s user -e --"/>
9 
10  <arg unless="$(arg debug)" name="LAUNCH_PREFIX" value=""/>
11  <arg if="$(arg debug)" name="LAUNCH_PREFIX" value="gdb -ex run --args "/>
12 
13  <node
14  launch-prefix="$(arg CSET_LAUNCH_PREFIX) $(arg LAUNCH_PREFIX)"
15  name="velma_sim"
16  pkg="subsystem_deployer" type="deployer"
17  args="-l $(arg LOG_LEVEL) -x $(find velma_sim)/config/velma_core_re.xml -m velma_sim -p 40 -c 1 --" output="screen">
18 <!-- <env name="LD_PRELOAD" value="librtt_malloc_hook.so" />-->
19  </node>
20 
21  <param name="/robot_description"
22  command="$(find xacro)/xacro '$(find velma_description)/robots/velma.urdf.xacro'" />
23  <param name="/robot_description_semantic" command="$(find xacro)/xacro.py '$(find velma_description)/robots/velma.srdf'" />
24 <!--
25  <node pkg="robot_state_publisher" type="robot_state_publisher" name="rob_st_pub" >
26  <param name="use_tf_static" value="false"/>
27  </node>
28 -->
29  <param name="/use_sim_time" value="false" />
30 
31  <group ns="velma_sim">
32  <rosparam>
33  LWRrSim:
34  name: right
35  init_joint_names: [right_arm_0_joint, right_arm_1_joint, right_arm_2_joint, right_arm_3_joint, right_arm_4_joint, right_arm_5_joint, right_arm_6_joint]
36  init_joint_positions: [0,-1.57,1.57,1.57,0,-1.57,0]
37  tool:
38  m: 1.2391
39  com:
40  x: 0.1749
41  y: 0.0134
42  z: -0.0781
43  ixx: 0.1
44  ixy: 0.0
45  ixz: 0.0
46  iyy: 0.1
47  iyz: 0.0
48  izz: 0.1
49  LWRlSim:
50  name: left
51  init_joint_names: [left_arm_0_joint, left_arm_1_joint, left_arm_2_joint, left_arm_3_joint, left_arm_4_joint, left_arm_5_joint, left_arm_6_joint]
52  init_joint_positions: [0,1.57,-1.57,-1.57,0,1.57,0]
53  tool:
54  m: 1.2391
55  com:
56  x: -0.1749
57  y: 0.0134
58  z: -0.0781
59  ixx: 0.1
60  ixy: 0.0
61  ixz: 0.0
62  iyy: 0.1
63  iyz: 0.0
64  izz: 0.1
65  RightHand:
66  prefix: right
67  disable_component: false
68  can_id_base: 11
69  LeftHand:
70  prefix: left
71  disable_component: false
72  can_id_base: 15
73  RightHandTactile:
74  prefix: right
75  LeftHandOptoforce:
76  device_name: gazebo_leftHand
77  n_sensors: 3
78  frame_id_vec: [left_HandFingerOneKnuckleThreeOptoforceBase, left_HandFingerTwoKnuckleThreeOptoforceBase, left_HandFingerThreeKnuckleThreeOptoforceBase]
79  RightFtSensor:
80  joint_name: rightFtSensorJoint
81  transform_xyz: [0, 0, 0]
82  transform_rpy: [0, 0, 0]
83  LeftFtSensor:
84  joint_name: leftFtSensorJoint
85  transform_xyz: [0, 0, 0]
86  transform_rpy: [0, 0, 0]
87  safe:
88  l_arm_damping_factors: [10, 10, 5, 5, 2, 1, 1]
89  r_arm_damping_factors: [10, 10, 5, 5, 2, 1, 1]
90  torso_damping_factor: 20
91  arm_q_limits_lo: [-2.96, -2.09, -2.96, -2.09, -2.96, -2.09, -2.96]
92  arm_q_limits_hi: [2.96, 2.09, 2.96, 2.09, 2.96, 2.09, 2.96]
93  arm_dq_limits: [2, 2, 2, 2, 2, 2, 2]
94  arm_t_limits: [100.0, 100.0, 100.0, 100.0, 100.0, 60.0, 60.0]
95  can_queue_tx_r:
96  invert_rx_tx: true
97  can_queue_tx_l:
98  invert_rx_tx: true
99  </rosparam>
100  </group>
101 </launch>