mani_skill.envs.tasks.control.hopper ==================================== .. py:module:: mani_skill.envs.tasks.control.hopper .. autoapi-nested-parse:: Adapted from https://github.com/google-deepmind/dm_control/blob/main/dm_control/suite/hopper.py Attributes ---------- .. autoapisummary:: mani_skill.envs.tasks.control.hopper.MJCF_FILE mani_skill.envs.tasks.control.hopper._HOP_SPEED mani_skill.envs.tasks.control.hopper._STAND_HEIGHT Classes ------- .. autoapisummary:: mani_skill.envs.tasks.control.hopper.HopperEnv mani_skill.envs.tasks.control.hopper.HopperHopEnv mani_skill.envs.tasks.control.hopper.HopperRobot mani_skill.envs.tasks.control.hopper.HopperStandEnv Module Contents --------------- .. py:class:: HopperEnv(*args, robot_uids=HopperRobot, **kwargs) Bases: :py:obj:`mani_skill.envs.sapien_env.BaseEnv` Superclass for ManiSkill environments. :param num_envs: number of parallel environments to run. By default this is 1, which means a CPU simulation is used. If greater than 1, then we initialize the GPU simulation setup. Note that not all environments are faster when simulated on the GPU due to limitations of GPU simulations. For example, environments with many moving objects are better simulated by parallelizing across CPUs. :param obs_mode: observation mode to be used. Must be one of ("state", "state_dict", "none", "sensor_data", "rgb", "depth", "segmentation", "rgbd", "rgb+depth", "rgb+depth+segmentation", "rgb+segmentation", "depth+segmentation", "pointcloud") The obs_mode is mostly for convenience to automatically optimize/setup all sensors/cameras for the given observation mode to render the correct data and try to ignore unnecessary rendering. For the most advanced use cases (e.g. you have 1 RGB only camera and 1 depth only camera) :param reward_mode: reward mode to use. Must be one of ("normalized_dense", "dense", "sparse", "none"). With "none" the reward returned is always 0 :param control_mode: control mode of the agent. "*" represents all registered controllers, and the action space will be a dict. :param render_mode: render mode registered in @SUPPORTED_RENDER_MODES. :param shader_dir: shader directory. Defaults to None. Setting this will override the shader used for all cameras in the environment. This is legacy behavior kept for backwards compatibility. The proper way to change the shaders used for cameras is to either change the environment code or pass in sensor_configs/human_render_camera_configs with the desired shaders. Previously the options are "default", "rt", "rt-fast". "rt" means ray-tracing which results in more photorealistic renders but is slow, "rt-fast" is a lower quality but faster version of "rt". :type shader_dir: Optional[str] :param enable_shadow: whether to enable shadow for lights. Defaults to False. :type enable_shadow: bool :param sensor_configs: configurations of sensors to override any environment defaults. If the key is one of sensor names (e.g. a camera), the config value will be applied to the corresponding sensor. Otherwise, the value will be applied to all sensors (but overridden by sensor-specific values). For possible configurations see the documentation see :doc:`the sensors documentation `. :type sensor_configs: dict :param human_render_camera_configs: configurations of human rendering cameras to override any environment defaults. Similar usage as @sensor_configs. :type human_render_camera_configs: dict :param viewer_camera_configs: configurations of the viewer camera in the GUI to override any environment defaults. Similar usage as @sensor_configs. :type viewer_camera_configs: dict :param robot_uids: list of robots to instantiate and control in the environment. :type robot_uids: Union[str, BaseAgent, list[Union[str, BaseAgent]]] :param sim_config: Configurations for simulation if used that override the environment defaults. If given a dictionary, it can just override specific attributes e.g. ``sim_config=dict(scene_config=dict(solver_iterations=25))``. If passing in a SimConfig object, while typed, will override every attribute including the task defaults. Some environments define their own recommended default sim configurations via the ``self._default_sim_config`` attribute that generally should not be completely overriden. :type sim_config: Union[SimConfig, dict] :param reconfiguration_freq: How frequently to call reconfigure when environment is reset via `self.reset(...)` Generally for most users who are not building tasks this does not need to be changed. The default is 0, which means the environment reconfigures upon creation, and never again. :type reconfiguration_freq: int :param sim_backend: By default this is "auto". If sim_backend is "auto", then if ``num_envs == 1``, we use the PhysX CPU sim backend, otherwise we use the PhysX GPU sim backend and automatically pick a GPU to use. Can also be "physx_cpu" or "physx_cuda" to force usage of a particular sim backend. To select a particular GPU to run the simulation on, you can pass "physx_cuda:n" where n is the ID of the GPU, similar to the way PyTorch selects GPUs. Note that if this is "physx_cpu", num_envs can only be equal to 1. :type sim_backend: str :param render_backend: By default this is "gpu". If render_backend is "gpu" or it's alias "sapien_cuda", then we auto select a GPU to render with. It can be "sapien_cuda:n" where n is the ID of the GPU to render with. If this is "cpu" or "sapien_cpu", then we try to render on the CPU. If this is "none" or None, then we disable rendering. Note that some environments may require rendering functionalities to work. Moreover it is sometimes difficult to determine before running an environment if your machine can render or not. If you encounter some issue with rendering you can first try to double check your NVIDIA drivers / Vulkan drivers are setup correctly. If you don't need to do rendering you can simply disable it by setting render_backend to "none" or None. :type render_backend: str :param parallel_in_single_scene: By default this is False. If True, rendered images and the GUI will show all objects in one view. This is only really useful for generating cool videos showing all environments at once but it is not recommended otherwise as it slows down simulation and rendering. :type parallel_in_single_scene: bool :param enhanced_determinism: By default this is False and env resets will reset the episode RNG only when a seed / seed list is given. If True, the environment will reset the episode RNG upon each reset regardless of whether a seed is provided. Generally enhanced_determinisim is not needed and users are recommended to pass seeds into the env reset function instead. :type enhanced_determinism: bool .. py:method:: _get_obs_state_dict(info) Get (ground-truth) state-based observations. .. py:method:: _initialize_episode(env_idx, options) Initialize the episode, e.g., poses of actors and articulations, as well as task relevant data like randomizing goal positions .. py:method:: _load_scene(options) Loads all objects like actors and articulations into the scene. Called by `self._reconfigure`. Given options argument is the same options dictionary passed to the self.reset function .. py:method:: touch(link_name) Returns function of sensor force values .. py:property:: _default_human_render_camera_configs Add default cameras for rendering when using render_mode='rgb_array'. These can be overriden by the user at env creation time .. py:property:: _default_sensor_configs Add default (non-agent) sensors to the environment by returning sensor configurations. These can be overriden by the user at env creation time .. py:property:: _default_sim_config .. py:attribute:: agent :type: Union[HopperRobot] .. py:property:: height Returns relative height of the robot .. py:property:: subtreelinvelx .. py:class:: HopperHopEnv(*args, **kwargs) Bases: :py:obj:`HopperEnv` **Task Description:** Hopper robot stays upright and moves in positive x direction with hopping motion **Randomizations:** - Hopper robot is randomly rotated [-pi, pi] radians about y axis. - Hopper qpos are uniformly sampled within their allowed ranges **Success Conditions:** - No specific success conditions. The task is considered successful if the hopper hops for the whole episode. .. py:method:: compute_dense_reward(obs, action, info) Compute the dense reward. :param obs: The observation data. By default the observation data will be in its most raw form, a dictionary (no flattening, wrappers etc.) :type obs: Any :param action: The most recent action. :type action: torch.Tensor :param info: The info dictionary. :type info: dict .. py:method:: compute_normalized_dense_reward(obs, action, info) Compute the normalized dense reward. :param obs: The observation data. By default the observation data will be in its most raw form, a dictionary (no flattening, wrappers etc.) :type obs: Any :param action: The most recent action. :type action: torch.Tensor :param info: The info dictionary. :type info: dict .. py:class:: HopperRobot(*args, **kwargs) Bases: :py:obj:`mani_skill.agents.base_agent.BaseAgent` Base class for agents/robots, forming an interface of an articulated robot (SAPIEN's physx.PhysxArticulation). Users implementing their own agents/robots should inherit from this class. A tutorial on how to build your own agent can be found in :doc:`its tutorial ` :param scene: simulation scene instance. :type scene: ManiSkillScene :param control_freq: control frequency (Hz). :type control_freq: int :param control_mode: uid of controller to use :type control_mode: str | None :param fix_root_link: whether to fix the robot root link :type fix_root_link: bool :param agent_idx: an index for this agent in a multi-agent task setup If None, the task should be single-agent :type agent_idx: str | None :param initial_pose: the initial pose of the robot. Important to set for GPU simulation to ensure robot :type initial_pose: sapien.Pose | Pose | None :param does not collide with other objects in the scene during GPU initialization which occurs before `env._initialize_episode` is called: .. py:method:: _load_articulation(initial_pose = None) Load the robot articulation .. py:method:: get_proprioception() Get the proprioceptive state of the agent, default is the qpos and qvel of the robot and any controller state. .. py:property:: _controller_configs Returns a dict of controller configs for this agent. By default this is a PDJointPos (delta and non delta) controller for all active joints. .. py:attribute:: mjcf_path :value: 'Uninferable' path to a MJCF .xml file defining a robot. This will only load the articulation defined in the XML and nothing else. One of urdf_path or mjcf_path must be provided. .. py:attribute:: uid :value: 'hopper' unique identifier string of this .. py:class:: HopperStandEnv(*args, **kwargs) Bases: :py:obj:`HopperEnv` **Task Description:** Hopper robot stands upright **Randomizations:** - Hopper robot is randomly rotated [-pi, pi] radians about y axis. - Hopper qpos are uniformly sampled within their allowed ranges **Success Conditions:** - No specific success conditions. .. py:method:: compute_dense_reward(obs, action, info) Compute the dense reward. :param obs: The observation data. By default the observation data will be in its most raw form, a dictionary (no flattening, wrappers etc.) :type obs: Any :param action: The most recent action. :type action: torch.Tensor :param info: The info dictionary. :type info: dict .. py:method:: compute_normalized_dense_reward(obs, action, info) Compute the normalized dense reward. :param obs: The observation data. By default the observation data will be in its most raw form, a dictionary (no flattening, wrappers etc.) :type obs: Any :param action: The most recent action. :type action: torch.Tensor :param info: The info dictionary. :type info: dict .. py:data:: MJCF_FILE :value: 'Uninferable' .. py:data:: _HOP_SPEED :value: 2 .. py:data:: _STAND_HEIGHT :value: 0.6