dm_robotics.panda.gripper module

Panda Hand gripper.

class dm_robotics.panda.gripper.DummyHand(*args, **kwargs)[source]

Bases: RobotHand

A fully MoMa compatible but empty RobotHand model.

property actuators: Sequence[_ElementImpl]

List of actuator elements belonging to the hand.

property joints: Sequence[_ElementImpl]

List of joint elements belonging to the hand.

property mjcf_model: _ElementImpl

Returns the mjcf.RootElement object corresponding to the robot hand.

property name: str

Name of the robot hand.

property tool_center_point: _ElementImpl

Tool center point site of the hand.

class dm_robotics.panda.gripper.PandaHand(*args, **kwargs)[source]

Bases: RobotHand

MoMa robot hand model of the Franka Hand.

property actuators: Sequence[_ElementImpl]

List of actuator elements belonging to the hand.

initialize_episode(physics: Physics, random_state: RandomState)[source]

Function called at the beginning of every episode.

property joints: Sequence[_ElementImpl]

List of joint elements belonging to the hand.

property mjcf_model: _ElementImpl

Returns the mjcf.RootElement object corresponding to the robot hand.

property name: str

Name of the robot hand.

set_joint_positions(physics: Physics, joint_positions: ndarray) None[source]

Sets the joints of the gripper to a given configuration.

Changes the joint state as well as the current control signal to the desired joint state.

Parameters:
  • physics – A mujoco.Physics instance.

  • joint_positions – The desired joint state for the robot gripper.

set_width(physics: Physics, width: float)[source]

Set desired aperture of the gripper.

property tool_center_point: _ElementImpl

Tool center point site of the hand.

class dm_robotics.panda.gripper.PandaHandEffector(robot_params: RobotParams, gripper: RobotHand, panda_hand_sensor: PandaHandSensor)[source]

Bases: DefaultGripperEffector

Panda gripper effector.

Action space is binary. The gripper’s finger will move until blocked and then continuously apply a force either outwards or inwards, corresponding to actions 1 and 0 respectively. Actions between 0 and 1 get rounded.

__init__(robot_params: RobotParams, gripper: RobotHand, panda_hand_sensor: PandaHandSensor)[source]
action_spec(physics: Physics) BoundedArray[source]
set_control(physics: Physics, command: ndarray) None[source]
class dm_robotics.panda.gripper.PandaHandSensor(gripper: PandaHand, name: str)[source]

Bases: Sensor

Sensor for the Panda gripper.

Provides two observations, namely, the current aperture or width between the fingers as well as gripper’s state.

__init__(gripper: PandaHand, name: str) None[source]
get_obs_key(obs: Enum) str[source]

Returns the key to an observable provided by this sensor.

initialize_episode(physics: Physics, random_state: RandomState) None[source]

Called on a new episode, after the environment has been reset.

This is called before the agent has got a timestep in the episode that is about to start. Sensors can reset any state they may have.

Parameters:
  • physics – The MuJoCo physics the environment uses.

  • random_state – A PRNG seed.

property name: str
property observables: Dict[str, Observable]

Get the observables for this Sensor.

This will be called after initialize_for_task.

It’s expected that the keys in this dict are values from self.get_obs_key(SOME_ENUM_VALUE), the values are Observables. See the class docstring for more information about Observable.

subclassing dm_control.composer.observation.observable.Generic is a simple way to create an Observable. Observables have many properties that are used by composer to alter how the values it produces are processed.

See the code dm_control.composer.observation for more information.