Utility Functions

Configuration

commonroad_reach.utility.configuration.compute_disc_radius_and_distance(length, width, ref_point='CENTER', dist_axle_rear=None)[source]

Computes the radius of discs and their distances used as the approximation of the shape of the ego vehicle.

Note

Vehicle occupancy is approximated by three equally sized discs with equidistant center points. (see Ziegler, J. and Stiller, C. (2010) “Fast collision checking for intelligent vehicle motion planning”, IEEE IV

Parameters
  • length (float) – vehicle length

  • width (float) – vehicle width

  • ref_point – “CENTER” or “REAR”

  • dist_axle_rear – if ref_point == “REAR”, the distance between vehicle center and rear axle has to be provided

Returns

radius_disc: radius of discs

Return type

Tuple[float, float]

Returns

dist_circles: distance between the first and the third circle

commonroad_reach.utility.configuration.compute_disc_radius_and_wheelbase(length, width, wheelbase=None)[source]

Computes the radius of the discs to approximate the shape of vehicle.

If wheelbase is not given, it is assumed that the front and rear axles are positioned at length * 1/6 and length * 5/6 of the shape, thus yielding a wheelbase of length * 4/6.

Parameters
  • length (float) – vehicle length

  • width (float) – vehicle width

  • wheelbase (Optional[float]) – wheelbase of the vehicle. If given, it is used to compute the radius of discs.

Returns

radius_disc: radius of discs

Return type

Tuple[float, float]

Returns

wheelbase: wheelbase computed from vehicle dimensions

commonroad_reach.utility.configuration.compute_inflation_radius(mode_inflation, length, width, radius_disc)[source]

Computes the radius to inflate the obstacles for collision check of the ego vehicle.

Based on the specified mode, we obtain either under or over-approximation of the shape of the ego vehicle.

Return type

float

Returns

radius_inflation: radius of inflation

Parameters
  • mode_inflation (int) –

  • length (float) –

  • width (float) –

  • radius_disc (float) –

commonroad_reach.utility.configuration.create_curvilinear_coordinate_system(reference_path, limit_projection_domain=30.0, eps=0.1, eps2=0.0001)[source]

Creates a curvilinear coordinate system from the given reference path.

Return type

CurvilinearCoordinateSystem

Parameters
  • reference_path (ndarray) –

  • limit_projection_domain (float) –

  • eps (float) –

  • eps2 (float) –

commonroad_reach.utility.configuration.compute_initial_state_cart(config)[source]

Computes the initial state of the ego vehicle given a planning problem in the Cartesian coordinate system.

Return type

Tuple

commonroad_reach.utility.configuration.compute_initial_state_cvln(config, state_initial=None)[source]

Computes the initial state of the ego vehicle given a planning problem or a state in a curvilinear coordinate system.

Note

For the transformation of the ego vehicle’s velocity to the curvilinear coordinate system, it is assumed that d * kappa_ref << 1 holds, where d is the distance of the ego vehicle to the reference path and kappa_ref is the curvature of the reference path

Parameters
  • config – configuration file

  • state_initial (Optional[State]) – initial state to overwrite the one from the planning problem

Return type

Tuple

commonroad_reach.utility.configuration.read_lut_longitudinal_enlargement(reference_point, dist_circles, path_to_lut)[source]

Reads look-up table for longitudinal enlargement for collision checking in reachability analysis.

:param reference_point :param dist_circles Distance between front and rear circle (see fun compute_disc_radius_and_distance() ) :type path_to_lut: str :param path_to_lut: path where look-up table is stored :rtype: Dict :return: look-up table as dictionary

Parameters
  • reference_point (str) –

  • dist_circles (float) –

  • path_to_lut (str) –

Return type

Dict

Coordinate System

commonroad_reach.utility.coordinate_system.create_curvilinear_aabb_from_obstacle(obstacle, CLCS, radius_disc, step=None, resolution=5)[source]

Returns a list of axis-aligned bounding boxes in a curvilinear coordinate system from an obstacle.

The shapes are dilated with the disc radius of the ego vehicle to consider its shape.

Return type

List[RectAABB]

Parameters
  • CLCS (CurvilinearCoordinateSystem) –

  • radius_disc (float) –

  • step (Optional[int]) –

  • resolution (int) –

commonroad_reach.utility.coordinate_system.create_curvilinear_and_rasterized_aabb_from_shape(shape, CLCS)[source]

Returns a list of axis-aligned and rasterized boxes in Curvilinear coordinate system from a CommonRoad shape.

Note

Since we use axis-aligned rectangles (bounding boxes) for collision checks in Curvilinear coordinate system, simply using the rectangle with min/max lon/lat vertices converted from the Cartesian coordinates incurs a large over-approximation of the shape of the obstacle. We therefore rasterize (partition) the converted rectangle in the longitudinal direction and adjust their lateral coordinates to reduce the over-approximation.

Return type

List[RectAABB]

Parameters
  • shape (Shape) –

  • CLCS (CurvilinearCoordinateSystem) –

commonroad_reach.utility.coordinate_system.convert_to_curvilinear_vertices(vertices_cart, CLCS)[source]

Converts a list of Cartesian vertices to Curvilinear vertices.

Parameters
  • vertices_cart (ndarray) –

  • CLCS (CurvilinearCoordinateSystem) –

commonroad_reach.utility.coordinate_system.convert_to_cartesian_polygons(rectangle_cvln, CLCS, split_wrt_angle)[source]

Returns a list of rectangles converted to Cartesian coordinate system.

If split_wrt_angle set to True, the converted rectangles will be further split into smaller ones if their upper and lower edges has a difference in angle greater than a threshold. This is to smoothen the plotting.

Return type

List[ReachPolygon]

Parameters
  • CLCS (CurvilinearCoordinateSystem) –

  • split_wrt_angle (bool) –

commonroad_reach.utility.coordinate_system.convert_to_cartesian_polygon(tuple_vertices, CLCS, split_wrt_angle)[source]

Converts a curvilinear polygon into list of cartesian polygons.

If split_wrt_angle is set to True, the converted rectangle will be recursively split if its upper and lower edges have a difference in angle greater than the threshold.

Return type

List[ReachPolygon]

Parameters

CLCS (CurvilinearCoordinateSystem) –

General

commonroad_reach.utility.general.load_scenario_and_planning_problem(config, idx_planning_problem=0)[source]

Loads a scenario and planning problem from the configuration.

Parameters
  • config – configuration

  • idx_planning_problem (int) – index of the planning problem

Return type

Tuple[Scenario, PlanningProblem]

Returns

scenario and planning problem

commonroad_reach.utility.general.power_set(iterable)[source]

Returns the power set of a given iterable.

Return type

Set[Tuple]

commonroad_reach.utility.general.create_lanelet_network_from_ids(lanelet_network, list_ids_lanelets)[source]

Creates a new lanelet network from a list of lanelet IDs in the original lanelet network.

Parameters
  • lanelet_network (LaneletNetwork) – reference lanelet network

  • list_ids_lanelets – list of ids of lanelets from which the new lanelet network should be constructed

Return type

LaneletNetwork

Returns

new lanelet network

Geometry

commonroad_reach.utility.geometry.linear_mapping(polygon, tuple_coefficients)[source]

Returns the linear mapping of the input polygon.

Return type

ReachPolygon

Parameters
  • polygon (ReachPolygon) –

  • tuple_coefficients (Tuple[float, float, float, float]) –

commonroad_reach.utility.geometry.minkowski_sum(polygon1, polygon2)[source]

Returns the Minkowski sum of the two input polygons.

Return type

Optional[ReachPolygon]

Parameters
commonroad_reach.utility.geometry.sort_vertices_counterclockwise(list_vertices)[source]

Sorts a list of vertices in the counterclockwise direction.

Steps:
  1. compute the center of mass

  2. compute the angle from the center of mass to each point

  3. sort with the computed angles

Return type

List[Tuple[float, float]]

Parameters

list_vertices (List[Tuple]) –

commonroad_reach.utility.geometry.create_adjacency_dictionary(list_rectangles_1, list_rectangles_2)[source]

Returns an adjacency dictionary from the two given list of rectangles.

Note

Example: {0 : [1, 2], 1 : [3, 4]} = rectangle_0 from 1st list overlaps with rectangles_1 and _2 from the 2nd list; rectangle_1 from the 1st list overlaps with rectangles_3 and _4 from the 2nd list.

Return type

Dict[int, List[int]]

Parameters
commonroad_reach.utility.geometry.obtain_extremum_coordinates_of_vertices(list_vertices)[source]

Returns the extremum coordinates of the given list of vertices.

Return type

Tuple[float, float, float, float]

Parameters

list_vertices (List[Tuple]) –

commonroad_reach.utility.geometry.create_aabb_from_coordinates(p_lon_min, p_lat_min, p_lon_max, p_lat_max)[source]

Returns a pycrcc.RectAABB object from the given coordinates.

Parameters
  • p_lon_min (float) –

  • p_lat_min (float) –

  • p_lon_max (float) –

  • p_lat_max (float) –

commonroad_reach.utility.geometry.rectangle_intersects_with_circle(rectangle, center, radius)[source]

Returns true if the given rectangles intersects with a circle.

Parameters
  • rectangle (ReachPolygon) – rectangle to be checked

  • center (Tuple[float, float]) – center of the circle to be checked

  • radius (float) – radius of the circle to be checked

Return type

bool

commonroad_reach.utility.geometry.clamp(value, min_value, max_value)[source]

Clamps a value between the min and max values.

Parameters
  • value (float) –

  • min_value (float) –

  • max_value (float) –

Logger

commonroad_reach.utility.logger.initialize_logger(config)[source]

Initializes the logging module and returns a logger.

Return type

Logger

commonroad_reach.utility.logger.print_and_log_debug(logger, message, verbose=False)[source]
Parameters
  • logger (Logger) –

  • message (str) –

  • verbose (bool) –

commonroad_reach.utility.logger.print_and_log_info(logger, message, verbose=True)[source]
Parameters
  • logger (Logger) –

  • message (str) –

  • verbose (bool) –

commonroad_reach.utility.logger.print_and_log_warning(logger, message, verbose=True)[source]
Parameters
  • logger (Logger) –

  • message (str) –

  • verbose (bool) –

commonroad_reach.utility.logger.print_and_log_error(logger, message, verbose=True)[source]
Parameters
  • logger (Logger) –

  • message (str) –

  • verbose (bool) –

Reach Operation

commonroad_reach.utility.reach_operation.create_zero_state_polygon(dt, a_min, a_max)[source]

Returns the zero-state polygon of the system.

Steps:
  1. prepare a bounding polygon to be intersected with halfspaces.

  2. compute coefficients of halfspaces and intersect them with the bounding polygon. We use three halfspaces to approximate the upper bound of the polygon, this applies to the lower bound as well A halfspace can be specified given a switching time (gamma).

Parameters
  • dt (float) – time duration (one step)

  • a_min (float) – minimum acceleration (maximum deceleration)

  • a_max (float) – maximum acceleration

Return type

ReachPolygon

commonroad_reach.utility.reach_operation.create_bounding_polygon(dt, a_min, a_max)[source]

Returns a polygon that has the min/max reachable position and velocity as its bounds.

Parameters
  • dt (float) – time duration (one step)

  • a_min (float) – minimum acceleration (maximum deceleration)

  • a_max (float) – maximum acceleration

Return type

ReachPolygon

commonroad_reach.utility.reach_operation.compute_halfspace_coefficients(dt, a_min, a_max, gamma)[source]

Computes the coefficients of halfspaces to be intersected.

Parameters
  • dt (float) – time duration (one step)

  • a_min (float) – minimum acceleration (maximum deceleration)

  • a_max (float) – maximum acceleration

  • gamma (float) – switching time between full braking and acceleration

Return type

Tuple

commonroad_reach.utility.reach_operation.generate_tuple_vertices_position_rectangle_initial(config)[source]

Returns a tuple of vertices for the position rectangle construction.

Return type

Tuple

Parameters

config (Configuration) –

commonroad_reach.utility.reach_operation.generate_tuples_vertices_polygons_initial(config)[source]

Returns tuples of vertices for the initial polygons in two directions.

Return type

Tuple

Parameters

config (Configuration) –

commonroad_reach.utility.reach_operation.propagate_polygon(polygon, polygon_zero_state, dt, v_min, v_max)[source]

Propagates the (lon/lat) polygon of a reach node.

Steps:
  1. convexify the polygon

  2. compute the linear mapping (zero-input response) of the polygon

  3. compute the minkowski sum of the zero-input and zero-state polygons

  4. intersect with halfspaces to consider velocity limits

Return type

ReachPolygon

Parameters
commonroad_reach.utility.reach_operation.project_base_sets_to_position_domain(list_base_sets_propagated)[source]

Returns a list of rectangles projected onto the position domain.

Return type

List[ReachPolygon]

Parameters

list_base_sets_propagated (List[ReachNode]) –

commonroad_reach.utility.reach_operation.create_repartitioned_rectangles(list_rectangles, size_grid)[source]

Returns a list of repartitioned rectangles.

Steps:
  1. obtain the minimum lon/lat positions of the list of rectangles.

  2. discretize rectangles

  3. repartition the rectangles into a new list of rectangles.

  4. restore the rectangles back to undiscretized ones.

Return type

List[ReachPolygon]

Parameters
  • list_rectangles (List[ReachPolygon]) –

  • size_grid (float) –

commonroad_reach.utility.reach_operation.compute_minimum_positions_of_rectangles(list_rectangles)[source]

Returns minimum lon/lat positions of the given list of rectangles.

Return type

Tuple[float, float]

Parameters

list_rectangles (List[ReachPolygon]) –

commonroad_reach.utility.reach_operation.compute_extremum_positions_of_rectangles(list_rectangles)[source]

Returns extremum lon/lat positions of the given list of rectangles.

Return type

Tuple[float, float, float, float]

Parameters

list_rectangles (List[ReachPolygon]) –

commonroad_reach.utility.reach_operation.discretize_rectangles(list_rectangles, tuple_p_min_rectangles, size_grid)[source]

Discretizes the given list of rectangles.

p_discretized = (p_undiscretized - p_min) / size_grid For over-approximation, take floor for minimum values, and take ceil for maximum values.

Return type

List[ReachPolygon]

Parameters
  • list_rectangles (List[ReachPolygon]) –

  • tuple_p_min_rectangles (Tuple[float, float]) –

  • size_grid (float) –

commonroad_reach.utility.reach_operation.repartition_rectangles(list_rectangles)[source]

Returns a list of repartitioned rectangles.

Steps:
  1. Obtain a list of vertical segments representing the contour of the union of the input rectangles.

  2. Create repartitioned rectangles from the list of vertical segments using the sweep line algorithm.

Return type

List[ReachPolygon]

Parameters

list_rectangles (List[ReachPolygon]) –

commonroad_reach.utility.reach_operation.undiscretized_rectangles(list_rectangles_discretized, tuple_p_min_rectangles, size_grid)[source]

Restores previously discretized rectangles back to undiscretized ones.

p_undiscretized = p_discretized * size_grid + p_min

Return type

List[ReachPolygon]

Parameters
  • list_rectangles_discretized (List[ReachPolygon]) –

  • tuple_p_min_rectangles (Tuple[float, float]) –

  • size_grid (float) –

commonroad_reach.utility.reach_operation.check_collision_and_split_rectangles(collision_checker, step, list_rectangles, radius_terminal_split)[source]

Checks collision status of the input rectangles and split them if colliding.

Return type

List[ReachPolygon]

Parameters
  • step (int) –

  • list_rectangles (List[ReachPolygon]) –

  • radius_terminal_split (float) –

commonroad_reach.utility.reach_operation.create_collision_free_rectangles(step, collision_checker, rectangle, radius_terminal_squared)[source]

Recursively creates a list of collision-free rectangles.

If a collision happens between a rectangle and other object, and the diagonal of the rectangle is greater than the terminal radius, it is split into two new rectangles along its longer (lon/lat) edge.

Return type

List[ReachPolygon]

Parameters
  • step (int) –

  • rectangle (ReachPolygon) –

  • radius_terminal_squared (float) –

commonroad_reach.utility.reach_operation.split_rectangle_into_two(rectangle)[source]

Returns two rectangles each of which is a half of the initial rectangle.

Split in the longer axis (longitudinal / lateral or x / y).

Return type

Tuple[ReachPolygon, ReachPolygon]

Parameters

rectangle (ReachPolygon) –

commonroad_reach.utility.reach_operation.construct_reach_nodes(drivable_area, list_base_sets_propagated, has_multi_generation=False)[source]

Constructs nodes of the reachability graph.

The nodes are constructed by intersecting propagated base sets with the drivable areas to determine the reachable positions and velocities.

Steps:
  1. examine the adjacency of drivable areas and the propagated base sets. They are considered adjacent if they overlap in the position domain.

  2. create a node from each drivable area and its adjacent propagated base sets.

Return type

List[ReachNode]

Parameters
  • drivable_area (List[ReachPolygon]) –

  • list_base_sets_propagated (List[ReachNode]) –

  • has_multi_generation (bool) –

commonroad_reach.utility.reach_operation.construct_reach_node(rectangle_drivable_area, list_base_sets_propagated, list_idx_base_sets_adjacent, multi_generation=False)[source]

Returns a reach node constructed from the propagated base sets.

Iterate through base sets that are adjacent to the drivable areas, and intersect the base sets with position constraints from the drivable areas. A non-empty intersected polygon imply that it is a valid base set and is considered as a parent of the rectangle (reachable from the node from which the base set was propagated).

Parameters
  • rectangle_drivable_area (ReachPolygon) –

  • list_base_sets_propagated (List[ReachNode]) –

  • list_idx_base_sets_adjacent (List[int]) –

commonroad_reach.utility.reach_operation.connect_children_to_parents(step, list_nodes)[source]

Connects child reach nodes to their parent nodes.

Parameters
  • step (int) –

  • list_nodes (List[ReachNode]) –

commonroad_reach.utility.reach_operation.adapt_rectangles_to_grid(list_rectangles, size_grid)[source]

Adapts the given list of position rectangles to a Cartesian grid.

Return type

List[ReachPolygon]

Parameters
  • list_rectangles (List[ReachPolygon]) –

  • size_grid (float) –

commonroad_reach.utility.reach_operation.remove_rectangles_out_of_kamms_circle(dt, a_max, list_rectangles)[source]

Discards position rectangles that do not intersect with Kamm’s friction circle.

Parameters
  • dt (float) – time duration

  • a_max (float) – maximum acceleration

  • list_rectangles (List[ReachPolygon]) – input list of rectangles

Return type

List[ReachPolygon]

commonroad_reach.utility.reach_operation.compute_area_of_reach_nodes(list_nodes_reach)[source]

Computes the area of a given list of reach nodes.

Return type

float

Parameters

list_nodes_reach (List[ReachNode]) –

commonroad_reach.utility.reach_operation.connected_reachset_py(list_nodes_reach, num_digits)[source]

Determines connected sets in the position domain.

Returns a dictionary in the form of {node index:list of tuples (node index, node index)}. This function is the equivalent python function to pycrreach.connected_reachset_boost().

Parameters
  • list_nodes_reach (List[ReachNode]) –

  • num_digits (int) –

commonroad_reach.utility.reach_operation.lon_interval_connected_set(connected_set)[source]

Projects a connected set onto longitudinal position domain and returns min/max longitudinal positions.

commonroad_reach.utility.reach_operation.lat_interval_connected_set(connected_set)[source]

Projects a connected set onto lateral position domain and returns min/max lateral positions.

Sweep Line

class commonroad_reach.utility.sweep_line.EventType(value)[source]

Possible types of events in the sweep line algorithm.

ENTER = 1
EXIT = 2
class commonroad_reach.utility.sweep_line.Event(type_vent, p_lon, p_lat_low, p_lat_high)[source]

Event in the sweep line algorithm.

p_lon = x (CART) = s (CVLN), p_lat = y (CART) = d (CVLN)

It is assumed that the line is swept from left to right. The left edge of a rectangle is typed ‘ENTER’, and the right edge ‘EXIT’.

class commonroad_reach.utility.sweep_line.SweepLine[source]

Class performing sweep line algorithms.

tree: Union[CounterSegmentTree, ToggleSegmentTree]
classmethod obtain_vertical_segments_from_rectangles(list_rectangles)[source]

Returns a list of vertical segments from the input rectangles.

Steps:
  1. create a segment tree with min/max lateral position of rectangles

  2. create events of line sweeping from rectangles: left edge = ENTER, right edge = EXIT

  3. create vertical segments with the events

Return type

List[ReachLine]

Parameters

list_rectangles (List[ReachPolygon]) –

static compute_extremum_lateral_positions_of_rectangles(list_rectangles)[source]

Returns the minimum and maximum lateral positions of the given list of rectangles.

Return type

Tuple[int, int]

Parameters

list_rectangles (List[ReachPolygon]) –

classmethod create_event_list(list_rectangles)[source]

Creates a list of sorted events with the given list of rectangles.

Return type

List[Event]

Parameters

list_rectangles (List[ReachPolygon]) –

classmethod sort_events(list_events)[source]
Return type

List[Event]

Parameters

list_events (List[Event]) –

classmethod compare_events(event1, event2)[source]

Custom comparison function for events.

Events are ordered in the following order:
  1. longitudinal position of rectangles

  2. type of the event

  3. lower lateral position

Parameters
classmethod create_vertical_segments_from_events(list_events)[source]

Creates a list of vertical segments from the list of events.

Return type

List[ReachLine]

Parameters

list_events (List[Event]) –

classmethod create_vertical_segments_from_event(event)[source]

Returns a list of vertical segments with the tree and event.

For each event, query the tree to get the nonactive intervals, which is the desired vertical segment.

Return type

List[ReachLine]

Parameters

event (Event) –

classmethod create_rectangles_from_vertical_segments(list_segments)[source]

Returns a list of rectangles from the given vertical segments.

Step:
  1. Create a segment tree with the list of segments.

  2. Create a dictionary that maps p_lon to a list of rectangles whose left edge is aligned with p_lon.

  3. Merge rectangles that share the same coordinates of p_lat.

Return type

List[ReachPolygon]

Parameters

list_segments (List[ReachLine]) –

static create_tree_from_segments(list_segments)[source]

Creates a ToggleSegmentTree from the list of given segments.

Return type

ToggleSegmentTree

Parameters

list_segments (List[ReachLine]) –

classmethod create_p_lon_to_rectangles_dictionary(list_segments)[source]

Create a dictionary that maps p_lon to a list of rectangles whose left edge is aligned with p_lon.

Steps:
  1. Create a dictionary that maps p_lon to list of tuples of p_lat from segments

  2. Iterate through p_lon, retrieve relevant tuples of p_lat and toggle the status of segments between these p_lat in the segment tree. Get intervals of active segments and create rectangles.

Return type

Dict[int, List[ReachPolygon]]

Parameters

list_segments (List[ReachLine]) –

classmethod merge_rectangles_with_same_lateral_coordinates(dict_p_lon_to_list_rectangles)[source]

Return a list of rectangles with possible merging.

Iterate through pairs of lists of rectangles, if there is a right rectangle with the same lateral coordinates, then do not add to list. Instead, the right rectangle is popped and replaced by the merged one.

Return type

List[ReachPolygon]

Parameters

dict_p_lon_to_list_rectangles (Dict[int, List[ReachPolygon]]) –

static rectangles_have_same_p_lat(rectangle1, rectangle2)[source]

Returns True if the two input rectangles have the same lateral positions.

Return type

bool

Parameters

Visualization

commonroad_reach.utility.visualization.plot_scenario_with_reachable_sets(reach_interface, figsize=None, step_start=0, step_end=0, steps=None, plot_limits=None, path_output=None, save_gif=True, duration=None, terminal_set=None)[source]

Plots scenario with computed reachable sets.

Parameters
  • reach_interface (ReachableSetInterface) –

  • figsize (Optional[Tuple]) –

  • step_start (int) –

  • step_end (int) –

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

  • plot_limits (Optional[List]) –

  • path_output (Optional[str]) –

  • save_gif (bool) –

  • duration (Optional[float]) –

commonroad_reach.utility.visualization.plot_scenario_with_drivable_area(reach_interface, figsize=None, step_start=0, step_end=0, steps=None, plot_limits=None, path_output=None, save_gif=True, duration=None)[source]

Plots scenario with drivable areas.

Parameters
  • reach_interface (ReachableSetInterface) –

  • figsize (Optional[Tuple]) –

  • step_start (int) –

  • step_end (int) –

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

  • plot_limits (Optional[List]) –

  • path_output (Optional[str]) –

  • save_gif (bool) –

  • duration (Optional[float]) –

commonroad_reach.utility.visualization.compute_plot_limits_from_reachable_sets(reach_interface, margin=20)[source]

Returns plot limits from the computed reachable sets.

Parameters
  • reach_interface (ReachableSetInterface) – interface holding the computed reachable sets.

  • margin (int) – additional margin for the plot limits.

Returns

commonroad_reach.utility.visualization.draw_reachable_sets(list_nodes, config, renderer, draw_params)[source]
commonroad_reach.utility.visualization.draw_drivable_area(list_rectangles, config, renderer, draw_params)[source]
commonroad_reach.utility.visualization.save_fig(save_gif, path_output, time_step)[source]
Parameters
  • save_gif (bool) –

  • path_output (str) –

  • time_step (int) –

commonroad_reach.utility.visualization.make_gif(path, prefix, steps, file_save_name='animation', duration=0.1)[source]
Parameters
  • path (str) –

  • prefix (str) –

  • steps (Union[range, List[int]]) –

  • duration (float) –

commonroad_reach.utility.visualization.plot_scenario_with_driving_corridor(driving_corridor, dc_id, reach_interface, step_start=None, step_end=None, steps=None, save_gif=False, duration=None, as_svg=False, terminal_set=None)[source]

2D visualization of a given driving corridor and scenario.

Parameters
  • driving_corridor (DrivingCorridor) – Driving corridor to visualize

  • dc_id (int) – id of driving corridor (idx in DC list)

  • reach_interface (ReachableSetInterface) – ReachableSetInterface object

  • step_start (Optional[int]) – start step for plotting

  • step_end (Optional[int]) – end step

  • steps (Optional[List[int]]) – list of steps to plot

  • save_gif (bool) – make gif (works only if step_end is given)

  • as_svg – save figures as svg for nice paper plots

  • duration (Optional[float]) – duration of a step

  • terminal_set – terminal set at which the driving corridor should end

commonroad_reach.utility.visualization.draw_driving_corridor_2d(driving_corridor, dc_id, reach_interface, trajectory=None, as_svg=False)[source]

Draws full driving corridor in 2D and (optionally) visualizes planned trajectory within the corridor.

Parameters
commonroad_reach.utility.visualization.draw_driving_corridor_3d(driving_corridor, dc_id, reach_interface, list_obstacle_ids=None, as_svg=False)[source]

Draws full driving corridor with 3D projection.

Parameters
commonroad_reach.utility.visualization.plot_scenario_with_reachable_sets_cpp(reachable_set, config, step_start=0, step_end=0, steps=None, plot_limits=None, figsize=None, path_output=None, save_gif=True, duration=None, terminal_set=None)[source]

Plots scenario with computed reachable sets.

Called by C++ script.

Parameters
  • reachable_set (ReachableSet) –

  • config (Configuration) –

  • step_start (int) –

  • step_end (int) –

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

  • plot_limits (Optional[List]) –

  • figsize (Optional[Tuple]) –

  • path_output (Optional[str]) –

  • save_gif (bool) –

  • duration (Optional[float]) –

commonroad_reach.utility.visualization.compute_plot_limits_from_reachable_sets_cpp(reachable_set, config, margin=20)[source]

Returns plot limits from the computed reachable sets.

Parameters
  • reachable_set (ReachableSet) – C++ class holding the computed reachable sets.

  • config (Configuration) – configuration file.

  • margin (int) – additional margin for the plot limits.

Returns

commonroad_reach.utility.visualization.plot_scenario_with_projection_domain(reach_interface)[source]
Parameters

reach_interface (ReachableSetInterface) –

commonroad_reach.utility.visualization.plot_collision_checker(reach_interface)[source]
Parameters

reach_interface (ReachableSetInterface) –