Skip to content
Open
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
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,10 @@
# modification, is not permitted without the express permission
# of Clearpath Robotics.
from clearpath_config.manipulators.types.arms import Franka
from clearpath_config.manipulators.types.grippers import FrankaGripper
from clearpath_config.manipulators.types.grippers import (
FrankaGripper,
Robotiq2F140
)
from clearpath_config.manipulators.types.manipulator import (
BaseManipulator,
ManipulatorPose
Expand Down Expand Up @@ -88,9 +91,18 @@ def __init__(self, manipulator):
super().__init__(manipulator)
self.parameters[self.NAME] = f'{manipulator.name}_{manipulator.arm_id}'

class Robotiq2F140SemanticDescription(BaseSemanticDescription):

def __init__(self, manipulator):
super().__init__(manipulator)
urdf_parameters = dict(manipulator.get_urdf_parameters())
self.parameters[Robotiq2F140.PADDING] = f"{
urdf_parameters.get(Robotiq2F140.PADDING, 'true')}"

MODEL = {
Franka.MANIPULATOR_MODEL: FrankaSemanticDescription,
FrankaGripper.MANIPULATOR_MODEL: FrankaSemanticDescription
FrankaGripper.MANIPULATOR_MODEL: FrankaSemanticDescription,
Robotiq2F140.MANIPULATOR_MODEL: Robotiq2F140SemanticDescription
}

def __new__(cls, manipulator: BaseManipulator) -> BaseManipulator:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,15 @@
</group_state>
</xacro:macro>

<xacro:macro name="robotiq_2f_140" params="name">
<xacro:macro name="robotiq_2f_140" params="name padding:=true">

<xacro:if value="${padding}">
<xacro:property name="upper_finger_joint_limit" value="0.7"/>
</xacro:if>
<xacro:unless value="${padding}">
<xacro:property name="upper_finger_joint_limit" value="0.767"/>
</xacro:unless>

<group name="${name}">
<joint name="${name}_finger_joint"/>
<joint name="${name}_left_inner_knuckle_joint"/>
Expand All @@ -26,12 +34,15 @@
<xacro:robotiq_2f_140_group_state
name="${name}"
group_state="close"
joint_positions="${[0.7]}"
joint_positions="${[upper_finger_joint_limit]}"
/>

<disable_collisions link1="${name}_left_inner_knuckle" link2="${name}_left_inner_finger" reason="User"/>
<disable_collisions link1="${name}_right_inner_knuckle" link2="${name}_right_inner_finger" reason="User"/>
<disable_collisions link1="${name}_left_outer_knuckle" link2="${name}_left_inner_knuckle" reason="User"/>
<disable_collisions link1="${name}_right_outer_knuckle" link2="${name}_right_inner_knuckle" reason="User"/>
<xacro:if value="${padding}">
<disable_collisions link1="${name}_right_inner_finger_pad" link2="${name}_left_inner_finger_pad" reason="User"/>
</xacro:if>
</xacro:macro>
</robot>
Original file line number Diff line number Diff line change
Expand Up @@ -16,11 +16,18 @@
sim_isaac:=false
isaac_joint_commands:=/isaac_joint_commands
isaac_joint_states:=/isaac_joint_states
com_port:=/dev/ttyUSB0">
com_port:=/dev/ttyUSB0
padding:=true">

<!-- Variables Mappings -->
<xacro:property name="prefix" value="${name}_"/>
<xacro:property name="stroke" value="140"/>
<xacro:if value="${padding}">
<xacro:property name="upper_finger_joint_limit" value="0.7"/>
</xacro:if>
<xacro:unless value="${padding}">
<xacro:property name="upper_finger_joint_limit" value="0.767"/>
</xacro:unless>

<!-- this is a temporary link to rotate the 2f-140 gripper to match the 2f-85 -->
<link name="${prefix}robotiq_base_link"/>
Expand Down Expand Up @@ -213,7 +220,7 @@
<parent link="${prefix}robotiq_140_base_link" />
<child link="${prefix}left_outer_knuckle" />
<axis xyz="-1 0 0" />
<limit lower="0" upper="0.7" velocity="2.0" effort="1000" />
<limit lower="0" upper="${upper_finger_joint_limit}" velocity="2.0" effort="1000" />
</joint>
<xacro:finger_joints prefix="${prefix}" fingerprefix="left" reflect="1.0"/>
</xacro:macro>
Expand All @@ -224,7 +231,7 @@
<parent link="${prefix}robotiq_140_base_link" />
<child link="${prefix}right_outer_knuckle" />
<axis xyz="1 0 0" />
<limit lower="-0.725" upper="0.725" velocity="2.0" effort="1000" />
<limit lower="-0.775" upper="0.775" velocity="2.0" effort="1000" />
<mimic joint="${prefix}finger_joint" multiplier="-1" offset="0" />
</joint>
<xacro:finger_joints prefix="${prefix}" fingerprefix="right" reflect="-1.0"/>
Expand Down Expand Up @@ -274,14 +281,18 @@
<xacro:outer_finger_joint prefix="${prefix}" fingerprefix="${fingerprefix}"/>
<xacro:inner_knuckle_joint prefix="${prefix}" fingerprefix="${fingerprefix}" reflect="${reflect}"/>
<xacro:inner_finger_joint prefix="${prefix}" fingerprefix="${fingerprefix}"/>
<xacro:inner_finger_pad_joint prefix="${prefix}" fingerprefix="${fingerprefix}"/>
<xacro:if value="${padding}">
<xacro:inner_finger_pad_joint prefix="${prefix}" fingerprefix="${fingerprefix}"/>
</xacro:if>
</xacro:macro>

<xacro:macro name="finger_links" params="prefix fingerprefix stroke">
<xacro:outer_knuckle prefix="${prefix}" fingerprefix="${fingerprefix}" stroke="${stroke}"/>
<xacro:outer_finger prefix="${prefix}" fingerprefix="${fingerprefix}" stroke="${stroke}"/>
<xacro:inner_finger prefix="${prefix}" fingerprefix="${fingerprefix}" stroke="${stroke}"/>
<xacro:inner_finger_pad prefix="${prefix}" fingerprefix="${fingerprefix}"/>
<xacro:if value="${padding}">
<xacro:inner_finger_pad prefix="${prefix}" fingerprefix="${fingerprefix}"/>
</xacro:if>
<xacro:inner_knuckle prefix="${prefix}" fingerprefix="${fingerprefix}" stroke="${stroke}"/>
</xacro:macro>

Expand Down
Loading