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 1 commit
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: 5 additions & 3 deletions src/pycram/robot_descriptions/boxy_description.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
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

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

Expand Down Expand Up @@ -29,7 +29,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.548
J-Schaefer marked this conversation as resolved.
Show resolved Hide resolved
right_arm.end_effector = right_gripper

################################## Left Arm ##################################
Expand All @@ -53,7 +54,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.548
J-Schaefer marked this conversation as resolved.
Show resolved Hide resolved
left_arm.end_effector = left_gripper

################################## Torso ##################################
Expand Down
3 changes: 2 additions & 1 deletion src/pycram/robot_descriptions/donbot_description.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,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.2
J-Schaefer marked this conversation as resolved.
Show resolved Hide resolved
right_arm.end_effector = right_gripper

################################## Torso ##################################
Expand Down
5 changes: 3 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,7 @@

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

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

Expand All @@ -29,7 +29,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.3
left_arm.end_effector = left_gripper

################################## Torso ##################################
Expand Down
3 changes: 2 additions & 1 deletion src/pycram/robot_descriptions/stretch_description.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,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.59
J-Schaefer marked this conversation as resolved.
Show resolved Hide resolved
arm_description.end_effector = gripper_description

################################## Neck ##################################
Expand Down
8 changes: 5 additions & 3 deletions src/pycram/robot_descriptions/tiago_description.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
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
Expand Down Expand Up @@ -38,7 +38,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.048
left_arm.end_effector = left_gripper

################################## Right Arm ##################################
Expand All @@ -64,7 +65,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.048
right_arm.end_effector = right_gripper

################################## Torso ##################################
Expand Down
4 changes: 2 additions & 2 deletions src/pycram/robot_descriptions/ur5_description.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
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

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

Expand Down Expand Up @@ -36,7 +36,7 @@
'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
arm.end_effector = gripper

# Add to RobotDescriptionManager
Expand Down