habitat.config.default_structured_configs.TaskConfig class

The definition of the task in Habitat.

There are many different Tasks determined by the habitat.task.type config:

  • Point navigation : Nav-0
  • Image navigation : Nav-0
  • Instance image navigation:InstanceImageNav-v1
  • Object navigation : ObjectNav-v1
  • Rearrangement close drawer: RearrangeCloseDrawerTask-v0
  • Rearrangement open drawer: RearrangeOpenDrawerTask-v0
  • Rearrangement close fridge : RearrangeCloseFridgeTask-v0
  • Rearrangement open fridge : RearrangeOpenFridgeTask-v0
  • Rearrangement navigate to object : NavToObjTask-v0
  • Rearrangement pick : RearrangePickTask-v0
  • Rearrangement place : RearrangePlaceTask-v0
  • Rearrangement do nothing : RearrangeEmptyTask-v0
  • Rearrangement reach : RearrangeReachTask-v0
  • Rearrangement composite tasks : RearrangePddlTask-v0

Special methods

def __init__(self, physics_target_sps: float = 60.0, reward_measure: typing.Optional[str] = None, success_measure: typing.Optional[str] = None, success_reward: float = 2.5, slack_reward: float = -0.01, end_on_success: bool = False, type: str = 'Nav-v0', lab_sensors: typing.Dict[str, habitat.config.default_structured_configs.LabSensorConfig] = <factory>, measurements: typing.Dict[str, habitat.config.default_structured_configs.MeasurementConfig] = <factory>, rank0_env0_measure_names: typing.List[str] = <factory>, rank0_measure_names: typing.List[str] = <factory>, goal_sensor_uuid: str = 'pointgoal', count_obj_collisions: bool = True, settle_steps: int = 5, constraint_violation_ends_episode: bool = True, constraint_violation_drops_object: bool = False, force_regenerate: bool = False, should_save_to_cache: bool = False, object_in_hand_sample_prob: float = 0.167, min_start_distance: float = 3.0, render_target: bool = True, filter_colliding_states: bool = True, num_spawn_attempts: int = 200, spawn_max_dist_to_obj: float = 2.0, base_angle_noise: float = 0.523599, spawn_max_dist_to_obj_delta: float = 0.02, recep_place_shrink_factor: float = 0.8, ee_sample_factor: float = 0.2, ee_exclude_region: float = 0.0, base_noise: float = 0.05, spawn_region_scale: float = 0.2, joint_max_impulse: float = -1.0, desired_resting_position: typing.List[float] = <factory>, use_marker_t: bool = True, cache_robot_init: bool = False, success_state: float = 0.0, should_enforce_target_within_reach: bool = False, task_spec_base_path: str = 'habitat/task/rearrange/pddl/', task_spec: str = '', pddl_domain_def: str = 'replica_cad', obj_succ_thresh: float = 0.3, enable_safe_drop: bool = False, art_succ_thresh: float = 0.15, robot_at_thresh: float = 2.0, min_distance_start_agents: float = -1.0, actions: typing.Dict[str, habitat.config.default_structured_configs.ActionConfig] = '???') -> None
def __repr__(self)

Data

actions: typing.Dict[str, habitat.config.default_structured_configs.ActionConfig] = '???'
art_succ_thresh: float = 0.15
base_angle_noise: float = 0.523599
base_noise: float = 0.05
cache_robot_init: bool = False
constraint_violation_drops_object: bool = False
constraint_violation_ends_episode: bool = True
count_obj_collisions: bool = True
ee_exclude_region: float = 0.0
ee_sample_factor: float = 0.2
enable_safe_drop: bool = False
end_on_success: bool = False
filter_colliding_states: bool = True
force_regenerate: bool = False
gfx_replay_dir = 'data/replays'
goal_sensor_uuid: str = 'pointgoal'
joint_max_impulse: float = -1.0
min_distance_start_agents: float = -1.0
min_start_distance: float = 3.0
num_spawn_attempts: int = 200
obj_succ_thresh: float = 0.3
object_in_hand_sample_prob: float = 0.167
pddl_domain_def: str = 'replica_cad'
physics_target_sps: float = 60.0
recep_place_shrink_factor: float = 0.8
render_target: bool = True
reward_measure: typing.Optional[str] = None
robot_at_thresh: float = 2.0
settle_steps: int = 5
should_enforce_target_within_reach: bool = False
should_save_to_cache: bool = False
slack_reward: float = -0.01
spawn_max_dist_to_obj: float = 2.0
spawn_max_dist_to_obj_delta: float = 0.02
spawn_region_scale: float = 0.2
success_measure: typing.Optional[str] = None
success_reward: float = 2.5
success_state: float = 0.0
task_spec: str = ''
task_spec_base_path: str = 'habitat/task/rearrange/pddl/'
type: str = 'Nav-v0'
use_marker_t: bool = True
lab_sensors: typing.Dict[str, habitat.config.default_structured_configs.LabSensorConfig] = None
measurements: typing.Dict[str, habitat.config.default_structured_configs.MeasurementConfig] = None
rank0_env0_measure_names: typing.List[str] = None
rank0_measure_names: typing.List[str] = None
desired_resting_position: typing.List[float] = None