mani_skill.agents.controllers#

Submodules#

Classes#

PDBaseForwardVelController

PDJointVelController for forward-only ego-centric base movement.

PDBaseForwardVelControllerConfig

PDBaseVelController

PDJointVelController for ego-centric base movement.

PDBaseVelControllerConfig

PDEEPosController

The PD EE Position controller. NOTE that on the GPU it is assumed the controlled robot is not a merged articulation and is the same across every sub-scene

PDEEPosControllerConfig

PDEEPoseController

The PD EE Position controller. NOTE that on the GPU it is assumed the controlled robot is not a merged articulation and is the same across every sub-scene

PDEEPoseControllerConfig

PDJointPosController

Base class for controllers.

PDJointPosControllerConfig

PDJointPosMimicController

Base class for controllers.

PDJointPosMimicControllerConfig

PD Joint Position mimic controller configuration. This kind of controller is used to emuluate a mimic joint. For some simulation backends mimic joints are not

PDJointPosVelController

Base class for controllers.

PDJointPosVelControllerConfig

PDJointVelController

Base class for controllers.

PDJointVelControllerConfig

PassiveController

Passive controller that does not do anything

PassiveControllerConfig

Functions#

deepcopy_dict(configs)

Make a deepcopy of dict.

Package Contents#

class mani_skill.agents.controllers.PDBaseForwardVelController(config, articulation, control_freq, sim_freq=None, scene=None)[source]#

Bases: mani_skill.agents.controllers.pd_joint_vel.PDJointVelController

PDJointVelController for forward-only ego-centric base movement.

Parameters:
_initialize_action_space()[source]#
set_action(action)[source]#

Set the action to execute. The action can be low-level control signals or high-level abstract commands.

Parameters:

action (mani_skill.utils.structs.types.Array) –

class mani_skill.agents.controllers.PDBaseForwardVelControllerConfig[source]#

Bases: mani_skill.agents.controllers.pd_joint_vel.PDJointVelControllerConfig

controller_cls#
class mani_skill.agents.controllers.PDBaseVelController(config, articulation, control_freq, sim_freq=None, scene=None)[source]#

Bases: mani_skill.agents.controllers.pd_joint_vel.PDJointVelController

PDJointVelController for ego-centric base movement.

Parameters:
_initialize_action_space()[source]#
set_action(action)[source]#

Set the action to execute. The action can be low-level control signals or high-level abstract commands.

Parameters:

action (mani_skill.utils.structs.types.Array) –

class mani_skill.agents.controllers.PDBaseVelControllerConfig[source]#

Bases: mani_skill.agents.controllers.pd_joint_vel.PDJointVelControllerConfig

controller_cls#
class mani_skill.agents.controllers.PDEEPosController(config, articulation, control_freq, sim_freq=None, scene=None)[source]#

Bases: mani_skill.agents.controllers.pd_joint_pos.PDJointPosController

The PD EE Position controller. NOTE that on the GPU it is assumed the controlled robot is not a merged articulation and is the same across every sub-scene

Parameters:
__repr__()[source]#
_check_gpu_sim_works()[source]#
_initialize_action_space()[source]#
_initialize_joints()[source]#
compute_target_pose(prev_ee_pose_at_base, action)[source]#
get_state()[source]#

Get the controller state.

Return type:

dict

reset()[source]#

Resets the controller to an initial state. This is called upon environment creation and each environment reset

set_action(action)[source]#

Set the action to execute. The action can be low-level control signals or high-level abstract commands.

Parameters:

action (mani_skill.utils.structs.types.Array) –

set_state(state)[source]#
Parameters:

state (dict) –

_target_pose = None#
config: PDEEPosControllerConfig#
property ee_pos#
property ee_pose#
property ee_pose_at_base#
class mani_skill.agents.controllers.PDEEPosControllerConfig[source]#

Bases: mani_skill.agents.controllers.base_controller.ControllerConfig

controller_cls#
damping: float | Sequence[float]#
delta_solver_config: dict#

//github.com/haosulab/ManiSkill/issues/955#issuecomment-2742253342 for some analysis on performance.

Type:

Configuration for the delta IK solver. Default is dict(type=”levenberg_marquardt”, alpha=1.0). type can be one of “levenberg_marquardt” or “pseudo_inverse”. alpha is a scaling term applied to the delta joint positions generated by the solver. Generally levenberg_marquardt is faster and more accurate than pseudo_inverse and is the recommended option, see https

drive_mode: Sequence[mani_skill.utils.structs.types.DriveMode] | mani_skill.utils.structs.types.DriveMode = 'force'#

The name of the end-effector link to control. Note that it does not have to be a end-effector necessarily and could just be any link.

force_limit: float | Sequence[float] = 10000000000.0#
frame: Literal['body_translation', 'root_translation'] = 'root_translation'#

Choice of frame to use for translational and rotational control of the end-effector. To learn how these work explicitly with videos of each one’s behavior see https://maniskill.readthedocs.io/en/latest/user_guide/concepts/controllers.html#pd-ee-end-effector-pose

friction: float | Sequence[float] = 0.0#
interpolate: bool = False#
normalize_action: bool = True#

Whether to normalize each action dimension into a range of [-1, 1]. Normally for most machine learning workflows this is recommended to be kept true.

pos_lower: float | Sequence[float]#

Lower bound for position control. If a single float then X, Y, and Z rotations are bounded by this value. Otherwise can be three floats to specify each dimensions bounds

pos_upper: float | Sequence[float]#

Upper bound for position control. If a single float then X, Y, and Z rotations are bounded by this value. Otherwise can be three floats to specify each dimensions bounds

Optionally set different root link for root translation control (e.g. if root is different than base)

stiffness: float | Sequence[float]#
urdf_path: str = None#

Path to the URDF file defining the robot to control.

use_delta: bool = True#

Whether to use delta-action control. If true then actions indicate the delta/change in position via translation and orientation via rotation. If false, then actions indicate in the base frame (typically wherever the root link of the robot is) what pose the end effector should try and reach via inverse kinematics.

use_target: bool = False#

Whether to use the most recent target end-effector pose for control. If false, actions taken in a chosen frame will be taken relative to the instantaneous/current end-effector pose.

class mani_skill.agents.controllers.PDEEPoseController(config, articulation, control_freq, sim_freq=None, scene=None)[source]#

Bases: PDEEPosController

The PD EE Position controller. NOTE that on the GPU it is assumed the controlled robot is not a merged articulation and is the same across every sub-scene

Parameters:
_check_gpu_sim_works()[source]#
_clip_and_scale_action(action)[source]#
_initialize_action_space()[source]#
compute_target_pose(prev_ee_pose_at_base, action)[source]#
Parameters:

prev_ee_pose_at_base (mani_skill.utils.structs.Pose) –

config: PDEEPoseControllerConfig#
class mani_skill.agents.controllers.PDEEPoseControllerConfig[source]#

Bases: PDEEPosControllerConfig

controller_cls#
damping: float | Sequence[float] = None#
force_limit: float | Sequence[float] = 10000000000.0#
frame: Literal['body_translation:root_aligned_body_rotation', 'root_translation:root_aligned_body_rotation', 'body_translation:body_aligned_body_rotation', 'root_translation:body_aligned_body_rotation'] = 'root_translation:root_aligned_body_rotation'#

Choice of frame to use for translational and rotational control of the end-effector. To learn how these work explicitly with videos of each one’s behavior see https://maniskill.readthedocs.io/en/latest/user_guide/concepts/controllers.html#pd-ee-end-effector-pose

friction: float | Sequence[float] = 0.0#
rot_lower: float | Sequence[float]#

Lower bound for rotation control. If a single float then X, Y, and Z rotations are bounded by this value. Otherwise can be three floats to specify each dimensions bounds

rot_upper: float | Sequence[float]#

Upper bound for rotation control. If a single float then X, Y, and Z rotations are bounded by this value. Otherwise can be three floats to specify each dimensions bounds

stiffness: float | Sequence[float] = None#
class mani_skill.agents.controllers.PDJointPosController(config, articulation, control_freq, sim_freq=None, scene=None)[source]#

Bases: mani_skill.agents.controllers.base_controller.BaseController

Base class for controllers. The controller is an interface for the robot to interact with the environment.

Parameters:
_get_joint_limits()[source]#
_initialize_action_space()[source]#
before_simulation_step()[source]#

Called before each simulation step in one control step.

get_state()[source]#

Get the controller state.

Return type:

dict

reset()[source]#

Resets the controller to an initial state. This is called upon environment creation and each environment reset

set_action(action)[source]#

Set the action to execute. The action can be low-level control signals or high-level abstract commands.

Parameters:

action (mani_skill.utils.structs.types.Array) –

set_drive_property()[source]#

Set the joint drive property according to the config.

set_drive_targets(targets)[source]#
set_state(state)[source]#
Parameters:

state (dict) –

_start_qpos = None#
_target_qpos = None#
config: PDJointPosControllerConfig#
sets_target_qpos = True#

Whether the controller sets the target qpos of the articulation

sets_target_qvel = False#

Whether the controller sets the target qvel of the articulation

class mani_skill.agents.controllers.PDJointPosControllerConfig[source]#

Bases: mani_skill.agents.controllers.base_controller.ControllerConfig

controller_cls#
damping: float | Sequence[float]#
drive_mode: Sequence[mani_skill.utils.structs.types.DriveMode] | mani_skill.utils.structs.types.DriveMode = 'force'#
force_limit: float | Sequence[float] = 10000000000.0#
friction: float | Sequence[float] = 0.0#
interpolate: bool = False#
lower: None | float | Sequence[float]#
normalize_action: bool = True#
stiffness: float | Sequence[float]#
upper: None | float | Sequence[float]#
use_delta: bool = False#
use_target: bool = False#
class mani_skill.agents.controllers.PDJointPosMimicController(config, articulation, control_freq, sim_freq=None, scene=None)[source]#

Bases: PDJointPosController

Base class for controllers. The controller is an interface for the robot to interact with the environment.

Parameters:
__repr__()[source]#
_get_joint_limits()[source]#
_initialize_joints()[source]#
set_action(action)[source]#

Set the action to execute. The action can be low-level control signals or high-level abstract commands.

Parameters:

action (mani_skill.utils.structs.types.Array) –

config: PDJointPosMimicControllerConfig#
class mani_skill.agents.controllers.PDJointPosMimicControllerConfig[source]#

Bases: PDJointPosControllerConfig

PD Joint Position mimic controller configuration. This kind of controller is used to emuluate a mimic joint. For some simulation backends mimic joints are not well simulated and/or are hard to tune and so a mimic controller can be used for better stability as well as alignment with a real robot.

The joint_names field is expected to be a list of all the joints, whether they are the joints to be controlled or the joints that are controlled via mimicing.

mimic is a dictionary that maps the mimic joint name to a dictionary of the format dict(joint: str, multiplier: float, offset: float). joint is the controlling joint name and is required. All given joints in joint_names must be in the mimic dictionary as either a key or a value. The ones that are keys are referred to as the mimic joints and the ones that are values are referred to as the control joints. Mimic joints are the ones directly controlled by the agent/user and control joints are implicitly controlled by following the mimic joints via the following equation:

q_mimic = q_controlling * multiplier + offset

By default, the multiplier is 1.0 and the offset is 0.0.

controller_cls#
mimic: dict[str, dict[str, float]]#

float, offset: float)

Type:

the mimic targets. Maps the actual mimic joint name to a dictionary of the format dict(joint

Type:

str, multiplier

class mani_skill.agents.controllers.PDJointPosVelController(config, articulation, control_freq, sim_freq=None, scene=None)[source]#

Bases: mani_skill.agents.controllers.pd_joint_pos.PDJointPosController

Base class for controllers. The controller is an interface for the robot to interact with the environment.

Parameters:
_initialize_action_space()[source]#
reset()[source]#

Resets the controller to an initial state. This is called upon environment creation and each environment reset

set_action(action)[source]#

Set the action to execute. The action can be low-level control signals or high-level abstract commands.

Parameters:

action (numpy.ndarray) –

set_drive_velocity_targets(targets)[source]#
_target_qvel = None#
config: PDJointPosVelControllerConfig#
sets_target_qpos = True#

Whether the controller sets the target qpos of the articulation

sets_target_qvel = True#

Whether the controller sets the target qvel of the articulation

class mani_skill.agents.controllers.PDJointPosVelControllerConfig[source]#

Bases: mani_skill.agents.controllers.pd_joint_pos.PDJointPosControllerConfig

controller_cls#
vel_lower: float | Sequence[float] = -1.0#
vel_upper: float | Sequence[float] = 1.0#
class mani_skill.agents.controllers.PDJointVelController(config, articulation, control_freq, sim_freq=None, scene=None)[source]#

Bases: mani_skill.agents.controllers.base_controller.BaseController

Base class for controllers. The controller is an interface for the robot to interact with the environment.

Parameters:
_initialize_action_space()[source]#
set_action(action)[source]#

Set the action to execute. The action can be low-level control signals or high-level abstract commands.

Parameters:

action (numpy.ndarray) –

set_drive_property()[source]#

Set the joint drive property according to the config.

config: PDJointVelControllerConfig#
sets_target_qpos = False#

Whether the controller sets the target qpos of the articulation

sets_target_qvel = True#

Whether the controller sets the target qvel of the articulation

class mani_skill.agents.controllers.PDJointVelControllerConfig[source]#

Bases: mani_skill.agents.controllers.base_controller.ControllerConfig

controller_cls#
damping: float | Sequence[float]#
drive_mode: Sequence[mani_skill.utils.structs.types.DriveMode] | mani_skill.utils.structs.types.DriveMode = 'force'#
force_limit: float | Sequence[float] = 10000000000.0#
friction: float | Sequence[float] = 0.0#
lower: float | Sequence[float]#
normalize_action: bool = True#
upper: float | Sequence[float]#
class mani_skill.agents.controllers.PassiveController(config, articulation, control_freq, sim_freq=None, scene=None)[source]#

Bases: mani_skill.agents.controllers.base_controller.BaseController

Passive controller that does not do anything

Parameters:
_initialize_action_space()[source]#
before_simulation_step()[source]#

Called before each simulation step in one control step.

set_action(action)[source]#

Set the action to execute. The action can be low-level control signals or high-level abstract commands.

Parameters:

action (numpy.ndarray) –

set_drive_property()[source]#

Set the joint drive property according to the config.

config: PassiveControllerConfig#
sets_target_qpos = False#

Whether the controller sets the target qpos of the articulation

sets_target_qvel = False#

Whether the controller sets the target qvel of the articulation

class mani_skill.agents.controllers.PassiveControllerConfig[source]#

Bases: mani_skill.agents.controllers.base_controller.ControllerConfig

controller_cls#
damping: float | Sequence[float]#
force_limit: float | Sequence[float] = 10000000000.0#
friction: float | Sequence[float] = 0.0#
mani_skill.agents.controllers.deepcopy_dict(configs)[source]#

Make a deepcopy of dict. The built-in behavior will not copy references to the same value.

Parameters:

configs (dict) –