mani_skill.agents.controllers.pd_ee_pose#

Classes#

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

Module Contents#

class mani_skill.agents.controllers.pd_ee_pose.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[source]#
config: PDEEPosControllerConfig[source]#
property ee_pos[source]#
property ee_pose[source]#
property ee_pose_at_base[source]#
class mani_skill.agents.controllers.pd_ee_pose.PDEEPosControllerConfig[source]#

Bases: mani_skill.agents.controllers.base_controller.ControllerConfig

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

//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'[source]#

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[source]#
frame: Literal['body_translation', 'root_translation'] = 'root_translation'[source]#

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[source]#
interpolate: bool = False[source]#
normalize_action: bool = True[source]#

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][source]#

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][source]#

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][source]#
urdf_path: str = None[source]#

Path to the URDF file defining the robot to control.

use_delta: bool = True[source]#

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[source]#

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.pd_ee_pose.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[source]#
class mani_skill.agents.controllers.pd_ee_pose.PDEEPoseControllerConfig[source]#

Bases: PDEEPosControllerConfig

controller_cls[source]#
damping: float | Sequence[float] = None[source]#
force_limit: float | Sequence[float] = 10000000000.0[source]#
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'[source]#

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[source]#
rot_lower: float | Sequence[float][source]#

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][source]#

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[source]#