Classes
-
module habitat
-
module config
-
module default_structured_configs
- class HabitatConfig The entry point for the configuration of Habitat. It holds the environment, simulator, task and dataset configurations.
- class DatasetConfig Configuration for the dataset of the task.
- class TaskConfig The definition of the task in Habitat.
- class EnvironmentConfig Some habitat environment configurations.
- class StopActionConfig In Navigation tasks only, the stop action is a discrete action. When called, the Agent will request to stop the navigation task. Note that this action is needed to succeed in a Navigation task since the Success is determined by the Agent calling the stop action within range of the target. Note that this is different from the RearrangeStopActionConfig that works for Rearrangement tasks only instead of the Navigation tasks.
- class MoveForwardActionConfig In Navigation tasks only, this discrete action will move the robot forward by a fixed amount determined by the SimulatorConfig.forward_step_size amount.
- class TurnLeftActionConfig In Navigation tasks only, this discrete action will rotate the robot to the left by a fixed amount determined by the SimulatorConfig.turn_angle amount.
- class TurnLeftActionConfig In Navigation tasks only, this discrete action will rotate the robot to the left by a fixed amount determined by the SimulatorConfig.turn_angle amount.
- class TurnRightActionConfig In Navigation tasks only, this discrete action will rotate the robot to the right by a fixed amount determined by the SimulatorConfig.turn_angle amount.
- class LookUpActionConfig In Navigation tasks only, this discrete action will rotate the robot’s camera up by a fixed amount determined by the SimulatorConfig.tilt_angle amount.
- class LookDownActionConfig In Navigation tasks only, this discrete action will rotate the robot’s camera down by a fixed amount determined by the SimulatorConfig.tilt_angle amount.
- class NumStepsMeasurementConfig In both Navigation and Rearrangement tasks, counts the number of steps since the start of the episode.
- class DistanceToGoalMeasurementConfig In Navigation tasks only, measures the geodesic distance to the goal.
- class SuccessMeasurementConfig For Navigation tasks only, Measures 1.0 if the robot reached a success and 0 otherwise. A success is defined as calling the StopAction when the DistanceToGoal Measure is smaller than success_distance.
- class SPLMeasurementConfig For Navigation tasks only, Measures the SPL (Success weighted by Path Length) ref: On Evaluation of Embodied Agents - Anderson et. al https://arxiv.org/pdf/1807.06757.pdf Measure is always 0 except at success where it will be the ratio of the optimal distance from start to goal over the total distance traveled by the agent. Maximum value is 1. SPL = success * optimal_distance_to_goal / distance_traveled_so_far
- class SoftSPLMeasurementConfig For Navigation tasks only, Similar to SPL, but instead of a boolean, success is now calculated as 1 - (ratio of distance covered to target). SoftSPL = max(0, 1 - distance_to_goal / optimal_distance_to_goal) * optimal_distance_to_goal / distance_traveled_so_far
- class DistanceToGoalRewardMeasurementConfig In Navigation tasks only, measures a reward based on the distance towards the goal. The reward is - (new_distance - previous_distance) i.e. the decrease of distance to the goal.
- class ObjectGoalSensorConfig For Object Navigation tasks only. Generates a discrete observation containing the id of the goal object for the episode.
- class InstanceImageGoalSensorConfig Used only by the InstanceImageGoal Navigation task. The observation is a rendered image of the goal object within the scene.
- class InstanceImageGoalHFOVSensorConfig Used only by the InstanceImageGoal Navigation task. The observation is a single float value corresponding to the Horizontal field of view (HFOV) in degrees of the image provided by the InstanceImageGoalSensor.
- class CompassSensorConfig For Navigation tasks only. The observation of the EpisodicCompassSensor is a single float value corresponding to the angle difference in radians between the current rotation of the robot and the start rotation of the robot along the vertical axis.
- class GPSSensorConfig For Navigation tasks only. The observation of the EpisodicGPSSensor are two float values corresponding to the vector difference in the horizontal plane between the current position and the start position of the robot (in meters).
- class PointGoalWithGPSCompassSensorConfig Indicates the position of the point goal in the frame of reference of the robot.
- class EmptyActionConfig In Navigation tasks only, the pass action. The robot will do nothing.
- class ArmActionConfig In Rearrangement tasks only, the action that will move the robot arm around. The action represents to delta angle (in radians) of each joint.
- class BaseVelocityActionConfig In Rearrangement only. Corresponds to the base velocity. Contains two continuous actions, the first one controls forward and backward motion, the second the rotation.
- class HumanoidJointActionConfig In Rearrangement only. Corresponds to actions to change the humanoid joints. Contains the parameter num_joints, indicating the joints that can be modified.
- class RearrangeStopActionConfig In rearrangement tasks only, if the robot calls this action, the task will end.
- class OracleNavActionConfig Rearrangement Only, Oracle navigation action. This action takes as input a discrete ID which refers to an object in the PDDL domain. The oracle navigation controller then computes the actions to navigate to that desired object.
- class RelativeRestingPositionSensorConfig Rearrangement only. Sensor for the relative position of the end-effector’s resting position, relative to the end-effector’s current position. The three values correspond to the cartesian coordinates of the resting position in the frame of reference of the end effector. The desired resting position is determined by the habitat.task.desired_resting_position coordinates relative to the robot’s base.
- class IsHoldingSensorConfig Rearrangement only. A single float sensor with value 1.0 if the robot is grasping any object and 0.0 otherwise.
- class EEPositionSensorConfig Rearrangement only. the cartesian coordinates (3 floats) of the arm’s end effector in the frame of reference of the robot’s base.
- class JointSensorConfig Rearrangement only. Returns the joint positions of the robot.
- class HumanoidJointSensorConfig Rearrangement only. Returns the joint positions of the robot.
- class TargetStartSensorConfig Rearrangement only. Returns the relative position from end effector to a target object that needs to be picked up.
- class GoalSensorConfig Rearrangement only. Returns the relative position from end effector to a goal position in which the agent needs to place an object.
- class TargetStartGpsCompassSensorConfig Rearrangement only. Returns the initial position of every object that needs to be rearranged in composite tasks, in 2D polar coordinates.
- class TargetGoalGpsCompassSensorConfig Rearrangement only. Returns the desired goal position of every object that needs to be rearranged in composite tasks, in 2D polar coordinates.
- class EndEffectorToRestDistanceMeasurementConfig Rearrangement only. Distance between current end effector position and the resting position of the end effector. Requires that the RelativeRestingPositionSensor is attached to the agent.
- class RobotForceMeasurementConfig The amount of force in newton’s applied by the robot. It computes both the instant and accumulated.
- class DoesWantTerminateMeasurementConfig Rearrangement Only. Measures 1 if the agent has called the stop action and 0 otherwise.
- class ForceTerminateMeasurementConfig If the force is greater than a certain threshold, this measure will be 1.0 and 0.0 otherwise. Note that if the measure is 1.0, the task will end as a result.
- class ObjectToGoalDistanceMeasurementConfig In rearrangement only. The distance between the target object and the goal position for the object.
- class ObjAtGoalMeasurementConfig The measure is a dictionary of target indexes to float. The values are 1 if the object is within succ_thresh of the goal position for that object.
- class ArtObjAtDesiredStateMeasurementConfig Rearrangement open/close container tasks only. Whether the articulated object (fridge or cabinet door) towards a desired state (open or closed) as defined by the task.
- class RotDistToGoalMeasurementConfig Rearrangement Navigation task only. The angle between the forward direction of the agent and the direction to the goal location.
- class PddlStageGoalsMeasurementConfig PDDL Rearrangement only. 1.0 if the agent complete a particular stage defined in stage_goals and 0.0 otherwise. Stage goals are specified in the pddl task description.
- class NavToPosSuccMeasurementConfig Rearrangement Navigation task only. The value is 1.0 if the robot is within success_distance of the goal position.
- class RearrangePickSuccessMeasurementConfig Rearrangement Only. Requires the end_effector_sensor lab sensor. 1.0 if the robot picked the target object.
- class RearrangePickRewardMeasurementConfig Rearrangement Only. Requires the end_effector_sensor lab sensor. The reward for the pick task.
- class PlaceSuccessMeasurementConfig Rearrangement Only. Requires the end_effector_sensor lab sensor. 1.0 if the robot placed the target object on the goal position and has its end effector within ee_resting_success_threshold of its resting position.
- class PlaceRewardMeasurementConfig Rearrangement Only. Requires the end_effector_sensor lab sensor. The reward for the place task.
- class ArtObjSuccessMeasurementConfig Rearrangement open/close container tasks only. Requires art_obj_at_desired_state. Is 1.0 if the articulated object is in desired state and the end effector is within rest_dist_threshold of the resting position. If must_call_stop is True, the robot must also call the rearrange_stop action.
- class ArtObjRewardMeasurementConfig Rearrangement open/close container tasks only. Requires art_obj_at_desired_state.
- class NavToObjSuccessMeasurementConfig Rearrangement Navigation only. Takes the value 1.0 when the Robot successfully navigated to the target object. Depends on nav_to_pos_succ.
- class NavToObjRewardMeasurementConfig Rearrangement Navigation task only. The reward for rearrangement navigation.
- class PddlSuccessMeasurementConfig PDDL rearrangement tasks only (rearrange, set_table, tidy_house). It uses a goal pddl expression to validate the success.
- class RuntimePerfStatsMeasurementConfig If added to the measurements, this will time various sections of code in the simulator and task logic. If using with a multi-environment trainer (like DD-PPO) it is recommended to only log this stat for one environment since this metric can include many numbers.
-
module default_structured_configs
-
module core
- module env
-
module embodied_task Implements task and measurements needed for training and benchmarking of
habitat.Agent
insidehabitat.Env
.- class Action An action that can be performed by an agent solving a task in environment.
For example for navigation task action classes will be:
MoveForwardAction, TurnLeftAction, TurnRightAction
. The action can useTask
members to pass a state to another action, as well as keep own state and reset when new episode starts. - class EmbodiedTask Base class for embodied task.
EmbodiedTask
holds definition of a task that agent needs to solve: action space, observation space, measures, simulator usage.EmbodiedTask
has reset() and step() methods that are called byEnv
.EmbodiedTask
is the one of main dimensions for the framework extension. Once new embodied task is introduced implementation ofEmbodiedTask
is a formal definition of the task that opens opportunity for others to propose solutions and include it into benchmark results. - class Measure Represents a measure that provides measurement on top of environment and task.
- class Measurements Represents a set of Measures, with each Measure being identified through a unique id.
- class Metrics Dictionary containing measurements.
- class SimulatorTaskAction An
EmbodiedTask
action that is wrapping simulator action.
- class Action An action that can be performed by an agent solving a task in environment.
For example for navigation task action classes will be:
-
module dataset Implements dataset functionality to be used
habitat.EmbodiedTask
.habitat.core.dataset
abstracts over a collection ofhabitat.core.Episode
. Each episode consists of a single instantiation of ahabitat.Agent
insidehabitat.Env
.- class BaseEpisode Base class for episode specification that includes only the episode_id and scene id. This class allows passing the minimum required episode information to identify the episode (unique key) to the habitat baseline process, thus saving evaluation time. :property episode_id: id of episode in the dataset, usually episode number. :property scene_id: id of scene in dataset.
- class Dataset Base class for dataset specification.
- class Episode Base class for episode specification that includes initial position and rotation of agent, scene id, episode. :property start_position: list of length 3 for cartesian coordinates (x, y, z) :property start_rotation: list of length 4 for (x, y, z, w) elements of unit quaternion (versor) representing 3D agent orientation (https://en.wikipedia.org/wiki/Versor). The rotation specifying the agent’s orientation is relative to the world coordinate axes.
- class EpisodeIterator Episode Iterator class that gives options for how a list of episodes should be iterated.
-
module simulator
- class ActionSpaceConfiguration
- class AgentState
- class BumpSensor
- class DepthSensor
- class Observations Dictionary containing sensor observations
- class RGBSensor
- class SemanticSensor
- class Sensor Represents a sensor that provides data from the environment to agent.
- class SensorSuite Represents a set of sensors, with each sensor being identified through a unique id.
- class ShortestPathPoint
- class Simulator Basic simulator class for habitat. New simulators to be added to habtiat must derive from this class and implement the abstarct methods.
-
module registry Registry is central source of truth in Habitat.
- class Registry
-
module vector_env
- class ThreadedVectorEnv Provides same functionality as VectorEnv, the only difference is it runs in a multi-thread setup inside a single process.
- class VectorEnv Vectorized environment which creates multiple processes where each process runs its own environment. Main class for parallelization of training and evaluation.
- class _ReadWrapper Convenience wrapper to track if a connection to a worker process should have something to read.
- class _WriteWrapper Convenience wrapper to track if a connection to a worker process can be written to safely. In other words, checks to make sure the result returned from the last write was read.
- module gym
- class Agent Abstract class for defining agents which act inside core.env.Env.
- class Benchmark Benchmark for evaluating agents in environments.
-
module config