dm_robotics.panda.parameters module

Contains dataclasses holding parameter configurations.

class dm_robotics.panda.parameters.CollisionBehavior(lower_torque_thresholds: list[float] = <factory>, upper_torque_thresholds: list[float] = <factory>, lower_force_thresholds: list[float] = <factory>, upper_force_thresholds: list[float] = <factory>)[source]

Bases: object

Parameters to define the collision behavior of the real robot.

__init__(lower_torque_thresholds: list[float] = <factory>, upper_torque_thresholds: list[float] = <factory>, lower_force_thresholds: list[float] = <factory>, upper_force_thresholds: list[float] = <factory>) None
lower_force_thresholds: list[float]
lower_torque_thresholds: list[float]
upper_force_thresholds: list[float]
upper_torque_thresholds: list[float]
class dm_robotics.panda.parameters.GripperParams(model: RobotHand, effector: Effector, sensors: Sequence[Sensor] | None = None)[source]

Bases: object

Parameters describing a custom gripper.

__init__(model: RobotHand, effector: Effector, sensors: Sequence[Sensor] | None = None) None
effector: Effector
model: RobotHand
sensors: Sequence[Sensor] | None = None
class dm_robotics.panda.parameters.RobotParams(name: str = 'panda', pose: ~typing.Sequence[float] | None = None, joint_positions: ~typing.Sequence[float] = (0, -0.785, 0, -2.356, 0, 1.571, 0.785), attach_site: ~dm_control.mjcf.base.Element | None = None, control_frame: ~dm_control.mjcf.base.Element | None = None, actuation: ~dm_robotics.panda.arm_constants.Actuation = Actuation.CARTESIAN_VELOCITY, has_hand: bool = True, gripper: ~dm_robotics.panda.parameters.GripperParams | None = None, robot_ip: str | None = None, joint_stiffness: ~typing.Sequence[float] = (600, 600, 600, 600, 250, 150, 50), joint_damping: ~typing.Sequence[float] = (50, 50, 50, 20, 20, 20, 10), collision_behavior: ~dm_robotics.panda.parameters.CollisionBehavior = <factory>, enforce_realtime: bool = False)[source]

Bases: object

Parameters used for building the Panda robot model.

Parameters:
  • name – Name of the robot, used as prefix in MoMa and namespace in MJCF.

  • pose – 6 DOF pose (position, euler angles) of the Panda’s base.

  • joint_values – Initial joint values of the arm.

  • attachment_frame – The frame the robot will be attached to. If None the Arena’s default attachment frame is used.

  • control_frame – MoMa Effector`s and `Sensor`s will use this frame as a reference where applicable or use world frame if `None.

  • actuation – Actuation mode.

  • cartesian – Use Effector with cartesian commands.

  • has_hand – Set to true to use the Panda Hand.

  • robot_ip – Robot IP or hostname. If None hardware in the loop is not used.

  • joint_stiffness – Joint stiffness of the robot used in actuation.

  • joint_damping – Joint damping of the robot used in actuation.

  • collision_behavior – configures the collision behavior of the real robot.

  • enforce_realtime – enforce realtime priority of real robot control threat

__init__(name: str = 'panda', pose: ~typing.Sequence[float] | None = None, joint_positions: ~typing.Sequence[float] = (0, -0.785, 0, -2.356, 0, 1.571, 0.785), attach_site: ~dm_control.mjcf.base.Element | None = None, control_frame: ~dm_control.mjcf.base.Element | None = None, actuation: ~dm_robotics.panda.arm_constants.Actuation = Actuation.CARTESIAN_VELOCITY, has_hand: bool = True, gripper: ~dm_robotics.panda.parameters.GripperParams | None = None, robot_ip: str | None = None, joint_stiffness: ~typing.Sequence[float] = (600, 600, 600, 600, 250, 150, 50), joint_damping: ~typing.Sequence[float] = (50, 50, 50, 20, 20, 20, 10), collision_behavior: ~dm_robotics.panda.parameters.CollisionBehavior = <factory>, enforce_realtime: bool = False) None
actuation: Actuation = 0
attach_site: Element | None = None
collision_behavior: CollisionBehavior
control_frame: Element | None = None
enforce_realtime: bool = False
gripper: GripperParams | None = None
has_hand: bool = True
joint_damping: Sequence[float] = (50, 50, 50, 20, 20, 20, 10)
joint_positions: Sequence[float] = (0, -0.785, 0, -2.356, 0, 1.571, 0.785)
joint_stiffness: Sequence[float] = (600, 600, 600, 600, 250, 150, 50)
name: str = 'panda'
pose: Sequence[float] | None = None
robot_ip: str | None = None