Skip to content

Configure ada_description for Articulable Fork #52

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

Draft
wants to merge 29 commits into
base: main
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
29 commits
Select commit Hold shift + click to select a range
d0544a6
Update forque_assembly_joint macro to allow fixed, revolute, and cont…
jjaime2 Nov 7, 2024
7847a68
Add Articulable Fork XACRO and STL
jjaime2 Nov 8, 2024
f72a2f8
Rename AFMotor2_to_AFMotorFixture1 to AFMotor2_to_AFMotor1
jjaime2 Nov 11, 2024
c102e12
Format forque.xacro using xmllint
jjaime2 Nov 12, 2024
9d435d9
Rename Articulable Fork links and joints
jjaime2 Nov 12, 2024
0c81299
Add default configuration for Articulable Fork joints
jjaime2 Nov 12, 2024
1d20fda
Revert "Format forque.xacro using xmllint"
jjaime2 Dec 12, 2024
6efbe95
Add end_effector_tool configuration, remove use_forque configuration
jjaime2 Dec 12, 2024
1ac9d62
Conditionally modify fork URDF based on end_effector_tool
jjaime2 Dec 12, 2024
f463f1f
Collapse XACRO elements
jjaime2 Dec 12, 2024
b0a0e67
More formatting
jjaime2 Dec 12, 2024
1ef30d9
Rename forkTine_to_forque to af_forque_joint
jjaime2 Dec 12, 2024
5e961d8
Decouple ADAs description into a macro that is explicitly instantiate…
jjaime2 Dec 14, 2024
e2b14e8
Merge branch 'main' into jjaime2/articulable_fork_description
jjaime2 Dec 18, 2024
9c4ac8c
Run pre-commit
jjaime2 Dec 18, 2024
0967dad
Remove actuator, transmission, and gazebo configurations
jjaime2 Dec 18, 2024
5c68db3
Merge branch 'main' into jjaime2/articulable_fork_description
jjaime2 Jan 14, 2025
703ff69
Add comments explaining macro imports in ada.xacro
jjaime2 Jan 29, 2025
8acecd5
Remove base_parent argument for ada macro, use root by default
jjaime2 Jan 29, 2025
9f2f8f7
Rename dummy_default_value to forque_assembly_dummy_default_value
jjaime2 Jan 29, 2025
6b6e5ba
Fix indentation
jjaime2 Jan 29, 2025
be387a5
Revert change to FTMount joint_origin_xyz
jjaime2 Jan 29, 2025
a5b43c5
Remove broken error messages, remove fixed parameter for forque_assem…
jjaime2 Jan 29, 2025
4d3c85c
Add comment for ada macro
jjaime2 Jan 29, 2025
753d5c7
Fix axis of rotation for af_joint_2
jjaime2 Feb 3, 2025
95f6531
Adjust af_joint_base joint_origin_xyz
jjaime2 Feb 3, 2025
6d39728
Remove slight rotation of forkHandle_to_FTMount joint since updated f…
jjaime2 Feb 3, 2025
f4aed22
Adjust af_joint_base joint_origin_xyz
jjaime2 Feb 3, 2025
91e15b1
Revert "Remove slight rotation of forkHandle_to_FTMount joint since u…
jjaime2 Feb 18, 2025
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
15 changes: 8 additions & 7 deletions ada_description/launch/view_ada.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -60,23 +60,24 @@ def generate_launch_description():
declared_arguments.append(
DeclareLaunchArgument(
"description_file",
default_value="ada.xacro",
default_value="ada_standalone.xacro",
description="URDF/XACRO description file with the robot.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"use_forque",
default_value="false",
description="If the forque apparatus is being used.",
"end_effector_tool",
default_value="none",
description="The end-effector tool being used: 'none', 'fork', 'articulable_fork'",
choices=["none", "fork", "articulable_fork"],
)
)

# Initialize Arguments
# General arguments
description_package = LaunchConfiguration("description_package")
description_file = LaunchConfiguration("description_file")
use_forque = LaunchConfiguration("use_forque")
end_effector_tool = LaunchConfiguration("end_effector_tool")

robot_description_content = Command(
[
Expand All @@ -86,8 +87,8 @@ def generate_launch_description():
[FindPackageShare(description_package), "urdf", description_file]
),
" ",
"use_forque:=",
use_forque,
"end_effector_tool:=",
end_effector_tool,
]
)
robot_description = {
Expand Down
Binary file added ada_description/meshes/forque/AFStabilizer.stl
Binary file not shown.
Binary file added ada_description/meshes/forque/XC-430_idle.stl
Binary file not shown.
Binary file added ada_description/meshes/forque/fr12-h103.stl
Binary file not shown.
Binary file added ada_description/meshes/forque/fr12-s101.stl
Binary file not shown.
Binary file not shown.
24 changes: 24 additions & 0 deletions ada_description/rviz/view_robot.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,30 @@ Visualization Manager:
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
af_link_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
af_link_1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
af_motor_fixture_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
af_link_2:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
af_ft_adapter_link:
Alpha: 1
Show Axes: false
Show Trail: false
FT:
Alpha: 1
Show Axes: false
Expand Down
103 changes: 52 additions & 51 deletions ada_description/urdf/ada.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -12,65 +12,66 @@
xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering"
xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable"
xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics"
xmlns:xacro="http://www.ros.org/wiki/xacro" name="ada">
xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:include filename="$(find ada_description)/urdf/forque/forque.xacro"/>
<xacro:include filename="$(find ada_description)/urdf/camera/camera.xacro"/>
<xacro:include filename="$(find ada_description)/urdf/j2n6s200.xacro"/>
<!-- Robot name must be defined in the Xacro file that instantiates the ada macro -->
<xacro:macro name="ada" params="end_effector_tool">
<!-- Import macros associated with forque, robot, and camera. Macros are added to the tree below -->
<xacro:include filename="$(find ada_description)/urdf/forque/forque.xacro"/>
<xacro:include filename="$(find ada_description)/urdf/camera/camera.xacro"/>
<xacro:include filename="$(find ada_description)/urdf/j2n6s200.xacro"/>

<xacro:arg name="use_forque" default="true"/>

<link name="root"/>

<link name="root_tilt"/>
<joint name="robot_tilt" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0" />
<child link="root_tilt" />
<parent link="root" />
<axis xyz="-1 0 0"/>
<!-- effort copied from j2n6s200 joint 2, velocity is max velocity the wheelchair can tilt,
lower and upper limits generously encompass the range of the wheelchair's tilt-->
<limit effort="80" velocity="0.15" lower="${-J_PI}" upper="${J_PI}"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="root"/>
<link name="root_tilt"/>
<joint name="robot_tilt" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0" />
<child link="root_tilt" />
<parent link="root" />
<axis xyz="-1 0 0"/>
<!-- effort copied from j2n6s200 joint 2, velocity is max velocity the wheelchair can tilt,
lower and upper limits generously encompass the range of the wheelchair's tilt-->
<limit effort="80" velocity="0.15" lower="${-J_PI}" upper="${J_PI}"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>

<xacro:property name="robot_root" value="root_tilt" />
<xacro:property name="robot_root" value="root_tilt" />

<xacro:j2n6s200 base_parent="${robot_root}"/>
<xacro:j2n6s200 base_parent="${robot_root}"/>

<xacro:camera_assembly base_parent="j2n6s200_link_6" base_xyz="0.0165 0 0.0011" base_rpy="${3*J_PI/2} 0 ${3*J_PI/2}"/>
<xacro:camera_assembly base_parent="j2n6s200_link_6" base_xyz="0.0165 0 0.0011" base_rpy="${3*J_PI/2} 0 ${3*J_PI/2}"/>

<!-- Hard-coded Extrinsics -->
<link name="camera_link" />
<joint name="extrinsics" type="fixed">
<origin xyz="0.0194 -0.01606 0.029014" rpy="0.17234 -1.56127 2.96967" />
<parent link="cameraMount" />
<child link="camera_link" />
</joint>
<!-- Copy Realsense in case of simulation -->
<!--
<link name="camera_color_optical_frame" />
<joint name="optical_republish" type="fixed">
<origin xyz="0.000 -0.015 0.000" rpy="-1.564 0.000 -1.573" />
<parent link="camera_link" />
<child link="camera_color_optical_frame" />
</joint>
-->
<!-- Hard-coded Extrinsics -->
<link name="camera_link" />
<joint name="extrinsics" type="fixed">
<origin xyz="0.0194 -0.01606 0.029014" rpy="0.17234 -1.56127 2.96967" />
<parent link="cameraMount" />
<child link="camera_link" />
</joint>
<!-- Copy Realsense in case of simulation -->
<!--
<link name="camera_color_optical_frame" />
<joint name="optical_republish" type="fixed">
<origin xyz="0.000 -0.015 0.000" rpy="-1.564 0.000 -1.573" />
<parent link="camera_link" />
<child link="camera_color_optical_frame" />
</joint>
-->

<xacro:forque_assembly_link link_name="FTArmMount" link_mesh="2024_01_18_FTArmMount" mass="0.03783" cog="0.010957 -0.019223 -0.03777">
<inertia ixx="0.000018817" iyy="0.00001119989" iyz="-0.00000120296" izz="0.000026883" ixy="-0.0000003327" ixz="-0.000000092476"/>
</xacro:forque_assembly_link>
<xacro:forque_assembly_joint joint_name="FTArmMount_to_arm" parent="j2n6s200_link_6" child="FTArmMount" joint_origin_xyz="0.0065 -0.011 -0.0075" joint_origin_rpy="${J_PI/2} 0 ${J_PI/2}"/>
<xacro:forque_assembly_link link_name="FTArmMount" link_mesh="2024_01_18_FTArmMount" mass="0.03783" cog="0.010957 -0.019223 -0.03777">
<inertia ixx="0.000018817" iyy="0.00001119989" iyz="-0.00000120296" izz="0.000026883" ixy="-0.0000003327" ixz="-0.000000092476"/>
</xacro:forque_assembly_link>
<xacro:forque_assembly_joint joint_name="FTArmMount_to_arm" type="fixed" parent="j2n6s200_link_6" child="FTArmMount" joint_axis_xyz="0 0 1" joint_origin_xyz="0.0065 -0.011 -0.0075" joint_origin_rpy="${J_PI/2} 0 ${J_PI/2}"/>

<xacro:if value="$(arg use_forque)">
<xacro:forque_assembly base_parent="FTArmMount"/>
<xacro:unless value="${end_effector_tool == 'none'}">
<xacro:forque_assembly base_parent="FTArmMount" end_effector_tool="${end_effector_tool}"/>

<link name="FTSensor" />
<joint name="EE_to_FTSensor" type="fixed">
<child link="FTSensor"/>
<parent link="j2n6s200_end_effector"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.092"/>
</joint>
</xacro:if>
<link name="FTSensor" />
<joint name="EE_to_FTSensor" type="fixed">
<child link="FTSensor"/>
<parent link="j2n6s200_end_effector"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.092"/>
</joint>
</xacro:unless>
</xacro:macro>

</robot>
25 changes: 25 additions & 0 deletions ada_description/urdf/ada_standalone.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<?xml version="1.0"?>
<robot xmlns:xi="http://www.w3.org/2001/XInclude"
xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz"
xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"
xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering"
xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable"
xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics"
xmlns:xacro="http://www.ros.org/wiki/xacro"
name="ada">

<xacro:arg name="end_effector_tool" default="fork" />

<xacro:include filename="$(find ada_description)/urdf/ada.xacro" />

<xacro:property name="root" value="root" />
<xacro:property name="end_effector_tool" value="$(arg end_effector_tool)" />
<xacro:ada end_effector_tool="${end_effector_tool}" />

</robot>
84 changes: 63 additions & 21 deletions ada_description/urdf/forque/forque.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<xacro:property name="default_inertial">
<inertia ixx="0.000005" iyy="0.000005" iyz="0" izz="0.000005" ixy="0" ixz="0"/>
</xacro:property>
<xacro:property name="forque_assembly_dummy_default_value" value="1234567890"/>


<xacro:macro name="forque_assembly_link" params="link_name link_mesh mass:=0 cog:='0 0 0' *inertia">
Expand Down Expand Up @@ -48,57 +49,98 @@
</link>
</xacro:macro>

<xacro:macro name="forque_assembly_joint" params="joint_name parent child joint_origin_xyz joint_origin_rpy">
<joint name="${joint_name}" type="fixed">
<parent link="${parent}"/>
<child link="${child}"/>
<axis xyz="0 0 1"/>
<origin xyz="${joint_origin_xyz}" rpy="${joint_origin_rpy}"/>
</joint>
<xacro:macro name="forque_assembly_joint" params="joint_name type parent child joint_axis_xyz joint_origin_xyz joint_origin_rpy joint_lower_limit:=${forque_assembly_dummy_default_value} joint_upper_limit:=${forque_assembly_dummy_default_value} joint_velocity_limit:=${forque_assembly_dummy_default_value} joint_torque_limit:=${forque_assembly_dummy_default_value}">

<joint name="${joint_name}" type="${type}">
<parent link="${parent}"/>
<child link="${child}"/>
<axis xyz="${joint_axis_xyz}"/>
<xacro:if value="${type == 'revolute'}">
<limit
effort="${joint_torque_limit}"
velocity="${joint_velocity_limit}"
lower="${joint_lower_limit}"
upper="${joint_upper_limit}"/>
</xacro:if>
<xacro:if value="${type == 'continuous'}">
<limit effort="${joint_torque_limit}" velocity="${joint_velocity_limit}"/>
</xacro:if>
<origin xyz="${joint_origin_xyz}" rpy="${joint_origin_rpy}"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
</xacro:macro>


<xacro:macro name="forque_assembly" params="base_parent use_antenna:=false">
<xacro:macro name="forque_assembly" params="base_parent end_effector_tool use_antenna:=false">

<xacro:forque_assembly_link link_name="FTMount" link_mesh="2024_01_18_FTMount" mass="0.103" cog="0.010934 -0.138522 -0.05066">
<inertia ixx="0.00017623" iyy="0.000068428" iyz="-0.00001757133" izz="0.00021455" ixy="0.00000095729" ixz="-0.0000000562908"/>
</xacro:forque_assembly_link>
<xacro:forque_assembly_joint joint_name="FTMount_to_world" parent="${base_parent}" child="FTMount" joint_origin_xyz="0 0 -0.005" joint_origin_rpy="0 0 0"/>
<xacro:forque_assembly_joint joint_name="FTMount_to_world" type="fixed" parent="${base_parent}" child="FTMount" joint_axis_xyz="0 0 1" joint_origin_xyz="0 0 -0.005" joint_origin_rpy="0 0 0"/>

<xacro:forque_assembly_link link_name="FT" link_mesh="2023_03_09_wirelessFT" mass="0.280" cog="0.0111446 -0.0882070 -0.0544936">
<inertia ixx="0.000543925" iyy="0.000165428" iyz="-0.00000001487288" izz="0.000691232" ixy="-0.00000128367" ixz="0"/>
</xacro:forque_assembly_link>
<xacro:forque_assembly_joint joint_name="FT_to_FTMount" parent="FTMount" child="FT" joint_origin_xyz="0 0 0" joint_origin_rpy="0 0 0"/>
<xacro:forque_assembly_joint joint_name="FT_to_FTMount" type="fixed" parent="FTMount" child="FT" joint_axis_xyz="0 0 1" joint_origin_xyz="0 0 0" joint_origin_rpy="0 0 0"/>


<xacro:if value="${use_antenna}">
<xacro:forque_assembly_link link_name="FTAntenna" link_mesh="2023_03_09_wirelessFTAntenna" mass="0.018" cog="-0.0162965 0.0666626 -0.0545096">
<xacro:insert_block name="default_inertial"/>
</xacro:forque_assembly_link>
<xacro:forque_assembly_joint joint_name="FTAntenna_to_FT" parent="FT" child="FTAntenna" joint_origin_xyz="0 0 0" joint_origin_rpy="0 0 0"/>
</xacro:if>
<xacro:forque_assembly_link link_name="FTAntenna" link_mesh="2023_03_09_wirelessFTAntenna" mass="0.018" cog="-0.0162965 0.0666626 -0.0545096">
<xacro:insert_block name="default_inertial"/>
</xacro:forque_assembly_link>
<xacro:forque_assembly_joint joint_name="FTAntenna_to_FT" type="fixed" parent="FT" child="FTAntenna" joint_axis_xyz="0 0 1" joint_origin_xyz="0 0 0" joint_origin_rpy="0 0 0"/>
</xacro:if>

<xacro:forque_assembly_link link_name="forkHandle" link_mesh="2024_06_24_forkHandleHollow" mass="0.028" cog="0.011097 -0.162629 -0.011948">
<inertia ixx="0.00003114" iyy="0.000011867" iyz="0.00000054005" izz="0.000038478" ixy="-0.00000050626" ixz="0.000000082271"/>
</xacro:forque_assembly_link>

<!-- The slight rotation was manually added due to empirical deformations in the robot gripped, such that the fingers and fork handle were slightly pitched up relative to the wrist. -->
<xacro:forque_assembly_joint joint_name="forkHandle_to_FTMount" parent="FTMount" child="forkHandle" joint_origin_xyz="0 0.005 0.0013" joint_origin_rpy="-0.025 0 -0.0065"/>
<xacro:forque_assembly_joint joint_name="forkHandle_to_FTMount" type="fixed" parent="FTMount" child="forkHandle" joint_axis_xyz="0 0 1" joint_origin_xyz="0 0.005 0.0013" joint_origin_rpy="-0.025 0 -0.0065"/>

<xacro:forque_assembly_link link_name="forkHandleCover" link_mesh="2024_06_24_forkHandleCover" mass="0.004" cog="0.011157 -0.168451 0.006404">
<inertia ixx="0.0000027878" iyy="0.00000064518" iyz="0.00000016201" izz="0.000003363634" ixy="0.00000000012805" ixz="0.00000000006585"/>
</xacro:forque_assembly_link>
<xacro:forque_assembly_joint joint_name="forkHandleCover_to_forkHandle" parent="forkHandle" child="forkHandleCover" joint_origin_xyz="0 0 0" joint_origin_rpy="0 0 0"/>
<xacro:forque_assembly_joint joint_name="forkHandleCover_to_forkHandle" type="fixed" parent="forkHandle" child="forkHandleCover" joint_axis_xyz="0 0 1" joint_origin_xyz="0 0 0" joint_origin_rpy="0 0 0"/>
<xacro:if value="${end_effector_tool == 'articulable_fork'}">
<xacro:forque_assembly_link link_name="af_link_base" link_mesh="fr12-h103" mass="0.0907185" cog="0.0 0.0 0.0">
<xacro:insert_block name="default_inertial"/>
</xacro:forque_assembly_link>
<xacro:forque_assembly_joint joint_name="af_joint_base" type="fixed" parent="forkHandle" child="af_link_base" joint_axis_xyz="0 0 1" joint_origin_xyz="0.010929196 -0.2826805 -0.0091" joint_origin_rpy="0 0 0"/>

<xacro:forque_assembly_link link_name="af_link_1" link_mesh="XC-430_idle" mass="0.065" cog="0.21641853 -14.751192 -16.796092">
<inertia ixx="18680.931" iyy="9585.9138" iyz="-845.46678" izz="17346.641" ixy="1.3348619" ixz="-45.354028"/>
</xacro:forque_assembly_link>
<xacro:forque_assembly_joint joint_name="af_joint_1" type="revolute" parent="af_link_base" child="af_link_1" joint_axis_xyz="0 0 1" joint_origin_xyz="0 0 0" joint_origin_rpy="${J_PI/2} 0 ${J_PI/2}" joint_lower_limit="${-J_PI/2}" joint_upper_limit="${J_PI/2}" joint_velocity_limit="1" joint_torque_limit="1.4"/>

<xacro:forque_assembly_link link_name="af_motor_fixture_link" link_mesh="fr12-s101" mass="0.0453592" cog="0 0 0">
<xacro:insert_block name="default_inertial"/>
</xacro:forque_assembly_link>
<xacro:forque_assembly_joint joint_name="af_motor_fixture_joint_1" type="fixed" parent="af_link_1" child="af_motor_fixture_link" joint_axis_xyz="0 0 1" joint_origin_xyz="0 0 0" joint_origin_rpy="0 ${-J_PI/2} 0"/>

<xacro:forque_assembly_link link_name="af_link_2" link_mesh="XC-430_idle" mass="0.065" cog="0.21641853 -14.751192 -16.796092">
<inertia ixx="18680.931" iyy="9585.9138" iyz="-845.46678" izz="17346.641" ixy="1.3348619" ixz="-45.354028"/>
</xacro:forque_assembly_link>
<xacro:forque_assembly_joint joint_name="af_motor_fixture_joint_2" type="fixed" parent="af_link_1" child="af_link_2" joint_axis_xyz="0 0 1" joint_origin_xyz="-0.03825 0 0" joint_origin_rpy="0 ${-J_PI/2} 0"/>

<xacro:forque_assembly_link link_name="af_ft_adapter_link" link_mesh="roll_to_ft_adapter" mass="0.001" cog="0 0 0">
<xacro:insert_block name="default_inertial"/>
</xacro:forque_assembly_link>
<xacro:forque_assembly_joint joint_name="af_joint_2" type="revolute" parent="af_link_2" child="af_ft_adapter_link" joint_axis_xyz="0 -1 0" joint_origin_xyz="0 0 0.019" joint_origin_rpy="${-J_PI/2} 0 0" joint_lower_limit="${-J_PI}" joint_upper_limit="${J_PI}" joint_velocity_limit="1" joint_torque_limit="1.4"/>
</xacro:if>

<xacro:forque_assembly_link link_name="forque" link_mesh="ATI-9105-TW-NANO25-E" mass="0.0634" cog="0.0124692 0.0137169 0.010558">
<inertia ixx="0.000005235822" iyy="0.000006264852" iyz="-0.00000004033694" izz="0.00000640797" ixy="-0.0000003129932" ixz="0.000000013798"/>
</xacro:forque_assembly_link>
<xacro:forque_assembly_joint joint_name="forque_to_forkHandle" parent="forkHandle" child="forque" joint_origin_xyz="-0.00634 -0.222553 -0.004286" joint_origin_rpy="${J_PI/2} ${J_PI/3} 0"/>
<xacro:if value="${end_effector_tool == 'articulable_fork'}">
<xacro:forque_assembly_joint joint_name="af_forque_joint" type="fixed" parent="af_ft_adapter_link" child="forque" joint_axis_xyz="0 0 1" joint_origin_xyz="-0.0175 -0.011 0.004" joint_origin_rpy="${J_PI/2} ${J_PI/3} 0"/>
</xacro:if>
<xacro:if value="${end_effector_tool == 'fork'}">
<xacro:forque_assembly_joint joint_name="af_forque_joint" type="fixed" parent="forkHandle" child="forque" joint_axis_xyz="0 0 1" joint_origin_xyz="-0.00634 -0.222553 -0.004286" joint_origin_rpy="${J_PI/2} ${J_PI/3} 0"/>
</xacro:if>

<xacro:forque_assembly_link link_name="forkTine" link_mesh="fork_tine" mass="0.024" cog="0.013090 0.0180789 0.0445231">
<inertia ixx="0.0000098769" iyy="0.000009848103" iyz="0.00000057639" izz="0.0000015674" ixy="0.000000000806182" ixz="-0.00000000296036"/>
</xacro:forque_assembly_link>
<xacro:forque_assembly_joint joint_name="forkTine_to_forque" parent="forque" child="forkTine" joint_origin_xyz="-0.0054 0.008 0.093" joint_origin_rpy="0 ${J_PI} ${240*J_PI/180}"/>
<xacro:forque_assembly_joint joint_name="forkTine_to_forque" type="fixed" parent="forque" child="forkTine" joint_axis_xyz="0 0 1" joint_origin_xyz="-0.0054 0.008 0.093" joint_origin_rpy="0 ${J_PI} ${240*J_PI/180}"/>

<link name="forkTip" />
<joint name="forkTip_to_forkTine" type="fixed">
Expand Down
Loading