mani_skill.agents.controllers.pd_ee_pose#
Classes#
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 |
|
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 |
|
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.PDJointPosControllerThe 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:
config (ControllerConfig) –
articulation (mani_skill.utils.structs.Articulation) –
control_freq (int) –
sim_freq (Optional[int]) –
scene (mani_skill.envs.scene.ManiSkillScene) –
- 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) –
- config: PDEEPosControllerConfig[source]#
- class mani_skill.agents.controllers.pd_ee_pose.PDEEPosControllerConfig[source]#
Bases:
mani_skill.agents.controllers.base_controller.ControllerConfig- 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]#
- ee_link: str = None[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.
- 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
- 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
- root_link_name: str | None = None[source]#
Optionally set different root link for root translation control (e.g. if root is different than base)
- 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.
- class mani_skill.agents.controllers.pd_ee_pose.PDEEPoseController(config, articulation, control_freq, sim_freq=None, scene=None)[source]#
Bases:
PDEEPosControllerThe 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:
config (ControllerConfig) –
articulation (mani_skill.utils.structs.Articulation) –
control_freq (int) –
sim_freq (Optional[int]) –
scene (mani_skill.envs.scene.ManiSkillScene) –
- compute_target_pose(prev_ee_pose_at_base, action)[source]#
- Parameters:
prev_ee_pose_at_base (mani_skill.utils.structs.Pose) –
- class mani_skill.agents.controllers.pd_ee_pose.PDEEPoseControllerConfig[source]#
Bases:
PDEEPosControllerConfig- 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
- 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