Data Structures

CollisionChecker

CollisionChecker class

class commonroad_reach.data_structure.collision_checker.CollisionChecker(config)[source]

Collision checker using C++ backend.

It handles collision checks in both Cartesian and curvilinear coordinate systems.

Parameters

config (Configuration) –

static create_scenario_with_road_boundaries(config)[source]

Returns a scenario with obstacles in the Cartesian coordinate system.

Elements included: lanelet network, obstacles, road boundaries.

Return type

Scenario

Parameters

config (Configuration) –

static create_cartesian_collision_checker_from_scenario(scenario, params)[source]
Return type

CollisionChecker

Parameters
  • scenario (Scenario) –

  • params (Dict) –

static retrieve_static_obstacles(scenario, lanelet_network, consider_traffic)[source]

Returns the list of static obstacles.

The static obstacles include static road traffic (obtained from scenario object) and road boundaries (obtained from lanelet_network object).

Return type

List[StaticObstacle]

Parameters
  • scenario (Scenario) –

  • lanelet_network (LaneletNetwork) –

  • consider_traffic (bool) –

static obtain_vertices_of_polygons_from_static_obstacles(list_obstacles_static)[source]

Returns the vertices of polygons from a given list of static obstacles.

Parameters

list_obstacles_static (List[StaticObstacle]) –

obtain_vertices_of_polygons_for_dynamic_obstacles(list_obstacles_dynamic, consider_traffic)[source]

Returns the vertices of polygons from a given list of dynamic obstacles.

Parameters
  • list_obstacles_dynamic (List[DynamicObstacle]) –

  • consider_traffic (bool) –

collides_at_step(step, input_rectangle)[source]

Returns true if the input rectangle collides with obstacles in the scenario at the given step.

Creating a query windows significantly decreases computation time.

Return type

bool

Parameters
static convert_reach_polygon_to_collision_object(input_rectangle)[source]

Converts a reach polygon object into a collision object of CommonRoad Drivability Checker.

Return type

RectAABB

Parameters

input_rectangle (ReachPolygon) –

Configuration

Configuration class

class commonroad_reach.data_structure.configuration.Configuration(config_omega)[source]

Class holding all relevant configurations.

Parameters

config_omega (Union[ListConfig, DictConfig]) –

update(scenario=None, planning_problem=None, idx_planning_problem=0, state_initial=None, goal_region=None, CLCS=None, list_ids_lanelets=None)[source]

Updates configuration based on the given attributes.

Possible ways of completing the configuration:

  1. Empty attributes: loads scenario and planning problem from the xml files, computes route and CLCS

  2. Scenario + planning problem (+ initial state): computes route and CLCS

  3. Scenario + initial state + goal region: computes route and CLCS

  4. Scenario + initial state + CLCS: retrieve reference path from CLCS

Additionally, a list of lanelet IDs (e.g., from a given route) can be passed to restrict the reachable set computation a-priori to a desired set of lanelets.

Parameters
  • scenario (Optional[Scenario]) –

  • planning_problem (Optional[PlanningProblem]) –

  • idx_planning_problem (int) –

  • state_initial (Optional[State]) –

  • goal_region (Optional[GoalRegion]) –

  • CLCS (Optional[CurvilinearCoordinateSystem]) –

  • list_ids_lanelets (Optional[List[int]]) –

print_configuration_summary()[source]

Prints a summary of the configuration.

save(path_save, name_file)[source]

Saves configuration to a yaml file.

Parameters
  • path_save (str) –

  • name_file (str) –

convert_to_cpp_configuration()[source]

Converts to a configuration that is readable by the C++ binding code.

Return type

Configuration

ConfigurationBuilder

ConfigurationBuilder class

class commonroad_reach.data_structure.configuration_builder.ConfigurationBuilder[source]

Class to build a configuration.

path_root: str = None
path_config: str = None
path_config_default: str = None
classmethod build_configuration(name_scenario, path_root=None, dir_config='configurations', dir_config_default='defaults')[source]

Builds configuration from default, scenario-specific, and commandline config files.

Parameters
  • name_scenario (str) – name of the considered scenario

  • path_root (Optional[str]) – root path of the package

  • dir_config (str) – directory storing configurations

  • dir_config_default (str) – directory storing default configurations

Return type

Configuration

Returns

built configuration

classmethod set_paths(path_root, dir_config, dir_config_default)[source]

Sets necessary paths of the configuration builder.

Parameters
  • path_root (str) – root directory

  • dir_config (str) – directory storing configurations

  • dir_config_default (str) – directory storing default configurations

classmethod construct_default_configuration()[source]

Constructs default configuration by accumulating yaml files.

Collects all configuration files ending with ‘.yaml’ in the directory storing default configurations.

Return type

Union[ListConfig, DictConfig]

classmethod convert_to_absolute_paths(config_default)[source]

Converts relative paths to absolute paths.

Return type

Union[ListConfig, DictConfig]

Parameters

config_default (Union[ListConfig, DictConfig]) –

classmethod construct_scenario_configuration(name_scenario)[source]

Constructs scenario-specific configuration.

Return type

Union[DictConfig, ListConfig]

Parameters

name_scenario (str) –

RegularGrid

RegularGrid RegularGrid

class commonroad_reach.data_structure.regular_grid.RegularGrid(ll, ur, collision_checker, dx, dy, planning_config, a_lon, a_lat, t_f, grid_shapes)[source]

Class for computing uniformly spatial partitioned grid of obstacles.

Parameters
  • ll (Dict[int, ndarray]) –

  • ur (Dict[int, ndarray]) –

  • collision_checker (CollisionChecker) –

  • dx (float) –

  • dy (float) –

  • planning_config (PlanningConfiguration) –

  • a_lon (float) –

  • a_lat (float) –

  • t_f (float) –

  • grid_shapes (Dict[int, Tuple[int, int]]) –

occupancy_grid_at_step(step, translate_reachset)[source]

Get occupancy matrix defined over regular grid with 0 = occupied, 1 = free space.

Parameters
  • step (int) – step of evaluation

  • translate_reachset (ndarray) – translation of reachable set

Return type

ndarray

Grid class

class commonroad_reach.data_structure.regular_grid.Grid(x_min, x_max, y_min, y_max, size_grid)[source]

Cartesian grid for discretizing reachable sets in the graph-based propagation method.

Parameters
  • x_min (float) –

  • x_max (float) –

  • y_min (float) –

  • y_max (float) –

  • size_grid (float) –

Cell class

class commonroad_reach.data_structure.regular_grid.Cell(x_min, x_max, y_min, y_max)[source]

Class representing a cell in a grid.

Parameters
  • x_min (float) –

  • x_max (float) –

  • y_min (float) –

  • y_max (float) –

cnt_id: int = 0

SegmentTree

CounterSegmentTree class

class commonroad_reach.data_structure.segment_tree.CounterSegmentTree(low, high)[source]

Segment tree to hold nodes (segments) of intervals.

Each leaf in this tree has a counter of times it has been activated.

Parameters
  • low (int) –

  • high (int) –

activate(low, high)[source]

Activates the root node for the input interval [low, high].

Parameters
  • low (int) –

  • high (int) –

deactivate(low, high)[source]

Deactivates the root node for the input interval [low, high].

Parameters
  • low (int) –

  • high (int) –

get_active_nodes()[source]

Returns the list of nodes whose status is ACTIVE.

get_stack_of_active_intervals()[source]

Returns the stack of currently active intervals.

Note

Stack is in the form of [low1, high1, low2, high2, ..]. When pushing into the stack, intervals are merged where applicable (e.g. low2 == high1).

Example:

  • [5, 10] => push TreeNode(low = 10, high = 15) => [5 ,15]

print_active_nodes()[source]
get_non_active_intervals(low, high)[source]

Returns the non-active intervals starting from the root node.

Parameters
  • low (int) –

  • high (int) –

static add_node_interval_to_stack(low, high, stack)[source]

Updates the stack containing the complement intervals.

Note

The intervals are merged.

Example:

  1. stack = []

  2. called with (5, 10) -> stack = [5, 10]

  3. called with (10, 15) -> stack = [5, 15]

  4. called with (18, 20) -> stack = [5, 15, 18, 20]

Parameters
  • low (int) –

  • high (int) –

  • stack (List) –

CounterTreeNode class

class commonroad_reach.data_structure.segment_tree.CounterTreeNode(low, high)[source]

Each node represents a segment on the axis.

Each segment is defined with an interval [low, high]. The counter represents the number of times it has been activated. Its potential left and right children have intervals [low, mid] and [mid, high], respectively.

Parameters
  • low (int) –

  • high (int) –

create_left_child()[source]
create_right_child()[source]
activate()[source]
deactivate()[source]
update_status()[source]
all_children_active()[source]
Return type

bool

all_children_non_active()[source]
Return type

bool

enclosed_by_interval(low, high)[source]

Returns whether the node is fully enclosed by the interval [low, high].

Return type

bool

Parameters
  • low (int) –

  • high (int) –

ToggleSegmentTree class

class commonroad_reach.data_structure.segment_tree.ToggleSegmentTree(low, high)[source]

Segment tree to hold nodes (segments) of intervals.

The states of leaves in this tree can be toggled.

Parameters
  • low (int) –

  • high (int) –

toggle(low, high)[source]

toggles the root node.

Parameters
  • low (int) –

  • high (int) –

get_active_nodes()[source]

Returns the list of nodes whose status is ACTIVE.

get_stack_of_active_intervals()[source]

Returns the stack of currently active intervals.

Note

Stack is in the form of [low1, high1, low2, high2, ..]. When pushing into the stack, intervals are merged where applicable (e.g. low2 == high1).

Example:

  • [5, 10] => push TreeNode(low = 10, high = 15) => [5 ,15]

print_active_nodes()[source]

ToggleTreeNode class

class commonroad_reach.data_structure.segment_tree.ToggleTreeNode(low, high, status=TreeNodeStatus.NONACTIVE)[source]

Each node represents a segment on the axis.

Each segment is defined with an interval [low, high]. The node only has a state, which is not based on counters. Its potential left and right children have intervals [low, mid] and [mid, high], respectively.

Parameters
  • low (int) –

  • high (int) –

create_left_child(status)[source]
create_right_child(status)[source]
toggle()[source]

Toggles the state of the node.

update_status()[source]
all_children_non_active()[source]
Return type

bool

all_children_active()[source]
Return type

bool

enclosed_by_interval(low, high)[source]

Returns whether the node is fully enclosed by the interval [low, high].

Return type

bool

Parameters
  • low (int) –

  • high (int) –

TreeNodeStatus class

class commonroad_reach.data_structure.segment_tree.TreeNodeStatus(value)[source]

Possible states of nodes representing segments.

  • ACTIVE: segment fully activated (entire [low, high])

  • PARTIAL: segment partially activated (subset of [low, high])

  • NONACTIVE: segment not activated (none within [low, high])

ACTIVE = 1
PARTIAL = 2
NONACTIVE = 3