mani_skill.agents.base_agent#
- class mani_skill.agents.base_agent.BaseAgent(scene: ManiSkillScene, control_freq: int, control_mode: str | None = None, agent_idx: str | None = None, initial_pose: sapien.Pose | Pose | None = None, build_separate: bool = False)[source]#
Bases:
objectBase 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 its tutorial
- Parameters:
scene (ManiSkillScene) – simulation scene instance.
control_freq (int) – control frequency (Hz).
control_mode (str | None) – uid of controller to use
fix_root_link (bool) – whether to fix the robot root link
agent_idx (str | None) – an index for this agent in a multi-agent task setup If None, the task should be single-agent
initial_pose (sapien.Pose | Pose | None) – the initial pose of the robot. Important to set for GPU simulation to ensure robot
called (does not collide with other objects in the scene during GPU initialization which occurs before env._initialize_episode is) –
- before_simulation_step()[source]#
Code that runs before each simulation step. By default it calls the controller’s before_simulation_step method.
- property control_mode#
Get the currently activated controller uid.
- property controller: BaseController#
Get currently activated controller.
- controllers: Dict[str, BaseController]#
The controllers of the robot.
- property device#
- disable_self_collisions: bool = False#
Whether to disable self collisions. This is generally not recommended as you should be defining a SRDF file to exclude specific collisions. However for some robots/tasks it may be easier to disable all self collisions between links in the robot to increase simulation speed
- fix_root_link: bool = True#
Whether to fix the root link of the robot in place.
- get_proprioception()[source]#
Get the proprioceptive state of the agent, default is the qpos and qvel of the robot and any controller state.
- is_grasping(object: Actor | None = None)[source]#
Check if this agent is grasping an object or grasping anything at all
- Parameters:
object (Actor | None) – If object is a Actor, this function checks grasping against that. If it is none, the function checks if the agent is grasping anything at all.
- Returns:
True if agent is grasping object. False otherwise. If object is None, returns True if agent is grasping something, False if agent is grasping nothing.
- is_static(threshold: float)[source]#
Check if this robot is static (within the given threshold) in terms of the q velocity
- Parameters:
threshold (float) – The threshold before this agent is considered static
- Returns:
True if agent is static within the threshold. False otherwise
- keyframes: Dict[str, Keyframe] = {}#
a dict of predefined keyframes similar to what Mujoco does that you can use to reset the agent to that may be of interest
- load_multiple_collisions: bool = False#
Whether the referenced collision meshes of a robot definition should be loaded as multiple convex collisions
- mjcf_path: str | None = None#
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.
- reset(init_qpos: Tensor | None = None)[source]#
Reset the robot to a clean state with zero velocity and forces.
- Parameters:
init_qpos (torch.Tensor) – The initial qpos to set the robot to. If None, the robot’s qpos is not changed.
- robot: Articulation#
The robot object, which is an Articulation. Data like pose, qpos etc. can be accessed from this object.
- sensors: Dict[str, BaseSensor]#
The sensors that come with the robot.
- set_action(action)[source]#
Set the agent’s action which is to be executed in the next environment timestep. This is essentially a wrapper around the controller’s set_action method.
- set_control_mode(control_mode: str | None = None)[source]#
Sets the controller to an pre-existing controller of this agent. This does not reset the controller. If given control mode is None, will set to the default control mode.
- set_state(state: Dict, ignore_controller=False)[source]#
Set the state of the agent, including the robot state and controller state. If ignore_controller is True, the controller state will not be updated.
- supported_control_modes#
List of all possible control modes for this robot.
- uid: str#
unique identifier string of this
- urdf_config: str | Dict = None#
Optional provide a urdf_config to further modify the created articulation
- urdf_path: str | None = None#
path to the .urdf file describe the agent’s geometry and visuals. One of urdf_path or mjcf_path must be provided.
- class mani_skill.agents.base_agent.Keyframe(pose: 'sapien.Pose', qpos: 'Optional[Array]' = None, qvel: 'Optional[Array]' = None)[source]#
Bases:
object- pose: Pose#
sapien Pose object describe this keyframe’s pose
- qpos: Tensor | ndarray | Sequence | None = None#
the qpos of the robot at this keyframe
- qvel: Tensor | ndarray | Sequence | None = None#
the qvel of the robot at this keyframe