diff --git a/urdf/robot/openarm_robot.xacro b/urdf/robot/openarm_robot.xacro index 29f629a..f556c30 100644 --- a/urdf/robot/openarm_robot.xacro +++ b/urdf/robot/openarm_robot.xacro @@ -32,11 +32,25 @@ left_arm_base_xyz='0 0 0' right_arm_base_rpy='0 0 0' left_arm_base_rpy='0 0 0' - left_can_interface:='can5' - right_can_interface:='can4' + left_can_interface:='can1' + right_can_interface:='can0' left_arm_prefix:='left_' right_arm_prefix:='right_' can_fd:='false' + gravity_compensation_enabled:='false' + gravity_compensation_use_kdl:='true' + gravity_torque_mode:='false' + gravity_scale:='1.0' + gravity_tau_limit1:='2.0' + gravity_tau_limit2:='2.0' + gravity_tau_limit3:='2.0' + gravity_tau_limit4:='2.0' + gravity_tau_limit5:='2.0' + gravity_tau_limit6:='2.0' + gravity_tau_limit7:='2.0' + kdl_urdf_path:='/tmp/openarm_bimanual_runtime.urdf' + kdl_base_link:='openarm_body_link0' + kdl_tip_link:='' " > @@ -110,7 +124,21 @@ fake_sensor_commands="${fake_sensor_commands}" left_arm_prefix="${left_arm_prefix}" right_arm_prefix="${right_arm_prefix}" - hand="${hand}"/> + hand="${hand}" + gravity_compensation_enabled="${gravity_compensation_enabled}" + gravity_compensation_use_kdl="${gravity_compensation_use_kdl}" + gravity_torque_mode="${gravity_torque_mode}" + gravity_scale="${gravity_scale}" + gravity_tau_limit1="${gravity_tau_limit1}" + gravity_tau_limit2="${gravity_tau_limit2}" + gravity_tau_limit3="${gravity_tau_limit3}" + gravity_tau_limit4="${gravity_tau_limit4}" + gravity_tau_limit5="${gravity_tau_limit5}" + gravity_tau_limit6="${gravity_tau_limit6}" + gravity_tau_limit7="${gravity_tau_limit7}" + kdl_urdf_path="${kdl_urdf_path}" + kdl_base_link="${kdl_base_link}" + kdl_tip_link="${kdl_tip_link}"/> diff --git a/urdf/robot/v10.urdf.xacro b/urdf/robot/v10.urdf.xacro index d7daaa9..3cdcdfe 100644 --- a/urdf/robot/v10.urdf.xacro +++ b/urdf/robot/v10.urdf.xacro @@ -25,11 +25,11 @@ - + - + @@ -48,6 +48,20 @@ + + + + + + + + + + + + + + diff --git a/urdf/ros2_control/openarm.bimanual.ros2_control.xacro b/urdf/ros2_control/openarm.bimanual.ros2_control.xacro index 9223d55..7d5546f 100644 --- a/urdf/ros2_control/openarm.bimanual.ros2_control.xacro +++ b/urdf/ros2_control/openarm.bimanual.ros2_control.xacro @@ -4,14 +4,28 @@ + can_fd:=^|false + gravity_compensation_enabled:=^|true + gravity_compensation_use_kdl:=^|true + gravity_torque_mode:=^|true + gravity_scale:=^|2.5 + gravity_tau_limit1:=^|10.0 + gravity_tau_limit2:=^|10.0 + gravity_tau_limit3:=^|5.0 + gravity_tau_limit4:=^|5.0 + gravity_tau_limit5:=^|5.0 + gravity_tau_limit6:=^|3.0 + gravity_tau_limit7:=^|3.0 + kdl_urdf_path:=^|/tmp/openarm_bimanual_runtime.urdf + kdl_base_link:=^|openarm_body_link0 + kdl_tip_link:=^|"> @@ -28,6 +42,20 @@ ${left_arm_prefix} ${hand} ${can_fd} + ${gravity_compensation_enabled} + ${gravity_compensation_use_kdl} + ${gravity_torque_mode} + ${gravity_scale} + ${gravity_tau_limit1} + ${gravity_tau_limit2} + ${gravity_tau_limit3} + ${gravity_tau_limit4} + ${gravity_tau_limit5} + ${gravity_tau_limit6} + ${gravity_tau_limit7} + ${kdl_urdf_path} + ${kdl_base_link} + ${kdl_tip_link if kdl_tip_link != '' else 'openarm_' + left_arm_prefix + 'link7'} ${control_gains['joint1']['kp']} ${control_gains['joint2']['kp']} ${control_gains['joint3']['kp']} @@ -93,6 +121,20 @@ ${right_arm_prefix} ${hand} ${can_fd} + ${gravity_compensation_enabled} + ${gravity_compensation_use_kdl} + ${gravity_torque_mode} + ${gravity_scale} + ${gravity_tau_limit1} + ${gravity_tau_limit2} + ${gravity_tau_limit3} + ${gravity_tau_limit4} + ${gravity_tau_limit5} + ${gravity_tau_limit6} + ${gravity_tau_limit7} + ${kdl_urdf_path} + ${kdl_base_link} + ${kdl_tip_link if kdl_tip_link != '' else 'openarm_' + right_arm_prefix + 'link7'} ${control_gains['joint1']['kp']} ${control_gains['joint2']['kp']} ${control_gains['joint3']['kp']}