reachy.parts.hand

Hand part modules.

Define different hand parts:

Module Contents

Classes

Hand

Hand abstraction part.

EmptyHand

Wrist with no hand Part.

LeftEmptyHand

Left Empty Hand Part.

RightEmptyHand

Right Empty Hand Part.

ForceGripper

Force Gripper Part.

LeftForceGripper

Left Force Gripper Part.

RightForceGripper

Right Force Gripper Part.

OrbitaWrist

Orbita Wrist hand.

class reachy.parts.hand.Hand(root, io)

Bases: reachy.parts.part.ReachyPart

Hand abstraction part.

Parameters
  • side (str) – which side the hand is attached to (‘left’ or ‘right’)

  • io (str) – port name where the modules can be found

fans
class reachy.parts.hand.EmptyHand(root, io)

Bases: Hand

Wrist with no hand Part.

Parameters
  • io (str) – port name where the modules can be found

  • side (str) – which side the part is attached to (‘left’ or ‘right’)

Composed of three dynamixel motors.

fans
class reachy.parts.hand.LeftEmptyHand(root, io)

Bases: EmptyHand

Left Empty Hand Part.

dxl_motors
class reachy.parts.hand.RightEmptyHand(root, io)

Bases: EmptyHand

Right Empty Hand Part.

dxl_motors
class reachy.parts.hand.ForceGripper(root, io)

Bases: Hand

Force Gripper Part.

Parameters
  • io (str) – port name where the modules can be found

  • side (str) – which side the part is attached to (‘left’ or ‘right’)

Composed of three dynamixel motors and a force sensor for gripping pressure.

fans
__repr__(self)

Force gripper representation.

open(self, end_pos=- 30, duration=1)

Open the gripper.

Parameters
  • end_pos (float) – open end position (in degrees)

  • duration (float) – open move duration (in seconds)

close(self, end_pos=30, duration=1, target_grip_force=100)

Close the gripper.

Parameters
  • end_pos (float) – close end position (in degrees)

  • duration (float) – close move duration (in seconds)

  • target_grip_force (float) – force threshold to stop closing the gripper

Returns

whether we did grasp something

Return type

bool

property grip_force(self)

Get current grip force.

class reachy.parts.hand.LeftForceGripper(root, io)

Bases: ForceGripper

Left Force Gripper Part.

dxl_motors
class reachy.parts.hand.RightForceGripper(root, io)

Bases: ForceGripper

Right Force Gripper Part.

dxl_motors
class reachy.parts.hand.OrbitaWrist(root, io)

Bases: Hand

Orbita Wrist hand.

Parameters
  • io (str) – port name where the modules can be found

  • side (str) – which side the part is attached to (‘left’ or ‘right’)

A 3dof Orbita Wrist at the end of the arm.

dxl_motors
orbita_config
__repr__(self)

Orbita wrist representation.

homing(self)

Launch Wrist homing procedure.