dm_robotics.panda.arm module¶
MoMa robot arm model of the Panda along with specialized effectors and sensors.
- class dm_robotics.panda.arm.ArmEffector(robot_params: RobotParams, arm: RobotArm)[source]¶
Bases:
ArmEffector
Robot arm effector for the Panda MoMa model.
Takes
dm_robotics.panda.parameters.RobotParams
and changes the joint stiffness and damping of the robot arm. Otherwise behaves likedm_robotics.moma.effectors.arm_effector.ArmEffector
.- __init__(robot_params: RobotParams, arm: RobotArm)[source]¶
Constructor.
- Parameters:
robot_params – Dataclass containing robot parameters.
arm – The MoMa arm to control.
- class dm_robotics.panda.arm.Cartesian6dVelocityEffector(robot_params: RobotParams, arm: RobotArm, gripper: RobotHand, joint_velocity_effector: Effector, tcp_sensor: RobotTCPSensor, control_timestep: float = 0.1)[source]¶
Bases:
Cartesian6dVelocityEffector
Panda Version of the MoMa Cartesian6dVelocityEffector.
- __init__(robot_params: RobotParams, arm: RobotArm, gripper: RobotHand, joint_velocity_effector: Effector, tcp_sensor: RobotTCPSensor, control_timestep: float = 0.1)[source]¶
Initializes a QP-based 6D Cartesian velocity effector.
- Parameters:
robot_name – name of the robot the Cartesian effector controls.
joint_velocity_effector – Effector on the joint velocities being controlled to achieve the target Cartesian velocity. This class takes ownership of this effector, i.e. it will call initialize_episode automatically.
model_params – parameters that describe the object being controlled.
control_params – parameters that describe how the element should be controlled.
collision_params – parameters that describe the active collision avoidance behaviour, if any.
log_nullspace_failure_warnings – if true, a warning will be logged if the internal LSQP solver is unable to solve the nullspace optimization problem (second hierarchy). Ignored if nullspace control is disabled.
use_adaptive_qp_step_size – if true, the internal LSQP solver will use an adaptive step size when solving the resultant QP problem. Note that setting this to true can greatly speed up the computation time, but the solution will no longer be numerically deterministic.
compile_mjcf – if true, it will compile an MjModel from the MJCF during the after_compile stage. If false, it will re-use the MjModel in the mjcf.Physics object passed during the after_compile stage. Should only be set to false if the MjModel within the mjcf.Physics is guaranteed to be finalized and constant before and after after_compile is called.
- set_control(physics: Physics, command: ndarray) None [source]¶
Sets a 6 DoF Cartesian velocity command at the current timestep.
- Parameters:
physics – mjcf.Physics object with the updated environment state at the current timestep.
command – array of size 6 describing the desired 6 DoF Cartesian target [(lin_vel), (ang_vel)].
- class dm_robotics.panda.arm.ControlObservations(value)[source]¶
Bases:
Enum
Observations exposed by this sensor in control frame.
- POS = '{}_pos_control'¶
- POSE = '{}_pose_control'¶
- QUAT = '{}_quat_control'¶
- RMAT = '{}_rmat_control'¶
- VEL = '{}_vel_control'¶
- class dm_robotics.panda.arm.ExternalWrenchObserver(robot_params: RobotParams, arm: Panda, arm_sensor: RobotArmSensor)[source]¶
Bases:
Sensor
Estimates external wrench based on torque sensor signal.
- __init__(robot_params: RobotParams, arm: Panda, arm_sensor: RobotArmSensor) None [source]¶
- after_compile(mjcf_model: RootElement, physics: Physics) None [source]¶
Method called after the MJCF model has been compiled and finalized.
- Parameters:
mjcf_model – The root element of the scene MJCF model.
physics – Compiled physics.
- 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.
- class dm_robotics.panda.arm.Panda(*args, **kwargs)[source]¶
Bases:
RobotArm
A class representing a Panda robot arm.
- Parameters:
name – The name of this robot. Used as a prefix in the MJCF name attributes.
actuation – Instance of
dm_robotics.panda.arm_constants.Actuation
specifying which actuation mode to use.use_rotated_gripper – If True, mounts the gripper in a rotated position to match the real placement of the gripper on the physical Panda.
- property actuators: List[_ElementImpl]¶
List of actuator elements belonging to the arm.
- after_substep(physics: Physics, random_state: RandomState) None [source]¶
A callback which is executed after a simulation step.
- property attachment_site¶
Override wrist site for attachment, but NOT the one for observations.
- property base_site: _ElementImpl¶
Get the MuJoCo site of the base.
- Returns:
MuJoCo site
- initialize_episode(physics: Physics, random_state: RandomState)[source]¶
Function called at the beginning of every episode.
- property joint_torque_sensors: List[_ElementImpl]¶
Get MuJoCo sensor of the joint torques.
- property joints: List[_ElementImpl]¶
List of joint elements belonging to the arm.
- property mjcf_model: RootElement¶
Returns the mjcf.RootElement object corresponding to this robot arm.
- property name: str¶
Name of the robot arm.
- set_joint_angles(physics: Physics, joint_angles: ndarray) None [source]¶
Sets the joints of the robot to a given configuration.
This function allows to change the joint configuration of the Panda arm and sets the controller to prevent the impedance controller from moving back to the previous configuration.
- Parameters:
physics – A mujoco.Physics instance.
joint_angles – The desired joints configuration for the robot arm.
- property wrist_site: _ElementImpl¶
Get the MuJoCo site of the wrist.
- Returns:
MuJoCo site
- class dm_robotics.panda.arm.RobotArmSensor(robot_params: RobotParams, arm: RobotArm)[source]¶
Bases:
RobotArmSensor
Behaves like
dm_robotics.moma.sensors.robot_arm_sensor.RobotArmSensor
.Except that the joint torque signal does not include passive forces. This is done so as to model the external torque signal provided by the Panda robot.
- __init__(robot_params: RobotParams, arm: RobotArm)[source]¶
- class dm_robotics.panda.arm.RobotTCPSensor(gripper: RobotHand | RobotHand, robot_params: RobotParams)[source]¶
Bases:
SiteSensor
Version of dm_robotics.moma.sensors.site_sensor.SiteSensor that takes tool center point pose measurements of a gripper and accepts parameters.RobotParams to optionally change the reference frame. Otherwise behaves like a SiteSensor.
- __init__(gripper: RobotHand | RobotHand, robot_params: RobotParams)[source]¶
Constructor.
- Parameters:
gripper – This gripper’s TCP site is used for the measurements. robot_params: Set the control_frame field to a site to use as reference frame. Falls back to world frame if None.
- dm_robotics.panda.arm.build_robot(robot_params: RobotParams, control_timestep: float = 0.1) Robot [source]¶
Builds a MoMa robot model of the Panda.