openarm_description/urdf/robot/v10.urdf.xacro

121 lines
5.0 KiB
Plaintext
Raw Permalink Normal View History

2025-07-22 07:07:59 +00:00
<?xml version='1.0' encoding='utf-8'?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm">
<xacro:include filename="$(find openarm_description)/urdf/robot/openarm_robot.xacro"/>
<xacro:arg name="arm_type" default="v10" />
<xacro:arg name="body_type" default="v10" />
<xacro:arg name="ee_type" default="openarm_hand" />
<xacro:arg name="no_prefix" default="false"/>
<xacro:arg name="hand" default="true" />
<xacro:if value="$(eval ee_type == 'none')">
<xacro:property name="hand" value="false"/>
</xacro:if>
<xacro:arg name="parent" default="world" />
<xacro:arg name="xyz" default="0 0 0" />
<xacro:arg name="rpy" default="0 0 0" />
<xacro:arg name="ros2_control" default="false" />
2026-03-20 08:00:33 +00:00
<xacro:arg name="can_interface" default="can0" />
2025-07-22 07:07:59 +00:00
<xacro:arg name="left_can_interface" default="can1" />
2026-03-20 08:00:33 +00:00
<xacro:arg name="right_can_interface" default="can0" />
2026-02-27 06:45:17 +00:00
2025-07-22 07:07:59 +00:00
<xacro:arg name="left_arm_prefix" default="left_" />
<xacro:arg name="right_arm_prefix" default="right_" />
<xacro:arg name="use_fake_hardware" default="false" />
<xacro:arg name="fake_sensor_commands" default="false" />
<xacro:arg name="bimanual" default="false" />
<xacro:arg name="right_arm_base_xyz" default="0.0 -0.031 0.698" />
<xacro:arg name="right_arm_base_rpy" default="1.5708 0 0" />
<xacro:arg name="left_arm_base_xyz" default="0.0 0.031 0.698" />
<xacro:arg name="left_arm_base_rpy" default="-1.5708 0 0" />
2026-02-27 06:45:17 +00:00
<xacro:arg name="can_fd" default="false" />
2026-03-20 08:00:33 +00:00
<xacro:arg name="gravity_compensation_enabled" default="false" />
<xacro:arg name="gravity_compensation_use_kdl" default="true" />
<xacro:arg name="gravity_torque_mode" default="false" />
<xacro:arg name="gravity_scale" default="1.0" />
<xacro:arg name="gravity_tau_limit1" default="2.0" />
<xacro:arg name="gravity_tau_limit2" default="2.0" />
<xacro:arg name="gravity_tau_limit3" default="2.0" />
<xacro:arg name="gravity_tau_limit4" default="2.0" />
<xacro:arg name="gravity_tau_limit5" default="2.0" />
<xacro:arg name="gravity_tau_limit6" default="2.0" />
<xacro:arg name="gravity_tau_limit7" default="2.0" />
2026-03-31 06:25:39 +00:00
<xacro:arg name="gripper_gravity_tau" default="0.0" />
<xacro:arg name="gripper_gravity_tau_limit" default="0.5" />
2026-03-20 08:00:33 +00:00
<xacro:arg name="kdl_urdf_path" default="/tmp/openarm_bimanual_runtime.urdf" />
<xacro:arg name="kdl_base_link" default="openarm_body_link0" />
<xacro:arg name="kdl_tip_link" default="" />
2025-07-22 07:07:59 +00:00
<xacro:openarm_robot
arm_type="v10"
body_type="v10"
joint_limits="${xacro.load_yaml('$(find openarm_description)/config/arm/v10/joint_limits.yaml')}"
control_gains="${xacro.load_yaml('$(find openarm_description)/config/arm/v10/control_gains.yaml')}"
2025-07-22 07:07:59 +00:00
inertials="${xacro.load_yaml('$(find openarm_description)/config/arm/v10/inertials.yaml')}"
kinematics="${xacro.load_yaml('$(find openarm_description)/config/arm/v10/kinematics.yaml')}"
kinematics_link="${xacro.load_yaml('$(find openarm_description)/config/arm/v10/kinematics_link.yaml')}"
kinematics_offset="${xacro.load_yaml('$(find openarm_description)/config/arm/v10/kinematics_offset.yaml')}"
body_inertials="${xacro.load_yaml('$(find openarm_description)/config/body/v10/inertials.yaml')}"
body_kinematics="${xacro.load_yaml('$(find openarm_description)/config/body/v10/kinematics.yaml')}"
body_kinematics_link="${xacro.load_yaml('$(find openarm_description)/config/body/v10/kinematics.yaml')}"
ee_kinematics_link="${xacro.load_yaml('$(find openarm_description)/config/hand/openarm_hand/kinematics_link.yaml')}"
hand="$(arg hand)"
ee_type="$(arg ee_type)"
ros2_control="$(arg ros2_control)"
can_interface="$(arg can_interface)"
left_can_interface="$(arg left_can_interface)"
right_can_interface="$(arg right_can_interface)"
left_arm_prefix="$(arg left_arm_prefix)"
right_arm_prefix="$(arg right_arm_prefix)"
use_fake_hardware="$(arg use_fake_hardware)"
fake_sensor_commands="$(arg fake_sensor_commands)"
no_prefix="$(arg no_prefix)"
arm_prefix=""
body_prefix=""
arm_connected_to="base"
body_connected_to="world"
bimanual="$(arg bimanual)"
right_arm_base_xyz="$(arg right_arm_base_xyz)"
left_arm_base_xyz="$(arg left_arm_base_xyz)"
right_arm_base_rpy="$(arg right_arm_base_rpy)"
left_arm_base_rpy="$(arg left_arm_base_rpy)"
can_fd="$(arg can_fd)"
2026-03-20 08:00:33 +00:00
gravity_compensation_enabled="$(arg gravity_compensation_enabled)"
gravity_compensation_use_kdl="$(arg gravity_compensation_use_kdl)"
gravity_torque_mode="$(arg gravity_torque_mode)"
gravity_scale="$(arg gravity_scale)"
gravity_tau_limit1="$(arg gravity_tau_limit1)"
gravity_tau_limit2="$(arg gravity_tau_limit2)"
gravity_tau_limit3="$(arg gravity_tau_limit3)"
gravity_tau_limit4="$(arg gravity_tau_limit4)"
gravity_tau_limit5="$(arg gravity_tau_limit5)"
gravity_tau_limit6="$(arg gravity_tau_limit6)"
gravity_tau_limit7="$(arg gravity_tau_limit7)"
2026-03-31 06:25:39 +00:00
gripper_gravity_tau="$(arg gripper_gravity_tau)"
gripper_gravity_tau_limit="$(arg gripper_gravity_tau_limit)"
2026-03-20 08:00:33 +00:00
kdl_urdf_path="$(arg kdl_urdf_path)"
kdl_base_link="$(arg kdl_base_link)"
kdl_tip_link="$(arg kdl_tip_link)"
2025-07-22 07:07:59 +00:00
/>
</robot>