Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[SW-1507] gripperless URDF for Spot #520

Merged
merged 5 commits into from
Nov 5, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions spot_description/launch/description.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,12 @@ def generate_launch_description() -> launch.LaunchDescription:
choices=["True", "true", "False", "false"],
description="Flag to enable putting frames at the feet",
),
DeclareLaunchArgument(
name="gripperless",
default_value="False",
choices=["True", "true", "False", "false"],
description="Flag to remove the gripper from the arm model",
),
DeclareLaunchArgument(
"tf_prefix", default_value='""', description="Apply namespace prefix to robot links and joints"
),
Expand All @@ -56,6 +62,8 @@ def generate_launch_description() -> launch.LaunchDescription:
LaunchConfiguration("arm"),
" feet:=",
LaunchConfiguration("feet"),
" gripperless:=",
LaunchConfiguration("gripperless"),
" tf_prefix:=",
LaunchConfiguration("tf_prefix"),
]
Expand Down
14 changes: 12 additions & 2 deletions spot_description/urdf/spot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,18 @@
<xacro:include filename="$(find spot_description)/urdf/spot.ros2_control.xacro" />

<!-- General parameters -->

<!-- String that will be prepended to all joints and links-->
<xacro:arg name="tf_prefix" default="" />

<!-- Set to true if Spot has an arm -->
<xacro:arg name="arm" default="false" />

<!-- Set to true if Spot has an arm but not a gripper -->
<xacro:arg name="gripperless" default="false" />

<!-- Set to true to put links at the feet of Spot -->
<xacro:arg name="feet" default="false" />
<xacro:arg name="tf_prefix" default="" />

<!-- Parameters for ROS 2 control -->
<xacro:arg name="add_ros2_control_tag" default="false" />
Expand All @@ -24,7 +33,8 @@
<xacro:load_spot
arm="$(arg arm)"
feet="$(arg feet)"
tf_prefix="$(arg tf_prefix)" />
tf_prefix="$(arg tf_prefix)"
gripperless="$(arg gripperless)"/>

<!-- Adding the ROS 2 control tags -->
<xacro:if value="$(arg add_ros2_control_tag)">
Expand Down
213 changes: 118 additions & 95 deletions spot_description/urdf/spot_arm_macro.urdf
Original file line number Diff line number Diff line change
@@ -1,7 +1,10 @@
<?xml version="1.0"?>
<robot name="spot_arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="load_arm" params="
tf_prefix">
tf_prefix gripperless custom_gripper_base_link">

<!-- Useful boolean variable for determining if custom gripper base link should be used in the xacro -->
<xacro:property name="use_custom_gripper_base_link" value="${gripperless and custom_gripper_base_link!=''}"/>

<link name="${tf_prefix}arm_link_sh0">
<visual>
Expand Down Expand Up @@ -201,107 +204,127 @@
upper="1.83259571459404613236" />
</joint>

<link name="${tf_prefix}arm_link_wr1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://spot_description/meshes/arm/visual/arm_link_wr1.obj" />
</geometry>
<material name="arm_link_wr1">
<color rgba="0.2 0.2 0.2 1" />
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/arm_link_wr1.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/front_jaw.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/middle_jaw.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/jaw_tooth.obj" />
</geometry>
</collision>
<inertial>
<origin rpy="0.006393076449033863 0.2928526604761865 -0.022814984050994802"
xyz="0.12516802549362183 0.00010137435310753062 -0.013997982256114483" />
<mass value="0.785" />
<inertia ixx="0.00076741362048185" ixy="0.0" ixz="0.0" iyy="0.0017628124054271809" iyz="0.0"
izz="0.0016818105865345951" />
</inertial>
</link>
<xacro:if value="${gripperless}">
<xacro:unless value="${use_custom_gripper_base_link}">
<!-- Here this link needs to still be defined as to not break WR1 joint but can't include the meshes below, as
these include parts of the gripper. Otherwise custom gripper base link will be used as the child of WR1 -->
<link name="${tf_prefix}arm_link_wr1" />
</xacro:unless>
</xacro:if>
<xacro:unless value="${gripperless}">
<link name="${tf_prefix}arm_link_wr1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://spot_description/meshes/arm/visual/arm_link_wr1.obj" />
</geometry>
<material name="arm_link_wr1">
<color rgba="0.2 0.2 0.2 1" />
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/arm_link_wr1.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/front_jaw.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/middle_jaw.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/jaw_tooth.obj" />
</geometry>
</collision>
<inertial>
<origin rpy="0.006393076449033863 0.2928526604761865 -0.022814984050994802"
xyz="0.12516802549362183 0.00010137435310753062 -0.013997982256114483" />
<mass value="0.785" />
<inertia ixx="0.00076741362048185" ixy="0.0" ixz="0.0" iyy="0.0017628124054271809" iyz="0.0"
izz="0.0016818105865345951" />
</inertial>
</link>
</xacro:unless>
<joint name="${tf_prefix}arm_wr1" type="revolute">
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
<axis xyz="1 0 0" />
<parent link="${tf_prefix}arm_link_wr0" />
<child link="${tf_prefix}arm_link_wr1" />
<!-- Child link can be different depending on gripperless status: -->
<xacro:if value="${use_custom_gripper_base_link}">
<!-- can optionally be the custom link specified via arg -->
<child link="${custom_gripper_base_link}" />
</xacro:if>
<xacro:unless value="${use_custom_gripper_base_link}">
<!-- else defaults to normal arm_link_wr1 -->
<child link="${tf_prefix}arm_link_wr1" />
</xacro:unless>
<limit effort="30.3" velocity="10.0" lower="-2.87979326579064354163"
upper="2.87979326579064354163" />
</joint>

<link name="${tf_prefix}arm_link_fngr">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://spot_description/meshes/arm/visual/arm_link_fngr.obj" />
</geometry>
<material name="arm_link_fngr">
<color rgba="0.2 0.2 0.2 1" />
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/left_hinge.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/left_finger.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/left_tooth.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/right_hinge.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/right_finger.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/right_tooth.obj" />
</geometry>
</collision>
<inertial>
<origin rpy="0.0003416659657240473 0.3751670012784243 -0.004058661249495721"
xyz="0.04787873849272728 -0.00020676758140325546 -0.01628788933157921" />
<mass value="0.2" />
<inertia ixx="0.0001439963634171048" ixy="0.0" ixz="0.0" iyy="0.0003007126997998294"
iyz="0.0" izz="0.0003912783268020657" />
</inertial>
</link>
<joint name="${tf_prefix}arm_f1x" type="revolute">
<origin xyz="0.11745 0 0.014820" rpy="0 0 0" />
<axis xyz="0.0 1.0 0.0" />
<parent link="${tf_prefix}arm_link_wr1" />
<child link="${tf_prefix}arm_link_fngr" />
<limit effort="15.32" velocity="10.0" lower="-1.57" upper="0.0" />
</joint>
<!-- Finger joint and link shouldn't be included if gripperless -->
<xacro:unless value="${gripperless}">
<link name="${tf_prefix}arm_link_fngr">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://spot_description/meshes/arm/visual/arm_link_fngr.obj" />
</geometry>
<material name="arm_link_fngr">
<color rgba="0.2 0.2 0.2 1" />
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/left_hinge.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/left_finger.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/left_tooth.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/right_hinge.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/right_finger.obj" />
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/right_tooth.obj" />
</geometry>
</collision>
<inertial>
<origin rpy="0.0003416659657240473 0.3751670012784243 -0.004058661249495721"
xyz="0.04787873849272728 -0.00020676758140325546 -0.01628788933157921" />
<mass value="0.2" />
<inertia ixx="0.0001439963634171048" ixy="0.0" ixz="0.0" iyy="0.0003007126997998294"
iyz="0.0" izz="0.0003912783268020657" />
</inertial>
</link>
<joint name="${tf_prefix}arm_f1x" type="revolute">
<origin xyz="0.11745 0 0.014820" rpy="0 0 0" />
<axis xyz="0.0 1.0 0.0" />
<parent link="${tf_prefix}arm_link_wr1" />
<child link="${tf_prefix}arm_link_fngr" />
<limit effort="15.32" velocity="10.0" lower="-1.57" upper="0.0" />
</joint>
</xacro:unless>
</xacro:macro>
</robot>
6 changes: 5 additions & 1 deletion spot_description/urdf/spot_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
<xacro:macro name="load_spot" params="
arm:=false
feet:=false
gripperless:=false
custom_gripper_base_link:=''
tf_prefix">

<link name="${tf_prefix}body">
Expand Down Expand Up @@ -417,7 +419,9 @@
<!-- Include Arm if necessary-->
<xacro:if value="${arm}">
<xacro:include filename="$(find spot_description)/urdf/spot_arm_macro.urdf" />
<xacro:load_arm tf_prefix="${tf_prefix}" />
<xacro:load_arm tf_prefix="${tf_prefix}"
gripperless="${gripperless}"
custom_gripper_base_link="${custom_gripper_base_link}" />
</xacro:if>

<!-- Include links at feet if necessary -->
Expand Down
Loading