mani_skill.agents.controllers ============================= .. py:module:: mani_skill.agents.controllers Submodules ---------- .. toctree:: :maxdepth: 1 /api/mani_skill/agents/controllers/base_controller/index /api/mani_skill/agents/controllers/passive_controller/index /api/mani_skill/agents/controllers/pd_base_vel/index /api/mani_skill/agents/controllers/pd_ee_pose/index /api/mani_skill/agents/controllers/pd_joint_pos/index /api/mani_skill/agents/controllers/pd_joint_pos_vel/index /api/mani_skill/agents/controllers/pd_joint_vel/index /api/mani_skill/agents/controllers/utils/index Classes ------- .. autoapisummary:: mani_skill.agents.controllers.PDBaseForwardVelController mani_skill.agents.controllers.PDBaseForwardVelControllerConfig mani_skill.agents.controllers.PDBaseVelController mani_skill.agents.controllers.PDBaseVelControllerConfig mani_skill.agents.controllers.PDEEPosController mani_skill.agents.controllers.PDEEPosControllerConfig mani_skill.agents.controllers.PDEEPoseController mani_skill.agents.controllers.PDEEPoseControllerConfig mani_skill.agents.controllers.PDJointPosController mani_skill.agents.controllers.PDJointPosControllerConfig mani_skill.agents.controllers.PDJointPosMimicController mani_skill.agents.controllers.PDJointPosMimicControllerConfig mani_skill.agents.controllers.PDJointPosVelController mani_skill.agents.controllers.PDJointPosVelControllerConfig mani_skill.agents.controllers.PDJointVelController mani_skill.agents.controllers.PDJointVelControllerConfig mani_skill.agents.controllers.PassiveController mani_skill.agents.controllers.PassiveControllerConfig Functions --------- .. autoapisummary:: mani_skill.agents.controllers.deepcopy_dict Package Contents ---------------- .. py:class:: PDBaseForwardVelController(config, articulation, control_freq, sim_freq = None, scene = None) Bases: :py:obj:`mani_skill.agents.controllers.pd_joint_vel.PDJointVelController` PDJointVelController for forward-only ego-centric base movement. .. py:method:: _initialize_action_space() .. py:method:: set_action(action) Set the action to execute. The action can be low-level control signals or high-level abstract commands. .. py:class:: PDBaseForwardVelControllerConfig Bases: :py:obj:`mani_skill.agents.controllers.pd_joint_vel.PDJointVelControllerConfig` .. py:attribute:: controller_cls .. py:class:: PDBaseVelController(config, articulation, control_freq, sim_freq = None, scene = None) Bases: :py:obj:`mani_skill.agents.controllers.pd_joint_vel.PDJointVelController` PDJointVelController for ego-centric base movement. .. py:method:: _initialize_action_space() .. py:method:: set_action(action) Set the action to execute. The action can be low-level control signals or high-level abstract commands. .. py:class:: PDBaseVelControllerConfig Bases: :py:obj:`mani_skill.agents.controllers.pd_joint_vel.PDJointVelControllerConfig` .. py:attribute:: controller_cls .. py:class:: PDEEPosController(config, articulation, control_freq, sim_freq = None, scene = None) Bases: :py:obj:`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 .. py:method:: __repr__() .. py:method:: _check_gpu_sim_works() .. py:method:: _initialize_action_space() .. py:method:: _initialize_joints() .. py:method:: compute_target_pose(prev_ee_pose_at_base, action) .. py:method:: get_state() Get the controller state. .. py:method:: reset() Resets the controller to an initial state. This is called upon environment creation and each environment reset .. py:method:: set_action(action) Set the action to execute. The action can be low-level control signals or high-level abstract commands. .. py:method:: set_state(state) .. py:attribute:: _target_pose :value: None .. py:attribute:: config :type: PDEEPosControllerConfig .. py:property:: ee_pos .. py:property:: ee_pose .. py:property:: ee_pose_at_base .. py:class:: PDEEPosControllerConfig Bases: :py:obj:`mani_skill.agents.controllers.base_controller.ControllerConfig` .. py:attribute:: controller_cls .. py:attribute:: damping :type: Union[float, Sequence[float]] .. py:attribute:: delta_solver_config :type: 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 .. py:attribute:: drive_mode :type: Union[Sequence[mani_skill.utils.structs.types.DriveMode], mani_skill.utils.structs.types.DriveMode] :value: 'force' .. py:attribute:: ee_link :type: str :value: None 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. .. py:attribute:: force_limit :type: Union[float, Sequence[float]] :value: 10000000000.0 .. py:attribute:: frame :type: Literal['body_translation', 'root_translation'] :value: '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 .. py:attribute:: friction :type: Union[float, Sequence[float]] :value: 0.0 .. py:attribute:: interpolate :type: bool :value: False .. py:attribute:: normalize_action :type: bool :value: 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. .. py:attribute:: pos_lower :type: Union[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 .. py:attribute:: pos_upper :type: Union[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 .. py:attribute:: root_link_name :type: Optional[str] :value: None Optionally set different root link for root translation control (e.g. if root is different than base) .. py:attribute:: stiffness :type: Union[float, Sequence[float]] .. py:attribute:: urdf_path :type: str :value: None Path to the URDF file defining the robot to control. .. py:attribute:: use_delta :type: bool :value: 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. .. py:attribute:: use_target :type: bool :value: 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. .. py:class:: PDEEPoseController(config, articulation, control_freq, sim_freq = None, scene = None) Bases: :py:obj:`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 .. py:method:: _check_gpu_sim_works() .. py:method:: _clip_and_scale_action(action) .. py:method:: _initialize_action_space() .. py:method:: compute_target_pose(prev_ee_pose_at_base, action) .. py:attribute:: config :type: PDEEPoseControllerConfig .. py:class:: PDEEPoseControllerConfig Bases: :py:obj:`PDEEPosControllerConfig` .. py:attribute:: controller_cls .. py:attribute:: damping :type: Union[float, Sequence[float]] :value: None .. py:attribute:: force_limit :type: Union[float, Sequence[float]] :value: 10000000000.0 .. py:attribute:: frame :type: 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'] :value: '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 .. py:attribute:: friction :type: Union[float, Sequence[float]] :value: 0.0 .. py:attribute:: rot_lower :type: Union[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 .. py:attribute:: rot_upper :type: Union[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 .. py:attribute:: stiffness :type: Union[float, Sequence[float]] :value: None .. py:class:: PDJointPosController(config, articulation, control_freq, sim_freq = None, scene = None) Bases: :py:obj:`mani_skill.agents.controllers.base_controller.BaseController` Base class for controllers. The controller is an interface for the robot to interact with the environment. .. py:method:: _get_joint_limits() .. py:method:: _initialize_action_space() .. py:method:: before_simulation_step() Called before each simulation step in one control step. .. py:method:: get_state() Get the controller state. .. py:method:: reset() Resets the controller to an initial state. This is called upon environment creation and each environment reset .. py:method:: set_action(action) Set the action to execute. The action can be low-level control signals or high-level abstract commands. .. py:method:: set_drive_property() Set the joint drive property according to the config. .. py:method:: set_drive_targets(targets) .. py:method:: set_state(state) .. py:attribute:: _start_qpos :value: None .. py:attribute:: _target_qpos :value: None .. py:attribute:: config :type: PDJointPosControllerConfig .. py:attribute:: sets_target_qpos :value: True Whether the controller sets the target qpos of the articulation .. py:attribute:: sets_target_qvel :value: False Whether the controller sets the target qvel of the articulation .. py:class:: PDJointPosControllerConfig Bases: :py:obj:`mani_skill.agents.controllers.base_controller.ControllerConfig` .. py:attribute:: controller_cls .. py:attribute:: damping :type: Union[float, Sequence[float]] .. py:attribute:: drive_mode :type: Union[Sequence[mani_skill.utils.structs.types.DriveMode], mani_skill.utils.structs.types.DriveMode] :value: 'force' .. py:attribute:: force_limit :type: Union[float, Sequence[float]] :value: 10000000000.0 .. py:attribute:: friction :type: Union[float, Sequence[float]] :value: 0.0 .. py:attribute:: interpolate :type: bool :value: False .. py:attribute:: lower :type: Union[None, float, Sequence[float]] .. py:attribute:: normalize_action :type: bool :value: True .. py:attribute:: stiffness :type: Union[float, Sequence[float]] .. py:attribute:: upper :type: Union[None, float, Sequence[float]] .. py:attribute:: use_delta :type: bool :value: False .. py:attribute:: use_target :type: bool :value: False .. py:class:: PDJointPosMimicController(config, articulation, control_freq, sim_freq = None, scene = None) Bases: :py:obj:`PDJointPosController` Base class for controllers. The controller is an interface for the robot to interact with the environment. .. py:method:: __repr__() .. py:method:: _get_joint_limits() .. py:method:: _initialize_joints() .. py:method:: set_action(action) Set the action to execute. The action can be low-level control signals or high-level abstract commands. .. py:attribute:: config :type: PDJointPosMimicControllerConfig .. py:class:: PDJointPosMimicControllerConfig Bases: :py:obj:`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. .. py:attribute:: controller_cls .. py:attribute:: mimic :type: 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 .. py:class:: PDJointPosVelController(config, articulation, control_freq, sim_freq = None, scene = None) Bases: :py:obj:`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. .. py:method:: _initialize_action_space() .. py:method:: reset() Resets the controller to an initial state. This is called upon environment creation and each environment reset .. py:method:: set_action(action) Set the action to execute. The action can be low-level control signals or high-level abstract commands. .. py:method:: set_drive_velocity_targets(targets) .. py:attribute:: _target_qvel :value: None .. py:attribute:: config :type: PDJointPosVelControllerConfig .. py:attribute:: sets_target_qpos :value: True Whether the controller sets the target qpos of the articulation .. py:attribute:: sets_target_qvel :value: True Whether the controller sets the target qvel of the articulation .. py:class:: PDJointPosVelControllerConfig Bases: :py:obj:`mani_skill.agents.controllers.pd_joint_pos.PDJointPosControllerConfig` .. py:attribute:: controller_cls .. py:attribute:: vel_lower :type: Union[float, Sequence[float]] :value: -1.0 .. py:attribute:: vel_upper :type: Union[float, Sequence[float]] :value: 1.0 .. py:class:: PDJointVelController(config, articulation, control_freq, sim_freq = None, scene = None) Bases: :py:obj:`mani_skill.agents.controllers.base_controller.BaseController` Base class for controllers. The controller is an interface for the robot to interact with the environment. .. py:method:: _initialize_action_space() .. py:method:: set_action(action) Set the action to execute. The action can be low-level control signals or high-level abstract commands. .. py:method:: set_drive_property() Set the joint drive property according to the config. .. py:attribute:: config :type: PDJointVelControllerConfig .. py:attribute:: sets_target_qpos :value: False Whether the controller sets the target qpos of the articulation .. py:attribute:: sets_target_qvel :value: True Whether the controller sets the target qvel of the articulation .. py:class:: PDJointVelControllerConfig Bases: :py:obj:`mani_skill.agents.controllers.base_controller.ControllerConfig` .. py:attribute:: controller_cls .. py:attribute:: damping :type: Union[float, Sequence[float]] .. py:attribute:: drive_mode :type: Union[Sequence[mani_skill.utils.structs.types.DriveMode], mani_skill.utils.structs.types.DriveMode] :value: 'force' .. py:attribute:: force_limit :type: Union[float, Sequence[float]] :value: 10000000000.0 .. py:attribute:: friction :type: Union[float, Sequence[float]] :value: 0.0 .. py:attribute:: lower :type: Union[float, Sequence[float]] .. py:attribute:: normalize_action :type: bool :value: True .. py:attribute:: upper :type: Union[float, Sequence[float]] .. py:class:: PassiveController(config, articulation, control_freq, sim_freq = None, scene = None) Bases: :py:obj:`mani_skill.agents.controllers.base_controller.BaseController` Passive controller that does not do anything .. py:method:: _initialize_action_space() .. py:method:: before_simulation_step() Called before each simulation step in one control step. .. py:method:: set_action(action) Set the action to execute. The action can be low-level control signals or high-level abstract commands. .. py:method:: set_drive_property() Set the joint drive property according to the config. .. py:attribute:: config :type: PassiveControllerConfig .. py:attribute:: sets_target_qpos :value: False Whether the controller sets the target qpos of the articulation .. py:attribute:: sets_target_qvel :value: False Whether the controller sets the target qvel of the articulation .. py:class:: PassiveControllerConfig Bases: :py:obj:`mani_skill.agents.controllers.base_controller.ControllerConfig` .. py:attribute:: controller_cls .. py:attribute:: damping :type: Union[float, Sequence[float]] .. py:attribute:: force_limit :type: Union[float, Sequence[float]] :value: 10000000000.0 .. py:attribute:: friction :type: Union[float, Sequence[float]] :value: 0.0 .. py:function:: deepcopy_dict(configs) Make a deepcopy of dict. The built-in behavior will not copy references to the same value.