habitat.tasks.rearrange.rearrange_sim.RearrangeSim class

Static methods

def build_semantic_CC_objects(…)
Get a dictionary of the current semantic scene’s connected components keyed by color or id, where each value is a list of Semantic Objects corresponding to an individual connected component.

Methods

def _create_obj_viz(self)
Adds a visualization of the goal for each of the target objects in the scene. This is the same as the target object, but is a render only object. This also places dots around the bounding box of the object to further distinguish the goal from the target object.
def _get_target_trans(self) -> typing.List[typing.Tuple[int, _magnum.Matrix4]]
This is how the target transforms should be accessed since multiprocessing does not allow pickling.
def _set_ao_states_from_ep(self, ep_info: datasets.rearrange.rearrange_dataset.RearrangeEpisode) -> None
Sets the ArticulatedObject states for the episode which are differ from base scene state.
def _sleep_all_objects(self)
De-activate (sleep) all rigid objects in the scene, assuming they are already in a dynamically stable state.
def action_space_shortest_path(self, source: core.simulator.AgentState, targets: typing.Sequence[core.simulator.AgentState], agent_id: int = 0) -> typing.List[core.simulator.ShortestPathPoint]
Returns: List of agent states and actions along the shortest path from source to the nearest target (both included). If one of the target(s) is identical to the source, a list containing only one node with the identical agent state is returned. Returns an empty list in case none of the targets are reachable from the source. For the last item in the returned list the action will be None.
def add_gradient_trajectory_object(self, traj_vis_name: str, points: typing.List[_magnum.Vector3], colors: typing.List[_magnum.Color3], num_segments: int = 3, radius: float = 0.001, smooth: bool = False, num_interpolations: int = 10) -> int
def add_keyframe_to_observations(self, observations)
Adds an item to observations that contains the latest gfx-replay keyframe. This is used to communicate the state of concurrent simulators to the batch renderer between processes.
def add_perf_timing(self, desc: str, t_start: float) -> None
Records a duration since t_start into the perf stats. Note that this is additive, so times between successive calls accumulate, not reset. Also note that this will only log if self._perf_logging_enabled=True.
def add_sensor(self, sensor_spec: habitat_sim._ext.habitat_sim_bindings.SensorSpec, agent_id: typing.Optional[int] = None) -> None
def add_trajectory_object(self, traj_vis_name: str, points: typing.List[_magnum.Vector3], num_segments: int = 3, radius: float = 0.001, color: _magnum.Color4 = Vector(0.9, 0.1, 0.1, 1), smooth: bool = False, num_interpolations: int = 10) -> int
Build a tube visualization around the passed trajectory of points. points : (list of 3-tuples of floats) key point locations to use to create trajectory tube. num_segments : (Integer) the number of segments around the tube to be used to make the visualization. radius : (Float) the radius of the resultant tube. color : (4-tuple of float) the color of the trajectory tube. smooth : (Bool) whether or not to smooth trajectory using a Catmull-Rom spline interpolating spline. num_interpolations : (Integer) the number of interpolation points to find between successive key points.
def build_vertex_color_map_report(self, /) -> typing.List[str]
Get a list of strings describing first each color found on vertices in the semantic mesh that is not present in the loaded semantic scene descriptor file, and then a list of each semantic object whose specified color is not found on any vertex in the mesh.
def capture_state(self, with_articulated_agent_js = False) -> typing.Dict[str, typing.Any]
Record and return a dict of state info.
def cast_ray(self, ray: habitat_sim._ext.habitat_sim_bindings.Ray, max_distance: float = 100.0) -> habitat_sim._ext.habitat_sim_bindings.RaycastResults
Cast a ray into the collidable scene and return hit results. Physics must be enabled. max_distance in units of ray length.
def close(self, destroy: bool = True) -> None
Close the simulator instance.
def contact_test(self, object_id: int) -> bool
DEPRECATED AND WILL BE REMOVED IN HABITAT-SIM 2.0. Run collision detection and return a binary indicator of penetration between the specified object and any other collision object. Physics must be enabled.
def create_rigid_constraint(self, settings: habitat_sim._ext.habitat_sim_bindings.RigidConstraintSettings) -> int
Create a rigid constraint between two objects or an object and the world from a RigidConstraintsSettings.
def create_sim_config(self, _sensor_suite: core.simulator.SensorSuite) -> habitat_sim.simulator.Configuration
def distance_to_closest_obstacle(self, position: numpy.ndarray, max_search_radius: float = 2.0) -> float
def enable_perf_logging(self)
Will turn on the performance logging (by default this is off).
def geodesic_distance(self, position_a: typing.Union[typing.Sequence[float], numpy.ndarray], position_b: typing.Union[typing.Sequence[float], typing.Sequence[typing.Sequence[float]], numpy.ndarray], episode: typing.Optional[core.dataset.Episode] = None) -> float
def get_active_scene_graph(self, /) -> habitat_sim._ext.habitat_sim_bindings.SceneGraph
PYTHON DOES NOT GET OWNERSHIP
def get_active_semantic_scene_graph(self, /) -> habitat_sim._ext.habitat_sim_bindings.SceneGraph
PYTHON DOES NOT GET OWNERSHIP
def get_agent(self, agent_id: int) -> habitat_sim.agent.agent.Agent
def get_agent_data(self, agent_idx: typing.Optional[int]) -> articulated_agent_manager.ArticulatedAgentData
def get_agent_state(self, agent_id: int = 0) -> habitat_sim.agent.agent.AgentState
def get_all_markers(self)
def get_articulated_object_manager(self, /) -> habitat_sim._ext.habitat_sim_bindings.ArticulatedObjectManager
Get the manager responsible for organizing and accessing all the currently constructed articulated objects.
def get_asset_template_manager(self, /) -> habitat_sim._ext.habitat_sim_bindings.AssetAttributesManager
Get the current dataset’s AssetAttributesManager instance for configuring primitive asset templates.
def get_current_light_setup(self, /) -> typing.List[habitat_sim._ext.habitat_sim_bindings.LightInfo]
Get a copy of the LightSetup used to create the current scene.
def get_debug_line_render(self, /) -> habitat_sim._ext.habitat_sim_bindings.DebugLineRender
Get visualization helper for rendering lines.
def get_gravity(self, /) -> _magnum.Vector3
Query the gravity vector for the scene.
def get_light_setup(self, key: str = '') -> typing.List[habitat_sim._ext.habitat_sim_bindings.LightInfo]
Get a copy of the LightSetup registered with a specific key.
def get_lighting_template_manager(self, /) -> habitat_sim._ext.habitat_sim_bindings.LightLayoutAttributesManager
Get the current dataset’s LightLayoutAttributesManager instance for configuring light templates and layouts.
def get_marker(self, name: str) -> marker_info.MarkerInfo
def get_n_targets(self) -> int
Get the number of rearrange targets.
def get_object_template_manager(self, /) -> habitat_sim._ext.habitat_sim_bindings.ObjectAttributesManager
Get the current dataset’s ObjectAttributesManager instance for configuring object templates.
def get_observations_at(self, position: typing.Optional[typing.List[float]] = None, rotation: typing.Optional[typing.List[float]] = None, keep_agent_at_new_pose: bool = False) -> typing.Optional[core.simulator.Observations]
def get_physics_contact_points(self, /) -> typing.List[habitat_sim._ext.habitat_sim_bindings.ContactPointData]
Return a list of ContactPointData ” “objects describing the contacts from the most recent physics substep.
def get_physics_num_active_contact_points(self, /) -> int
The number of contact points that were active during the last step. An object resting on another object will involve several active contact points. Once both objects are asleep, the contact points are inactive. This count is a proxy for complexity/cost of collision-handling in the current scene.
def get_physics_num_active_overlapping_pairs(self, /) -> int
The number of active overlapping pairs during the last step. When object bounding boxes overlap and either object is active, additional “narrowphase” collision-detection must be run. This count is a proxy for complexity/cost of collision-handling in the current scene.
def get_physics_simulation_library(self, /) -> habitat_sim._ext.habitat_sim_bindings.PhysicsSimulationLibrary
Query the physics library implementation currently configured by this Simulator instance.
def get_physics_step_collision_summary(self, /) -> str
Get a summary of collision-processing from the last physics step.
def get_physics_template_manager(self, /) -> habitat_sim._ext.habitat_sim_bindings.PhysicsAttributesManager
Get the current PhysicsAttributesManager instance for configuring PhysicsManager templates.
def get_physics_time_step(self, /) -> float
Get the last used physics timestep
def get_rigid_constraint_settings(self, constraint_id: int) -> habitat_sim._ext.habitat_sim_bindings.RigidConstraintSettings
Get a copy of the settings for an existing rigid constraint.
def get_rigid_object_manager(self, /) -> habitat_sim._ext.habitat_sim_bindings.RigidObjectManager
Get the manager responsible for organizing and accessing all the currently constructed rigid objects.
def get_runtime_perf_stat_names(self, /) -> typing.List[str]
Runtime perf stats are various scalars helpful for troubleshooting runtime perf. This can be called once at startup. See also get_runtime_perf_stat_values.
def get_runtime_perf_stat_values(self, /) -> typing.List[float]
Runtime perf stats are various scalars helpful for troubleshooting runtime perf. These values generally change after every sim step. See also get_runtime_perf_stat_names.
def get_runtime_perf_stats(self) -> typing.Dict[str, float]
def get_scene_pos(self) -> numpy.ndarray
Get the positions of all clutter RigidObjects in the scene as a numpy array.
def get_sensor_observations(self, agent_ids: typing.Union[int, typing.List[int]] = 0) -> typing.Union[typing.Dict[str, typing.Union[bool, numpy.ndarray, torch.Tensor]], typing.Dict[int, typing.Dict[str, typing.Union[bool, numpy.ndarray, torch.Tensor]]]]
def get_sensor_observations_async_finish(self) -> typing.Union[typing.Dict[str, typing.Union[numpy.ndarray, torch.Tensor]], typing.Dict[int, typing.Dict[str, typing.Union[numpy.ndarray, torch.Tensor]]]]
def get_stage_initialization_template(self, /) -> habitat_sim._ext.habitat_sim_bindings.StageAttributes
Get a copy of the StageAttributes template used to instance a scene’s stage or None if it does not exist.
def get_stage_is_collidable(self, /) -> bool
Get whether or not the static stage is collidable.
def get_stage_template_manager(self, /) -> habitat_sim._ext.habitat_sim_bindings.StageAttributesManager
Get the current dataset’s StageAttributesManager instance for configuring simulation stage templates.
def get_straight_shortest_path_points(self, position_a, position_b)
def get_target_objs_start(self) -> numpy.ndarray
Get the initial positions of all objects targeted for rearrangement as a numpy array.
def get_targets(self) -> typing.Tuple[numpy.ndarray, numpy.ndarray]
Get a mapping of object ids to goal positions for rearrange targets.
def get_world_time(self, /) -> float
Query the current simulation world time.
def initialize_agent(self, agent_id: int, initial_state: typing.Optional[habitat_sim.agent.agent.AgentState] = None) -> habitat_sim.agent.agent.Agent
def internal_step(self, dt: typing.Union[int, float], update_articulated_agent: bool = True) -> None
Step the world and update the articulated_agent.
def is_navigable(self, point: typing.List[float]) -> bool
def is_point_within_bounds(self, pos)
def island_radius(self, position: typing.Sequence[float]) -> float
def last_state(self, agent_id: typing.Optional[int] = None) -> habitat_sim.agent.agent.AgentState
def make_greedy_follower(self, agent_id: typing.Optional[int] = None, goal_radius: typing.Optional[float] = None, *, stop_key: typing.Optional[typing.Any] = None, forward_key: typing.Optional[typing.Any] = None, left_key: typing.Optional[typing.Any] = None, right_key: typing.Optional[typing.Any] = None, fix_thrashing: bool = True, thrashing_threshold: int = 16)
def maybe_update_articulated_agent(self)
Calls the update agents method on the articulated agent manager if the update_articulated_agent configuration is set to True. Among other things, this will set the articulated agent’s sensors’ positions to their new positions.
def perform_discrete_collision_detection(self, /) -> None
Perform discrete collision detection for the scene. Physics must be enabled. Warning: may break simulation determinism.
def physics_debug_draw(self, projMat: _magnum.Matrix4) -> None
Render any debugging visualizations provided by the underlying physics simulator implementation given the composed projection and transformation matrix for the render camera.
def recompute_navmesh(self, pathfinder: habitat_sim._ext.habitat_sim_bindings.PathFinder, navmesh_settings: habitat_sim._ext.habitat_sim_bindings.NavMeshSettings) -> bool
Recompute the NavMesh for a given PathFinder instance using configured NavMeshSettings.
def reconfigure(self, config: DictConfig, ep_info: datasets.rearrange.rearrange_dataset.RearrangeEpisode)
def remove_rigid_constraint(self, constraint_id: int) -> None
Remove a rigid constraint by id.
def render(self, mode: str = 'rgb') -> typing.Any
def reset(self)
def reset_agent(self, agent_id: int) -> None
def safe_snap_point(self, pos: numpy.ndarray) -> numpy.ndarray
Returns the 3D coordinates corresponding to a point belonging to the biggest navmesh island in the scenee and closest to pos. When that point returns NaN, computes a navigable point at increasing distances to it.
def sample_navigable_point(self) -> typing.List[float]
def save_current_scene_config(self, file_name: str) -> bool
Save the current simulation world’s state as a Scene Instance Config JSON using the passed name. This can be used to reload the stage, objects, articulated objects and other values as they currently are.
def save_current_scene_config(self, overwrite: bool = False) -> bool
Save the current simulation world’s state as a Scene Instance Config JSON using the name of the loaded scene, either overwritten, if overwrite is True, or with an incrementer in the file name of the form (copy xxxx) where xxxx is a number. This can be used to reload the stage, objects, articulated objects and other values as they currently are.
def seed(self, new_seed: int) -> None
def semantic_annotations(self)
Returns: SemanticScene which is a three level hierarchy of semantic annotations for the current scene. Specifically this method returns a SemanticScene which contains a list of SemanticLevel’s where each SemanticLevel contains a list of SemanticRegion’s where each SemanticRegion contains a list of SemanticObject’s.
def set_agent_state(self, position: typing.List[float], rotation: typing.List[float], agent_id: int = 0, reset_sensors: bool = True) -> bool
Sets agent state similar to initialize_agent, but without agents creation. On failure to place the agent in the proper position, it is moved back to its previous pose.
def set_articulated_agent_base_to_random_point(self, max_attempts: int = 50, agent_idx: typing.Optional[int] = None, filter_func: typing.Optional[typing.Callable[[numpy.ndarray, float], bool]] = None) -> typing.Tuple[numpy.ndarray, float]
def set_gravity(self, gravity: _magnum.Vector3) -> None
Set the gravity vector for the scene.
def set_light_setup(self, light_setup: typing.List[habitat_sim._ext.habitat_sim_bindings.LightInfo], key: str = '') -> None
Register a LightSetup with a specific key. If a LightSetup is already registered with this key, it will be overridden. All Drawables referencing the key will use the newly registered LightSetup.
def set_object_bb_draw(self, draw_bb: bool, object_id: int) -> None
Enable or disable bounding box visualization for an object.
def set_stage_is_collidable(self, collidable: bool) -> None
Set whether or not the static stage is collidable.
def set_state(self, state: typing.Dict[str, typing.Any], set_hold: bool = False) -> None
Sets the simulation state from a cached state info dict. See capture_state().
def start_async_render(self, agent_ids: typing.Union[int, typing.List[int]] = 0)
def start_async_render_and_step_physics(self, dt: float, agent_ids: typing.Union[int, typing.List[int]] = 0)
def step(self, action: typing.Union[str, int]) -> core.simulator.Observations
def step_filter(self, start_pos: _magnum.Vector3, end_pos: _magnum.Vector3) -> _magnum.Vector3
Computes a valid navigable end point given a target translation on the NavMesh. Uses the configured sliding flag.
def step_physics(self, dt: float) -> None
def step_world(self, dt: float = 0.016666666666666666) -> float
Step the physics simulation by a desired timestep (dt). Note that resulting world time after step may not be exactly t+dt. Use get_world_time to query current simulation time.
def update_rigid_constraint(self, constraint_id: int, settings: habitat_sim._ext.habitat_sim_bindings.RigidConstraintSettings) -> None
Update the settings of a rigid constraint.
def visualize_position(self, position: numpy.ndarray, viz_id: typing.Optional[int] = None, r: float = 0.05) -> int
Adds the sphere object to the specified position for visualization purpose.

Special methods

def __attrs_post_init__(self) -> None
def __del__(self) -> None
def __enter__(self) -> habitat_sim.simulator.Simulator
def __eq__(self, other)
Method generated by attrs for class Simulator.
def __exit__(self, exc_type, exc_val, exc_tb)
def __ge__(self, other)
Method generated by attrs for class Simulator.
def __gt__(self, other)
Method generated by attrs for class Simulator.
def __init__(self, config: DictConfig)
def __le__(self, other)
Method generated by attrs for class Simulator.
def __lt__(self, other)
Method generated by attrs for class Simulator.
def __ne__(self, other)
Method generated by attrs for class Simulator.
def __repr__(self)
Method generated by attrs for class Simulator.

Properties

action_space: gym.spaces.space.Space get
active_dataset: str get set
The currently active dataset being used. Will attempt to load configuration files specified if does not already exist.
articulated_agent get
curr_scene_name: str get
The simplified, but unique, name of the currently loaded scene.
draw_bb_objs: typing.List[int] get
Simulator object indices of objects to draw bounding boxes around if debug render is enabled. By default, this is populated with all target objects.
forward_vector: numpy.ndarray get
frustum_culling: bool get set
Enable or disable the frustum culling
gfx_replay_manager: habitat_sim._ext.habitat_sim_bindings.ReplayManager get
Use gfx_replay_manager for replay recording and playback.
gpu_device: int get
grasp_mgr: rearrange_grasp_manager.RearrangeGraspManager get
grasp_mgrs: typing.List[rearrange_grasp_manager.RearrangeGraspManager] get
handle_to_object_id: typing.Dict[str, int] get
Maps a handle name to the relative position of an object in self._scene_obj_ids.
largest_island_idx: int get
The path finder index of the indoor island that has the largest area.
metadata_mediator: habitat_sim._ext.habitat_sim_bindings.MetadataMediator get set
This construct manages all configuration template managers and the Scene Dataset Configurations
Enable or disable wireframe visualization of current pathfinder’s NavMesh.
num_articulated_agents get
pathfinder: habitat_sim._ext.habitat_sim_bindings.PathFinder get set
previous_step_collided get
Whether or not the previous step resulted in a collision
random: habitat_sim._ext.habitat_sim_bindings.Random get
receptacles: typing.Dict[str, datasets.rearrange.samplers.receptacle.Receptacle] get
renderer: habitat_sim._ext.habitat_sim_bindings.Renderer get
scene_obj_ids: typing.List[int] get
The simulator rigid body IDs of all objects in the scene.
semantic_color_map get
The list of semantic colors being used for semantic rendering. The index in the list corresponds to the semantic ID.
semantic_scene: habitat_sim._ext.habitat_sim_bindings.SemanticScene get
The semantic scene graph
sensor_suite: core.simulator.SensorSuite get
up_vector: numpy.ndarray get
config: habitat_sim.simulator.Configuration get set del
agents: typing.List[habitat_sim.agent.agent.Agent] get set del

Method documentation

def habitat.tasks.rearrange.rearrange_sim.RearrangeSim.add_keyframe_to_observations(self, observations)

Adds an item to observations that contains the latest gfx-replay keyframe. This is used to communicate the state of concurrent simulators to the batch renderer between processes.

Parameters
observations Original observations upon which the keyframe is added.

def habitat.tasks.rearrange.rearrange_sim.RearrangeSim.capture_state(self, with_articulated_agent_js = False) -> typing.Dict[str, typing.Any]

Record and return a dict of state info.

Parameters
with_articulated_agent_js If true, state dict includes articulated_agent joint positions in addition.
State info dict includes:
  • Robot transform
  • a list of ArticulatedObject transforms
  • a list of RigidObject transforms
  • a list of ArticulatedObject joint states
  • the object id of currently grasped object (or None)
  • (optionally) the articulated_agent’s joint positions

def habitat.tasks.rearrange.rearrange_sim.RearrangeSim.close(self, destroy: bool = True) -> None

Close the simulator instance.

Parameters
destroy Whether or not to force the OpenGL context to be destroyed if async rendering was used. If async rendering wasn’t used, this has no effect.

def habitat.tasks.rearrange.rearrange_sim.RearrangeSim.get_targets(self) -> typing.Tuple[numpy.ndarray, numpy.ndarray]

Get a mapping of object ids to goal positions for rearrange targets.

Returns ([idx: int], [goal_pos: list]) The index of the target object in self._scene_obj_ids and the 3D goal position, rotation is IGNORED. Note that goal_pos is the desired position of the object, not the starting position.

def habitat.tasks.rearrange.rearrange_sim.RearrangeSim.internal_step(self, dt: typing.Union[int, float], update_articulated_agent: bool = True) -> None

Step the world and update the articulated_agent.

Parameters
dt Timestep by which to advance the world. Multiple physics substeps can be executed within a single timestep. -1 indicates a single physics substep.
update_articulated_agent

Never call sim.step_world directly or miss updating the articulated_agent.

def habitat.tasks.rearrange.rearrange_sim.RearrangeSim.render(self, mode: str = 'rgb') -> typing.Any

Returns:
rendered frame according to the mode

def habitat.tasks.rearrange.rearrange_sim.RearrangeSim.set_state(self, state: typing.Dict[str, typing.Any], set_hold: bool = False) -> None

Sets the simulation state from a cached state info dict. See capture_state().

param set_hold:
If true this will set the snapped object from the state.

TODO: This should probably be True by default, but I am not sure the effect it will have.

def habitat.tasks.rearrange.rearrange_sim.RearrangeSim.step_filter(self, start_pos: _magnum.Vector3, end_pos: _magnum.Vector3) -> _magnum.Vector3

Computes a valid navigable end point given a target translation on the NavMesh. Uses the configured sliding flag.

Parameters
start_pos The valid initial position of a translation.
end_pos The target end position of a translation.

Property documentation

habitat.tasks.rearrange.rearrange_sim.RearrangeSim.semantic_scene: habitat_sim._ext.habitat_sim_bindings.SemanticScene get

The semantic scene graph