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

Add gripper types to various robot descriptions #259

Merged
merged 5 commits into from
Jan 22, 2025
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
5 changes: 3 additions & 2 deletions src/pycram/knowledge/knowledge_sources/facts_knowledge.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
from ...robot_description import RobotDescription
from ...world_reasoning import visible
from ...costmaps import OccupancyCostmap, GaussianCostmap
from ...units import meter

if TYPE_CHECKING:
from ...designators.object_designator import ObjectDesignatorDescription
Expand Down Expand Up @@ -91,9 +92,9 @@ def graspable(self, object_designator: ObjectDesignatorDescription) -> Reasoning
RobotDescription.current_robot_description.get_manipulator_chains()]

for dist in gripper_opening_dists:
if dist > obj_y:
if dist > obj_y * meter:
return ReasoningResult(True, {"grasp": Grasp.FRONT})
elif dist > obj_x:
elif dist > obj_x * meter:
return ReasoningResult(True, {"grasp": Grasp.LEFT})

return ReasoningResult(False)
Expand Down
9 changes: 6 additions & 3 deletions src/pycram/robot_descriptions/boxy_description.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
from ..ros.ros_tools import get_ros_package_path
from ..robot_description import RobotDescription, CameraDescription, KinematicChainDescription, \
EndEffectorDescription, RobotDescriptionManager
from ..datastructures.enums import Arms, Grasp, GripperState, TorsoState
from ..datastructures.enums import Arms, Grasp, GripperState, TorsoState, GripperType
from ..units import meter

filename = get_ros_package_path('pycram') + '/resources/robots/' + "boxy" + '.urdf'

Expand Down Expand Up @@ -29,7 +30,8 @@

right_gripper.add_static_joint_states(GripperState.OPEN, {"right_gripper_joint": 0.548})
right_gripper.add_static_joint_states(GripperState.CLOSE, {"right_gripper_joint": 0.0})

right_gripper.end_effector_type = GripperType.PARALLEL # current gripper in sim, change later
right_gripper.opening_distance = 0.11 * meter # 2x 55mm for WSG050
right_arm.end_effector = right_gripper

################################## Left Arm ##################################
Expand All @@ -53,7 +55,8 @@

left_gripper.add_static_joint_states(GripperState.OPEN, {"left_gripper_joint": 0.548})
left_gripper.add_static_joint_states(GripperState.CLOSE, {"left_gripper_joint": 0.0})

left_gripper.end_effector_type = GripperType.PARALLEL # current gripper in sim, change later
left_gripper.opening_distance = 0.11 * meter # 2x 55mm for WSG050
left_arm.end_effector = left_gripper

################################## Torso ##################################
Expand Down
6 changes: 4 additions & 2 deletions src/pycram/robot_descriptions/donbot_description.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
from ..ros.ros_tools import get_ros_package_path
from ..robot_description import RobotDescription, KinematicChainDescription, EndEffectorDescription, \
RobotDescriptionManager, CameraDescription
from ..datastructures.enums import Arms, Grasp, GripperState, TorsoState
from ..datastructures.enums import Arms, Grasp, GripperState, TorsoState, GripperType
from ..units import meter

filename = get_ros_package_path('pycram') + '/resources/robots/' + "iai_donbot" + '.urdf'

Expand All @@ -27,7 +28,8 @@

right_gripper.add_static_joint_states(GripperState.OPEN, {'gripper_joint': 0.0})
right_gripper.add_static_joint_states(GripperState.CLOSE, {'gripper_joint': 0.2})

right_gripper.end_effector_type = GripperType.PARALLEL
right_gripper.opening_distance = 0.11 * meter # 2x 55mm for WSG050
right_arm.end_effector = right_gripper

################################## Torso ##################################
Expand Down
6 changes: 4 additions & 2 deletions src/pycram/robot_descriptions/hsrb_description.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@

from ..robot_description import RobotDescription, KinematicChainDescription, EndEffectorDescription, \
RobotDescriptionManager, CameraDescription
from ..datastructures.enums import GripperState, Grasp, Arms, TorsoState
from ..datastructures.enums import GripperState, Grasp, Arms, TorsoState, GripperType
from ..units import meter

filename = get_ros_package_path('pycram') + '/resources/robots/' + "hsrb" + '.urdf'

Expand All @@ -29,7 +30,8 @@
left_gripper.add_static_joint_states(GripperState.CLOSE, {'hand_l_proximal_joint': 0.0,
'hand_r_proximal_joint': 0.0,
'hand_motor_joint': 0.0})

left_gripper.end_effector_type = GripperType.PARALLEL
left_gripper.opening_distance = 0.13 * meter
left_arm.end_effector = left_gripper

################################## Torso ##################################
Expand Down
5 changes: 3 additions & 2 deletions src/pycram/robot_descriptions/pr2_description.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
RobotDescriptionManager, CameraDescription
from ..datastructures.enums import Arms, Grasp, GripperState, GripperType, TorsoState
from ..ros.ros_tools import get_ros_package_path
from ..units import meter

from ..helper import get_robot_mjcf_path

Expand Down Expand Up @@ -39,7 +40,7 @@
left_gripper.add_static_joint_states(GripperState.CLOSE, {'l_gripper_l_finger_joint': 0.0,
'l_gripper_r_finger_joint': 0.0})
left_gripper.end_effector_type = GripperType.PARALLEL
left_gripper.opening_distance = 0.548
left_gripper.opening_distance = 0.086 * meter
left_arm.end_effector = left_gripper

################################## Right Arm ##################################
Expand All @@ -62,7 +63,7 @@
right_gripper.add_static_joint_states(GripperState.CLOSE, {'r_gripper_l_finger_joint': 0.0,
'r_gripper_r_finger_joint': 0.0})
right_gripper.end_effector_type = GripperType.PARALLEL
right_gripper.opening_distance = 0.548
right_gripper.opening_distance = 0.086 * meter
right_arm.end_effector = right_gripper

################################## Camera ##################################
Expand Down
6 changes: 4 additions & 2 deletions src/pycram/robot_descriptions/stretch_description.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@

from ..robot_description import RobotDescription, KinematicChainDescription, EndEffectorDescription, \
CameraDescription, RobotDescriptionManager
from ..datastructures.enums import GripperState, Arms, Grasp, TorsoState
from ..datastructures.enums import GripperState, Arms, Grasp, TorsoState, GripperType
from ..units import meter

filename = get_ros_package_path('pycram') + '/resources/robots/' + "stretch_description" + '.urdf'

Expand Down Expand Up @@ -31,7 +32,8 @@
'joint_gripper_finger_right': 0.59})
gripper_description.add_static_joint_states(GripperState.CLOSE, {'joint_gripper_finger_left': 0.0,
'joint_gripper_finger_right': 0.0})

gripper_description.end_effector_type = GripperType.PARALLEL
gripper_description.opening_distance = 0.14 * meter # assumption
arm_description.end_effector = gripper_description

################################## Neck ##################################
Expand Down
9 changes: 6 additions & 3 deletions src/pycram/robot_descriptions/tiago_description.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,11 @@
from ..ros.ros_tools import get_ros_package_path

from ..datastructures.dataclasses import VirtualMobileBaseJoints
from ..datastructures.enums import GripperState, Arms, Grasp, TorsoState
from ..datastructures.enums import GripperState, Arms, Grasp, TorsoState, GripperType
from ..robot_description import RobotDescription, KinematicChainDescription, EndEffectorDescription, \
RobotDescriptionManager, CameraDescription
from ..helper import get_robot_mjcf_path
from ..units import meter

filename = get_ros_package_path('pycram') + '/resources/robots/' + "tiago_dual" + '.urdf'

Expand Down Expand Up @@ -38,7 +39,8 @@

left_gripper.add_static_joint_states(GripperState.CLOSE, {'gripper_left_left_finger_joint': 0.0,
'gripper_left_right_finger_joint': 0.0})

left_gripper.end_effector_type = GripperType.PARALLEL
left_gripper.opening_distance = 0.09 * meter # measured
left_arm.end_effector = left_gripper

################################## Right Arm ##################################
Expand All @@ -64,7 +66,8 @@

right_gripper.add_static_joint_states(GripperState.CLOSE, {'gripper_right_left_finger_joint': 0.0,
'gripper_right_right_finger_joint': 0.0})

right_gripper.end_effector_type = GripperType.PARALLEL
right_gripper.opening_distance = 0.09 * meter # measured
right_arm.end_effector = right_gripper

################################## Torso ##################################
Expand Down
6 changes: 4 additions & 2 deletions src/pycram/robot_descriptions/ur5_description.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
from ..ros.ros_tools import get_ros_package_path
from ..robot_description import RobotDescription, KinematicChainDescription, EndEffectorDescription, \
RobotDescriptionManager
from ..datastructures.enums import Arms, Grasp, GripperState
from ..datastructures.enums import Arms, Grasp, GripperState, GripperType
from ..units import meter

filename = get_ros_package_path('pycram') + '/resources/robots/' + "ur5_robotiq" + '.urdf'

Expand Down Expand Up @@ -36,7 +37,8 @@
'robotiq_85_right_inner_knuckle_joint': 1.0,
'robotiq_85_left_finger_tip_joint': 1.0,
'robotiq_85_right_finger_tip_joint': 1.0})

gripper.end_effector_type = GripperType.PARALLEL
gripper.opening_distance = 0.085 * meter
arm.end_effector = gripper

# Add to RobotDescriptionManager
Expand Down
6 changes: 4 additions & 2 deletions src/pycram/robot_descriptions/ur5e_controlled_description.py
Original file line number Diff line number Diff line change
@@ -1,11 +1,12 @@
import os

from ..datastructures.enums import Arms, GripperState
from ..datastructures.enums import Arms, GripperState, GripperType
from ..helper import get_robot_mjcf_path, find_multiverse_resources_path, get_robot_urdf_path_from_multiverse
from ..robot_description import RobotDescription, KinematicChainDescription, EndEffectorDescription, \
RobotDescriptionManager
from ..object_descriptors.urdf import ObjectDescription as URDFObject
from ..ros.logging import logwarn
from ..units import meter

multiverse_resources = find_multiverse_resources_path()
ROBOT_NAME = "ur5e"
Expand Down Expand Up @@ -59,7 +60,8 @@
'left_coupler_joint': 0.00366,
'left_spring_link_joint': 0.796,
'left_follower_joint': -0.793})

gripper.end_effector_type = GripperType.PARALLEL
gripper.opening_distance = 0.085 * meter
arm.end_effector = gripper

# Add to RobotDescriptionManager
Expand Down