Skip to content

point_navigation_obstacle_task

PointNavigationDynamicObstacleTask

Bases: PointNavigationObstacleTask

Dynamic Navigation Random Task The goal is to navigate to a random goal position, in the presence of dynamic objects (moving turtlebots)

Parameters:

Name Type Description Default
robot_idn int

Which robot that this task corresponds to

0
floor int

Which floor to navigate on

0
initial_pos None or 3-array

If specified, should be (x,y,z) global initial position to place the robot at the start of each task episode. If None, a collision-free value will be randomly sampled

None
initial_quat None or 4-array

If specified, should be (x,y,z,w) global quaternion orientation to place the robot at the start of each task episode. If None, a value will be randomly sampled about the z-axis

None
goal_pos None or 3-array

If specified, should be (x,y,z) global goal position to reach for the given task episode. If None, a collision-free value will be randomly sampled

None
goal_tolerance float

Distance between goal position and current position below which is considered a task success

0.1
goal_in_polar bool

Whether to represent the goal in polar coordinates or not when capturing task observations

False
path_range None or 2-array

If specified, should be (min, max) values representing the range of valid total path lengths that are valid when sampling initial / goal positions

None
visualize_goal bool

Whether to visualize the initial / goal locations

False
visualize_path bool

Whether to visualize the path from initial to goal location, as represented by discrete waypoints

False
marker_height float

If visualizing, specifies the height of the visual markers (m)

0.2
waypoint_width float

If visualizing, specifies the width of the visual waypoints (m)

0.1
n_vis_waypoints int

If visualizing, specifies the number of waypoints to generate

250
reward_type str

Type of reward to use. Valid options are: {"l2", "geodesic"}

'l2'
n_obstacles int

Number of dynamic obstacles to generate

1
n_obstacle_action_repeat int

How many timesteps a dynamic obstacle should repeat its action before switching

10
termination_config None or dict

Keyword-mapped configuration to use to generate termination conditions. This should be specific to the task class. Default is None, which corresponds to a default config being usd. Note that any keyword required by a specific task class but not specified in the config will automatically be filled in with the default config. See cls.default_termination_config for default values used

None
reward_config None or dict

Keyword-mapped configuration to use to generate reward functions. This should be specific to the task class. Default is None, which corresponds to a default config being usd. Note that any keyword required by a specific task class but not specified in the config will automatically be filled in with the default config. See cls.default_reward_config for default values used

None
Source code in tasks/point_navigation_obstacle_task.py
class PointNavigationDynamicObstacleTask(PointNavigationObstacleTask):
    """
    Dynamic Navigation Random Task
    The goal is to navigate to a random goal position, in the presence of dynamic objects (moving turtlebots)

    Args:
        robot_idn (int): Which robot that this task corresponds to
        floor (int): Which floor to navigate on
        initial_pos (None or 3-array): If specified, should be (x,y,z) global initial position to place the robot
            at the start of each task episode. If None, a collision-free value will be randomly sampled
        initial_quat (None or 4-array): If specified, should be (x,y,z,w) global quaternion orientation to place the
            robot at the start of each task episode. If None, a value will be randomly sampled about the z-axis
        goal_pos (None or 3-array): If specified, should be (x,y,z) global goal position to reach for the given task
            episode. If None, a collision-free value will be randomly sampled
        goal_tolerance (float): Distance between goal position and current position below which is considered a task
            success
        goal_in_polar (bool): Whether to represent the goal in polar coordinates or not when capturing task observations
        path_range (None or 2-array): If specified, should be (min, max) values representing the range of valid
            total path lengths that are valid when sampling initial / goal positions
        visualize_goal (bool): Whether to visualize the initial / goal locations
        visualize_path (bool): Whether to visualize the path from initial to goal location, as represented by
            discrete waypoints
        marker_height (float): If visualizing, specifies the height of the visual markers (m)
        waypoint_width (float): If visualizing, specifies the width of the visual waypoints (m)
        n_vis_waypoints (int): If visualizing, specifies the number of waypoints to generate
        reward_type (str): Type of reward to use. Valid options are: {"l2", "geodesic"}
        n_obstacles (int): Number of dynamic obstacles to generate
        n_obstacle_action_repeat (int): How many timesteps a dynamic obstacle should repeat its action before switching
        termination_config (None or dict): Keyword-mapped configuration to use to generate termination conditions. This
            should be specific to the task class. Default is None, which corresponds to a default config being usd.
            Note that any keyword required by a specific task class but not specified in the config will automatically
            be filled in with the default config. See cls.default_termination_config for default values used
        reward_config (None or dict): Keyword-mapped configuration to use to generate reward functions. This should be
            specific to the task class. Default is None, which corresponds to a default config being usd. Note that
            any keyword required by a specific task class but not specified in the config will automatically be filled
            in with the default config. See cls.default_reward_config for default values used
    """

    def __init__(
            self,
            robot_idn=0,
            floor=0,
            initial_pos=None,
            initial_quat=None,
            goal_pos=None,
            goal_tolerance=0.1,
            goal_in_polar=False,
            path_range=None,
            visualize_goal=False,
            visualize_path=False,
            marker_height=0.2,
            waypoint_width=0.1,
            n_vis_waypoints=250,
            reward_type="l2",
            n_obstacles=1,
            n_obstacle_action_repeat=10,
            reward_config=None,
            termination_config=None,
    ):
        # Store inputs
        self._n_obstacle_action_repeat = n_obstacle_action_repeat

        # Initialize variables that will be filled in at runtime
        self._current_obstacle_actions = None

        # Run super init
        super().__init__(
            robot_idn=robot_idn,
            floor=floor,
            initial_pos=initial_pos,
            initial_quat=initial_quat,
            goal_pos=goal_pos,
            goal_tolerance=goal_tolerance,
            goal_in_polar=goal_in_polar,
            path_range=path_range,
            visualize_goal=visualize_goal,
            visualize_path=visualize_path,
            marker_height=marker_height,
            waypoint_width=waypoint_width,
            n_vis_waypoints=n_vis_waypoints,
            reward_type=reward_type,
            n_obstacles=n_obstacles,
            reward_config=reward_config,
            termination_config=termination_config,
        )

    def _load_obstacles(self, env):
        # Load turtlebots
        obstacles = []
        for i in range(self._n_obstacles):
            obstacle = Turtlebot(
                prim_path=f"/World/task_obstacle{i}",
                name=f"task_obscale{i}",
            )
            og.sim.import_object(obstacle)
            obstacles.append(obstacle)

        return obstacles

    def step(self, env, action):
        # Run super method first
        reward, done, info = super().step(env=env, action=action)
        # Apply actions for each dynamic obstacle
        if env.episode_steps % self._n_obstacle_action_repeat == 0:
            self._current_obstacle_actions = [robot.action_space.sample() for robot in self._obstacles]
        for robot, action in zip(self._obstacles, self._current_obstacle_actions):
            robot.apply_action(action)

        return reward, done, info

PointNavigationObstacleTask

Bases: PointNavigationTask

Interactive Navigation Random Task The goal is to navigate to a random goal position, in the presence of interactive objects. This is an abstract class

Parameters:

Name Type Description Default
robot_idn int

Which robot that this task corresponds to

0
floor int

Which floor to navigate on

0
initial_pos None or 3-array

If specified, should be (x,y,z) global initial position to place the robot at the start of each task episode. If None, a collision-free value will be randomly sampled

None
initial_quat None or 4-array

If specified, should be (x,y,z,w) global quaternion orientation to place the robot at the start of each task episode. If None, a value will be randomly sampled about the z-axis

None
goal_pos None or 3-array

If specified, should be (x,y,z) global goal position to reach for the given task episode. If None, a collision-free value will be randomly sampled

None
goal_tolerance float

Distance between goal position and current position below which is considered a task success

0.1
goal_in_polar bool

Whether to represent the goal in polar coordinates or not when capturing task observations

False
path_range None or 2-array

If specified, should be (min, max) values representing the range of valid total path lengths that are valid when sampling initial / goal positions

None
visualize_goal bool

Whether to visualize the initial / goal locations

False
visualize_path bool

Whether to visualize the path from initial to goal location, as represented by discrete waypoints

False
marker_height float

If visualizing, specifies the height of the visual markers (m)

0.2
waypoint_width float

If visualizing, specifies the width of the visual waypoints (m)

0.1
n_vis_waypoints int

If visualizing, specifies the number of waypoints to generate

250
reward_type str

Type of reward to use. Valid options are: {"l2", "geodesic"}

'l2'
n_obstacles int

Number of obstacles to generate

5
termination_config None or dict

Keyword-mapped configuration to use to generate termination conditions. This should be specific to the task class. Default is None, which corresponds to a default config being usd. Note that any keyword required by a specific task class but not specified in the config will automatically be filled in with the default config. See cls.default_termination_config for default values used

None
reward_config None or dict

Keyword-mapped configuration to use to generate reward functions. This should be specific to the task class. Default is None, which corresponds to a default config being usd. Note that any keyword required by a specific task class but not specified in the config will automatically be filled in with the default config. See cls.default_reward_config for default values used

None
Source code in tasks/point_navigation_obstacle_task.py
class PointNavigationObstacleTask(PointNavigationTask):
    """
    Interactive Navigation Random Task
    The goal is to navigate to a random goal position, in the presence of interactive objects. This is an abstract class

    Args:
        robot_idn (int): Which robot that this task corresponds to
        floor (int): Which floor to navigate on
        initial_pos (None or 3-array): If specified, should be (x,y,z) global initial position to place the robot
            at the start of each task episode. If None, a collision-free value will be randomly sampled
        initial_quat (None or 4-array): If specified, should be (x,y,z,w) global quaternion orientation to place the
            robot at the start of each task episode. If None, a value will be randomly sampled about the z-axis
        goal_pos (None or 3-array): If specified, should be (x,y,z) global goal position to reach for the given task
            episode. If None, a collision-free value will be randomly sampled
        goal_tolerance (float): Distance between goal position and current position below which is considered a task
            success
        goal_in_polar (bool): Whether to represent the goal in polar coordinates or not when capturing task observations
        path_range (None or 2-array): If specified, should be (min, max) values representing the range of valid
            total path lengths that are valid when sampling initial / goal positions
        visualize_goal (bool): Whether to visualize the initial / goal locations
        visualize_path (bool): Whether to visualize the path from initial to goal location, as represented by
            discrete waypoints
        marker_height (float): If visualizing, specifies the height of the visual markers (m)
        waypoint_width (float): If visualizing, specifies the width of the visual waypoints (m)
        n_vis_waypoints (int): If visualizing, specifies the number of waypoints to generate
        reward_type (str): Type of reward to use. Valid options are: {"l2", "geodesic"}
        n_obstacles (int): Number of obstacles to generate
        termination_config (None or dict): Keyword-mapped configuration to use to generate termination conditions. This
            should be specific to the task class. Default is None, which corresponds to a default config being usd.
            Note that any keyword required by a specific task class but not specified in the config will automatically
            be filled in with the default config. See cls.default_termination_config for default values used
        reward_config (None or dict): Keyword-mapped configuration to use to generate reward functions. This should be
            specific to the task class. Default is None, which corresponds to a default config being usd. Note that
            any keyword required by a specific task class but not specified in the config will automatically be filled
            in with the default config. See cls.default_reward_config for default values used
    """
    def __init__(
            self,
            robot_idn=0,
            floor=0,
            initial_pos=None,
            initial_quat=None,
            goal_pos=None,
            goal_tolerance=0.1,
            goal_in_polar=False,
            path_range=None,
            visualize_goal=False,
            visualize_path=False,
            marker_height=0.2,
            waypoint_width=0.1,
            n_vis_waypoints=250,
            reward_type="l2",
            n_obstacles=5,
            reward_config=None,
            termination_config=None,
    ):
        # Store inputs
        self._n_obstacles = n_obstacles

        # Initialize other variables that will be filled in at runtime
        self._obstacles = None

        # Run super init
        super().__init__(
            robot_idn=robot_idn,
            floor=floor,
            initial_pos=initial_pos,
            initial_quat=initial_quat,
            goal_pos=goal_pos,
            goal_tolerance=goal_tolerance,
            goal_in_polar=goal_in_polar,
            path_range=path_range,
            visualize_goal=visualize_goal,
            visualize_path=visualize_path,
            marker_height=marker_height,
            waypoint_width=waypoint_width,
            n_vis_waypoints=n_vis_waypoints,
            reward_type=reward_type,
            reward_config=reward_config,
            termination_config=termination_config,
        )

    def _load(self, env):
        # Load the interactive objects
        self._obstacles = self._load_obstacles(env=env)

    def _load_obstacles(self, env):
        """
        Load obstacles. Must be implemented by subclass.

        Args:
            env (OmniGibsonEnv): Environment instance

        Returns:
            list of BaseObject: Obstacle(s) generated for this task
        """
        raise NotImplementedError()

    def _reset_obstacles(self, env):
        """
        Reset the poses of obstacles to have no collisions with the scene or the robot

        Args:
            env (OmniGibsonEnv): Environment instance
        """
        success, max_trials, pos, ori = False, 100, None, None

        for obj in self._obstacles:
            # Save the state of this environment so we can restore it immediately after
            state = og.sim.dump_state(serialized=True)
            for _ in range(max_trials):
                _, pos = env.scene.get_random_point(floor=self._floor)
                quat = T.euler2quat(np.array([0, 0, np.random.uniform(0, np.pi * 2)]))
                success = test_valid_pose(obj, pos, quat, env.initial_pos_z_offset)
                og.sim.load_state(state=state, serialized=True)
                if success:
                    break

            if not success:
                logging.warning("WARNING: Failed to reset interactive obj without collision")

            land_object(obj, pos, ori, env.initial_pos_z_offset)

    def _reset_scene(self, env):
        # Run super first
        super()._reset_scene(env=env)

        # Reset the obstacles
        self._reset_obstacles(env=env)

    @classproperty
    def _do_not_register_classes(cls):
        # Don't register this class since it's an abstract template
        classes = super()._do_not_register_classes
        classes.add("PointNavigationObstacleTask")
        return classes