3 <arg name="LOG_LEVEL" default="Info"/>
4 <arg name="debug" default="false"/>
5 <arg name="cset" default="false"/>
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 --"/>
10 <arg unless="$(arg debug)" name="LAUNCH_PREFIX" value=""/>
11 <arg if="$(arg debug)" name="LAUNCH_PREFIX" value="gdb -ex run --args "/>
14 launch-prefix="$(arg CSET_LAUNCH_PREFIX) $(arg LAUNCH_PREFIX)"
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" />-->
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'" />
25 <node pkg="robot_state_publisher" type="robot_state_publisher" name="rob_st_pub" >
26 <param name="use_tf_static" value="false"/>
29 <param name="/use_sim_time" value="false" />
31 <group ns="velma_sim">
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]
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]
67 disable_component: false
71 disable_component: false
76 device_name: gazebo_leftHand
78 frame_id_vec: [left_HandFingerOneKnuckleThreeOptoforceBase, left_HandFingerTwoKnuckleThreeOptoforceBase, left_HandFingerThreeKnuckleThreeOptoforceBase]
80 joint_name: rightFtSensorJoint
81 transform_xyz: [0, 0, 0]
82 transform_rpy: [0, 0, 0]
84 joint_name: leftFtSensorJoint
85 transform_xyz: [0, 0, 0]
86 transform_rpy: [0, 0, 0]
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]