Skip to content

Commit

Permalink
Baseline gripperless parameter
Browse files Browse the repository at this point in the history
  • Loading branch information
Katie Hughes committed Oct 29, 2024
1 parent e3992eb commit d2859b0
Show file tree
Hide file tree
Showing 3 changed files with 65 additions and 60 deletions.
2 changes: 2 additions & 0 deletions spot_description/urdf/spot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@

<!-- General parameters -->
<xacro:arg name="arm" default="false" />
<xacro:arg name="gripperless" default="false" />
<xacro:arg name="feet" default="false" />
<xacro:arg name="tf_prefix" default="" />

Expand All @@ -23,6 +24,7 @@
<!-- Load Spot -->
<xacro:load_spot
arm="$(arg arm)"
gripperless="$(arg gripperless)"
feet="$(arg feet)"
tf_prefix="$(arg tf_prefix)" />

Expand Down
120 changes: 61 additions & 59 deletions spot_description/urdf/spot_arm_macro.urdf
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?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">

<link name="${tf_prefix}arm_link_sh0">
<visual>
Expand Down Expand Up @@ -217,9 +217,9 @@
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/front_jaw.obj" />
</geometry>
<geometry>
<mesh filename="package://spot_description/meshes/arm/collision/front_jaw.obj" />
</geometry>
</collision>
<collision>
<geometry>
Expand Down Expand Up @@ -248,60 +248,62 @@
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>
<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>
3 changes: 2 additions & 1 deletion spot_description/urdf/spot_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
<xacro:macro name="load_spot" params="
arm:=false
feet:=false
gripperless:=false
tf_prefix">

<link name="${tf_prefix}body">
Expand Down Expand Up @@ -417,7 +418,7 @@
<!-- 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}" />
</xacro:if>

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

0 comments on commit d2859b0

Please sign in to comment.