opencda.core.plan package

Submodules

opencda.core.plan.behavior_agent module

Behavior planning module

class opencda.core.plan.behavior_agent.BehaviorAgent(vehicle, carla_map, config_yaml)

Bases: object

A modulized version of carla BehaviorAgent.

Parameters:
  • vehicle (carla.Vehicle) – The carla.Vehicle. We need this class to spawn our gnss and imu sensor.

  • carla_map (carla.map) – The carla HD map for simulation world.

  • config_yaml (dict) – The configuration dictionary of the localization module.

_ego_pos

Posiion of the ego vehicle.

Type:

carla.position

_ego_speed

Speed of the ego vehicle.

Type:

float

_map

The HD map of the current simulation world.

Type:

carla.map

max_speed

The current speed limit of the ego vehicles.

Type:

float

break_distance

The current distance needed for ego vehicle to reach a steady stop.

Type:

float

_collision_check

A collision check class to estimate the collision with front obstacle.

Type:

collisionchecker

ignore_traffic_light

Boolean indicator of whether to ignore traffic light.

Type:

boolean

overtake_allowed

Boolean indicator of whether to allow overtake.

Type:

boolean

_local_planner

A carla local planner class for behavior planning.

Type:

LocalPlanner

lane_change_allowed

Boolean indicator of whether the lane change is allowed.

Type:

boolean

white_list

The white list contains all position of target platoon member for joining.

Type:

list

obstacle_vehicles

The list contains all obstacle vehicles nearby.

Type:

list

objects

The dictionary that contains all kinds of objects nearby.

Type:

dict

debug_helper

The helper class that help with the debug functions.

Type:

PlanDebugHelper

add_white_list(vm)

Add vehicle manager to white list.

car_following_manager(vehicle, distance, target_speed=None)

Module in charge of car-following behaviors when there’s someone in front of us.

Parameters:
  • vehicle (carla.vehicle)) – Leading vehicle to follow.

  • distance (float) – distance from leading vehicle.

  • target_speed (float) – The target car following speed.

Returns:

  • target_speed (float) – The target speed for the next step.

  • target_loc (carla.Location) – The target location.

check_lane_change_permission(lane_change_allowed, collision_detector_enabled, rk)

Check if lane change is allowed. Several conditions will influence the result such as the road curvature, collision detector, overtake and push status. Please refer to the code for complete conditions.

Parameters:
  • lane_change_allowed (boolean) – Previous lane change permission.

  • collision_detector_enabled (boolean) – True if collision detector is enabled.

  • rk (list) – List of planned path points’ curvatures.

Returns:

lane_change_enabled – True if lane change is allowed

Return type:

boolean

collision_manager(rx, ry, ryaw, waypoint, adjacent_check=False)

This module is in charge of warning in case of a collision.

Parameters:
  • rx (float) – x coordinates of plan path.

  • ry (float) – y coordinates of plan path.

  • ryaw (float) – yaw angle.

  • waypoint (carla.waypoint) – current waypoint of the agent.

  • adjacent_check (boolean) – Whether it is a check for adjacent lane.

get_local_planner()

return the local planner

get_push_destination(ego_vehicle_wp, is_intersection)

Get the destination for push operation.

Parameters:
  • ego_vehicle_wp (carla.waypoint) – Ego vehicle’s waypoint.

  • is_intersection (boolean) – True if in the intersection.

Returns:

reset_target – Temporal push destination.

Return type:

carla.waypoint

is_close_to_destination()

Check if the current ego vehicle’s position is close to destination

Returns:

flag – It is True if the current ego vehicle’s position is close to destination

Return type:

boolean

is_intersection(objects, waypoint_buffer)

Check the next waypoints is near the intersection. This is done by check the distance between the waypoints and the traffic light.

Parameters:
  • objects (dict) – The dictionary contains all objects info.

  • waypoint_buffer (deque) – The waypoint buffer.

Returns:

is_junc – Whether there is any future waypoint in the junction shortly.

Return type:

boolean

lane_change_management()

Identify whether a potential hazard exits if operating lane change.

Returns:

vehicle_state – Whether the lane change is dangerous.

Return type:

boolean

overtake_management(obstacle_vehicle)

Overtake behavior.

Parameters:

obstacle_vehicle (carla.vehicle) – The obstacle vehicle.

Returns:

vehicle_state – Flag indicating whether the vehicle is in dangerous state.

Return type:

boolean

reroute(spawn_points)

This method implements re-routing for vehicles approaching its destination. It finds a new target and

computes another path to reach it.

Parameters:

spawn_points (list) – List of possible destinations for the agent.

run_step(target_speed=None, collision_detector_enabled=True, lane_change_allowed=True)

Execute one step of navigation

Parameters:
  • collision_detector_enabled (boolean) – Whether to enable collision detection.

  • target_speed (float) – A manual order to achieve certain speed.

  • lane_change_allowed (boolean) – Whether lane change is allowed. This is passed from platoon behavior agent.

Returns:

control – Vehicle control of the next step.

Return type:

carla.VehicleControl

set_destination(start_location, end_location, clean=False, end_reset=True, clean_history=False)

This method creates a list of waypoints from agent’s position to destination location based on the route returned by the global router.

Parameters:
  • end_reset (boolean) – Flag to reset the waypoint queue.

  • start_location (carla.location) – Initial position.

  • end_location (carla.location) – Final position.

  • clean (boolean) – Flag to clean the waypoint queue.

  • clean_history (boolean) – Flag to clean the waypoint history.

traffic_light_manager(waypoint)

This method is in charge of behaviors for red lights and stops. WARNING: What follows is a proxy to avoid having a car brake after running a yellow light. This happens because the car is still under the influence of the semaphore, even after passing it. So, the semaphore id is temporarely saved to ignore it and go around this issue, until the car is near a new one.

Parameters:

waypoint (carla.waypoint) – Current waypoint of the agent.

update_information(ego_pos, ego_speed, objects)

Update the perception and localization information to the behavior agent.

Parameters:
  • ego_pos (carla.Transform) – Ego position from localization module.

  • ego_speed (float) – km/h, ego speed.

  • objects (dict) – Objects detection results from perception module.

white_list_match(obstacles)

Match the detected obstacles with the white list. Remove the obstacles that are in white list. The white list contains all position of target platoon member for joining.

Parameters:

obstacles (list) – A list of carla.Vehicle or ObstacleVehicle

Returns:

new_obstacle_list – The new list of obstacles.

Return type:

list

opencda.core.plan.collision_check module

This module is used to check collision possibility

class opencda.core.plan.collision_check.CollisionChecker(time_ahead=1.2, circle_radius=1.0, circle_offsets=None)

Bases: object

The default collision checker module.

Parameters:
  • time_ahead (float) – how many seconds we look ahead in advance for collision check.

  • circle_radius (float) – The radius of the collision checking circle.

  • circle_offsets (float) – The offset between collision checking circle and the trajectory point.

adjacent_lane_collision_check(ego_loc, target_wpt, overtake, carla_map, world)

Generate a straight line in the adjacent lane for collision detection during overtake/lane change.

Parameters:
  • -ego_loc (carla.Location) – Ego Location.

  • -target_wpt (carla.Waypoint) – the check point in the adjacent at a far distance.

  • -overtake (bool) – indicate whether this is an overtake or normal lane change behavior.

  • -world (carla.World) – CARLA Simulation world, used to draw debug lines.

Returns:

the x coordinates of the collision check line in

the adjacent lane

-ry (list): the y coordinates of the collision check line in

the adjacent lane

-ryaw (list): the yaw angle of the the collision check line in

the adjacent lane

Return type:

-rx (list)

collision_circle_check(path_x, path_y, path_yaw, obstacle_vehicle, speed, carla_map, adjacent_check=False)

Use circled collision check to see whether potential hazard on the forwarding path.

Parameters:
  • -adjacent_check (boolean) – Indicator of whether do adjacent check. Note: always give full path for adjacent lane check.

  • -speed (float) – ego vehicle speed in m/s.

  • -path_yaw (float) – a list of yaw angles

  • -path_x (list) – a list of x coordinates

  • -path_y (list) – a list of y coordinates

  • -obstacle_vehicle (carla.vehicle) – potention hazard vehicle on the way

Returns:

Flag indicate whether the

current range is collision free.

Return type:

-collision_free (boolean)

is_in_range(ego_pos, target_vehicle, candidate_vehicle, carla_map)

Check whether there is a obstacle vehicle between target_vehicle and ego_vehicle during back_joining.

Parameters:
  • carla_map (carla.map) – Carla map of the current simulation world.

  • ego_pos (carla.transform) – Ego vehicle position.

  • target_vehicle (carla.vehicle) – The target vehicle that ego vehicle trying to catch up with.

  • candidate_vehicle (carla.vehicle) – The possible obstacle vehicle blocking the ego vehicle and target vehicle.

Returns:

  • detection result (boolean)

  • Indicator of whether the target vehicle is in range.

opencda.core.plan.drive_profile_plotting module

Tools to plot velocity, acceleration, and curvation.

opencda.core.plan.drive_profile_plotting.draw_acceleration_profile_single_plot(acceleration)

Draw velocity profiles in a single plot.

Parameters:

acceleration (list) – The vehicle acceleration profile saved in a list.

opencda.core.plan.drive_profile_plotting.draw_dist_gap_profile_singel_plot(gap_list)

Draw distance gap profiles in a single plot.

Parameters:

gap_list (list) – The vehicle front distance gap profile saved in a list.

opencda.core.plan.drive_profile_plotting.draw_sub_plot(velocity_list, acceleration_list, time_gap_list, distance_gap_list, ttc_list)

This is a specific function that draws 4 in 1 images for trajectory following task.

Parameters:
  • velocity_list (list) – The vehicle velocity profile saved in a list.

  • distance_gap_list (list) – The vehicle distance gap profile saved in a list.

  • time_gap_list (list) – The vehicle time gap profile saved in a list.

  • acceleration_list (list) – The vehicle acceleration profile saved in a list.

  • ttc_list (list) – The ttc list.

opencda.core.plan.drive_profile_plotting.draw_time_gap_profile_singel_plot(gap_list)

Draw inter gap profiles in a single plot.

Parameters:

gap_list (list) – The vehicle front time gap profile saved in a list.

opencda.core.plan.drive_profile_plotting.draw_ttc_profile_single_plot(ttc_list)

Draw ttc.

Parameters:

ttc_list (list) – The vehicle time to collision profile saved in a list.

opencda.core.plan.drive_profile_plotting.draw_velocity_profile_single_plot(velocity_list)

Draw velocity profiles in a single plot.

Parameters:

velocity_list (list) – The vehicle velocity profile saved in a list.

opencda.core.plan.global_route_planner module

This module provides GlobalRoutePlanner implementation.

class opencda.core.plan.global_route_planner.GlobalRoutePlanner(dao)

Bases: object

This class provides a very high level route plan. Instantiate the class by passing a reference to A GlobalRoutePlannerDAO object.

Parameters:

dao (carla.dao) – A global plan that contains routes from start to end.

_topology

The topology graph of the current routes.

Type:

carla.topology

_graph

The node-edge graph of the current routes.

Type:

nx.DiGraph

_id_map

A map constructed with road segment IDs.

Type:

dict

_road_id_to_edge

A mapping that reference road it to edge in the graph.

Type:

list

_intersection_end_node

The node ID of at the end of the intersection.

Type:

int

_previous_decision

The previous behavioral option of the ego vehicle.

Type:

carla.RoadOption

abstract_route_plan(origin, destination)

The function that generates the route plan based on origin and destination.

Parameters:
  • -origin (carla.Location) – object of the route’s start position.

  • -destination (carla.Location) – object of the route’s end position.

Returns:

List of turn by turn navigation decisions

as agents.navigation.local_planner.RoadOption.

Return type:

  • plan (list)

setup()

Performs initial server data lookup for detailed topology and builds graph representation of the world map.

trace_route(origin, destination)

This method returns list of (carla.Waypoint, RoadOption) from origin to destination.

opencda.core.plan.global_route_planner_dao module

This module provides implementation for GlobalRoutePlannerDAO

class opencda.core.plan.global_route_planner_dao.GlobalRoutePlannerDAO(wmap, sampling_resolution)

Bases: object

This class is the data access layer for fetching data from the carla server instance for GlobalRoutePlanner.

Parameters -wmap : carla.world

The current carla simulation world.

-sampling_resolutionfloat

sampling distance between waypoints.

get_resolution()

Return the sampling resolution.

get_topology()

Accessor for topology. This function retrieves topology from the server as a list of road segments as pairs of waypoint objects, and processes the topology into a list of dictionary objects.

return topology:

entry - waypoint of entry point of road segment entryxyz- (x,y,z) of entry point of road segment exit - waypoint of exit point of road segment exitxyz - (x,y,z) of exit point of road segment path - list of waypoints separated by 1m from entry

to exit

get_waypoint(location)

The method returns waypoint at given location.

Parameters:

-location (carla.lcoation) – Vehicle location.

Returns:

Newly generated waypoint close to location.

Return type:

-waypoint (carla.waypoint)

opencda.core.plan.local_planner_behavior module

This module contains a local planner to perform low-level waypoint following based on PID controllers.

class opencda.core.plan.local_planner_behavior.LocalPlanner(agent, carla_map, config_yaml)

Bases: object

LocalPlanner implements the basic behavior of following a trajectory of waypoints that is generated on-the-fly.The low-level motion of the vehicle is computed by using lateral and longitudinal PID controllers. When multiple paths are available (intersections) this local planner makes a random choice.

Parameters:
  • agent (carla.agent) – The carla.agent that applying vehicle contorl.

  • carla_map (carla.map) – The HD map of the current simulation world.

  • config (dict) – The configuration dictionary of the trajectory planning module.

_vehicle

The caral vehicle objcet.

Type:

carla.vehicle

_ego_pos

The current position of the ego vehicle.

Type:

carla.position

_ego_speed

The current speed of the ego vehicle.

Type:

float

waypoints_queue

The waypoint deque of the current plan.

Type:

deque

_waypoint_buffer

A buffer deque to store waypoints of the next steps.

Type:

deque

_long_plan_debug

A list that stores the waypoints of global plan for debug purposes.

Type:

list

_trajectory_buffer

A deque buffer that stores the current trajectory.

Type:

deque

_history_buffer

A deque buffer that stores the trajectory history of the ego vehicle.

Type:

deque

potential_curved_road

A indicator used to identify whether the road is potentially curved by using lane_id and lane’s lateral change

Type:

boolean

lane_id_change
In some corner cases, the id is not changed but we regard it

as lane change due to large lateral diff.

Type:

boolean

buffer_filter()

Remove the waypoints in the global route plan which has dramatic change of yaw angle. Such waypoint can cause bad vehicle dynnamics.

generate_path()

Generate the smooth path using cubic spline.

Returns :

rxlist

List of planned path points’ x coordinates.

rylist

List of planned path points’ y coordinates.

ryawlist

List of planned path points’ yaw angles.

rklist

List of planned path points’ curvatures.

generate_trajectory(rx, ry, rk)

Sampling the generated path and assign speed to each point.

Parameters:
  • rx (list) – List of planned path points’ x coordinates.

  • ry (list) – List of planned path points’ y coordinates.

  • rk (list) – List of planned path points’ curvatures.

  • debug (boolean) – whether to draw the whole plan path

get_history_buffer()

Get the _history_buffer

Returns:

self._history_buffer – A deque buffer that stores the trajectory history of the ego vehicle.

Return type:

deque

get_trajectory()

Get the trajetory

Returns :

self._trajectory_bufferdeque

Trajectory buffer.

get_waypoint_buffer()

Get the _waypoint_buffer.

Returns:

self._waypoint_buffer – A buffer deque to store waypoints of the next steps.

Return type:

deque

get_waypoints_queue()

Get the waypoints_queue. :returns: self.waypoints_queue – The waypoint deque of the current plan. :rtype: deque

pop_buffer(vehicle_transform)

Remove waypoints the ego vehicle has achieved.

Parameters:

vehicle_transform (carla.position) – The position of vehicle.

run_step(rx, ry, rk, target_speed=None, trajectory=None, following=False)

Execute one step of local planning which involves running the longitudinal and lateral PID controllers to follow the smooth waypoints trajectory.

Parameters:
  • rx (list) – List of planned path points’ x coordinates.

  • ry (list) – List of planned path points’ y coordinates.

  • ryaw (list) – List of planned path points’ yaw angles.

  • rk (list) – List of planned path points’ curvatures.

  • following (boolean) – Indicator of whether the vehicle is under following status.

  • trajectory (list) – Pre-generated car-following trajectory only for platoon members.

  • target_speed (float) – The ego vehicle’s desired speed.

Returns:

  • speed (float) – Next trajectory point’s target speed。

  • waypoint (carla.waypoint) – Next trajectory point’s waypoint.

set_global_plan(current_plan, clean=False)

Sets new global plan.

Parameters:
  • current_plan (list) – List of waypoints in the actual plan.

  • clean (boolean) – Indicator of whether to clear the global plan.

update_information(ego_pos, ego_speed)

Update the ego position and speed for trajectory planner.

Parameters:
  • ego_pos (carla.Transform) – Ego position from localization module.

  • ego_speed (float) – Ego speed(km/h) from localization module.

class opencda.core.plan.local_planner_behavior.RoadOption(value)

Bases: Enum

RoadOption represents the possible topological configurations when moving from a segment of lane to other.

CHANGELANELEFT = 5
CHANGELANERIGHT = 6
LANEFOLLOW = 4
LEFT = 1
RIGHT = 2
STRAIGHT = 3
VOID = -1

opencda.core.plan.planer_debug_helper module

Analysis + Visualization functions for planning

class opencda.core.plan.planer_debug_helper.PlanDebugHelper(actor_id)

Bases: object

This class aims to save statistics for planner behaviour.

Parameters: -actor_id : int

The actor ID of the target vehicle for bebuging.

Attributes -speed_list : list

The list containing speed info(m/s) of all time-steps.

-acc_listlist

The list containing acceleration info(m^2/s) of all time-steps.

-ttc_listlist

The list containing ttc info(s) for all time-steps.

-countint

Used to count how many simulation steps have been executed.

evaluate()

Evaluate the target vehicle and visulize the plot. :returns:

The target vehicle’s planning

profile (velocity, acceleration, and ttc).

-perform_txt (txt file): The target vehicle’s planning profile as text files.

Return type:

-figure (matplotlib.pyplot.figure)

update(ego_speed, ttc)

Update the speed info. :param -ego_speed: Ego speed in km/h. :type -ego_speed: float :param -ttc: Time to collision in seconds. :type -ttc: flot

opencda.core.plan.spline module

Cubic spline planner

Author: Atsushi Sakai(@Atsushi_twi)

class opencda.core.plan.spline.Spline(x, y)

Bases: object

Cubic Spline class for calculte curvature

(Author: Atsushi Sakai(@Atsushi_twi)).

Parameters -x : float

The x coordinate.

-yfloat

The y coordinate.

Attributes -b : float

The spline coefficient b.

-cfloat

The spline coefficient c.

-dfloat

The spline coefficient d.

-wfloat

The spline coefficient w.

-nxfloat

The dimension of x.

-hfloat

The n-th discrete difference along the x-axis.

calc(t)

Calc position

Parameters:

t (-) – if t is outside of the input x, return None

Returns:

The calcualtion result of position.

If t is outside the range of x, return None.

Return type:

  • result (float)

calcd(t)

Calc first derivative. If t is outside of the input x, return None.

calcdd(t)

Calc second derivative, If t is outside of the input x, return None.

class opencda.core.plan.spline.Spline2D(x, y)

Bases: object

2D Cubic Spline class for calculte curvature

(Author: Atsushi Sakai(@Atsushi_twi)).

Parameters -x : float

The x coordinate.

-yfloat

The y coordinate.

Attributes -b : float

The spline coefficient b.

-cfloat

The spline coefficient c.

-dfloat

The spline coefficient d.

-wfloat

The spline coefficient w.

-nxfloat

The dimension of x.

-hfloat

The n-th discrete difference along the x-axis.

calc_curvature(s)

Calculate curvature.

calc_position(s)

Calculate position.

calc_yaw(s)

Calculate yaw.

opencda.core.plan.spline.calc_spline_course(x, y, ds=0.1)

Caculate 2D splice course.

Parameters:
  • -x (float) – The x coordinate of the input point.

  • -y (float) – The y coordinate of the input point.

  • -ds (flost) – The s step value. Default value equals to 0.1.

Returns:

List of spline course points’ x coordinates. -ry (list): List of spline course points’ y coordinates. -ryaw (list): List of spline course points’ yaw angles. -rk (list): List of spline course points’ curvatures. -s (list): List of spline course points’ s values.

Return type:

-rx (list)

opencda.core.plan.spline.main()

Main function to calculate spline and visulize the results.

Module contents