Impedance Controller#

class gymnasium_planar_robotics.utils.impedance_control.MoverImpedanceController(model: MjModel, mover_joint_name: str, joint_mask: ndarray | None = None, translational_stiffness: ndarray | float = 1.0, rotational_stiffness: ndarray | float = 0.1)[source]

A mover impedance controller which solves a position and orientation task for one mover.

Parameters:
  • model – mjModel of the MuJoCo environment

  • mover_joint_name – the name of the joint of the mover in the MuJoCo model

  • joint_mask – None or a numpy array of shape (6,) which contains only 0 and 1, defaults to None. This array can be used to control only certain DoFs of a mover with this controller (1 for controlling a DoF). If set to None, all DoFs are controlled.

  • translational_stiffness – a numpy array of shape (3,) or a single float value, defaults to 1.0. Use the numpy array to specify different stiffness values for x,y and z. If only a single float value is specified, the same stiffness value is used for all translational axes.

  • rotational_stiffness – a numpy array of shape (3,) or a single float value, defaults to 0.1. Use the numpy array to specify different stiffness values for a (rotation about x-axis of the mover frame), b (rotation about y-axis of the mover frame) and c (rotation about z-axis of the mover frame). If only a single float value is specified, the same stiffness value is used for all rotational axes.

ctrl_callback(ctrl: ndarray)[source]

A callback that can be used to modify the desired forces and torques computed by the update() method, e.g. to ensure minimum and maximum forces and torques.

Parameters:

ctrl – the desired controls (forces, torques) computed by the ‘update()’ method, i.e. a numpy array of shape (6,) with the following order of DoFs: x,y,z,a,b,c.

Returns:

the modified controls, i.e. a numpy array of shape (6,) with the following order of DoFs: x,y,z,a,b,c.

generate_actuator_xml_string(idx_mover: int)[source]

Generate an actuator xml string which can be added to the MuJoCo model xml string. Note that only actuators for DoFs that are controlled by this controller are added. This method must be called manually by the user after the controller has been initialized.

Parameters:

idx_mover – the index of the mover (can be found in the body name of the mover, e.g. for a mover with index 0: ‘mover_0’)

Returns:

the actuator xml string

init_stiffness_mat(stiffness: ndarray | float) ndarray[source]

Initialize a stiffness matrix.

Parameters:

stiffness – the stiffness values - either a numpy array of shape (3,) or a single float value

Returns:

a numpy array of shape (3,3) which is a diagonal matrix with the stiffness values on its diagonal

set_joint_mask(new_joint_mask: ndarray)[source]

Set a new joint mask to control only specified DoFs of a mover with this controller.

Parameters:

new_joint_mask – the new joint mask - a numpy array of shape (6,) which contains only 0 and 1 (1 for controlling a DoF).

update(model: MjModel, data: MjData, pos_d: ndarray, quat_d: ndarray) None[source]

Compute new controls based on the position and orientation error.

Parameters:
  • model – mjModel of the MuJoCo environment

  • data – mjData of the MuJoCo environment

  • pos_d – the desired position (x_p,y_p,z_p) specified as a numpy array of shape (3,)

  • quat_d – the desired orientation, specified as a quaternion (w_o,x_o,y_o,z_o), i.e. numpy array of shape (4,)