Skip to content

Global Planner

GlobalPlanner

Global Planner for CommonRoad scenarios. This is essentially a small wrapper around the commonroad-route-planner for route and reference path planning and the commonroad velocity planner for velocity profile planning.

Source code in commonroad_global_planner/global_planner.py
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
class GlobalPlanner:
    """
    Global Planner for CommonRoad scenarios. This is essentially a small wrapper around the commonroad-route-planner
    for route and reference path planning and the commonroad velocity planner for velocity profile planning.
    """

    def __init__(
        self,
        scenario: Scenario,
        planning_problem: PlanningProblem,
    ) -> None:
        """
        CommonRoad global planner. The global planner can generate a route, reference path and velocity profile.
        It is essentially a wrapper for the commonroad-route-planner and the commonroad-velocity-planner.
        :param scenario: cr scenario object
        :param planning_problem: cr planning problem
        """
        self._scenario: Scenario = scenario
        self._planning_problem: PlanningProblem = planning_problem

    @property
    def scenario(self) -> Scenario:
        """
        :return: cr scenario
        """
        return self._scenario

    @scenario.setter
    def scenario(self, scenario: Scenario) -> None:
        """
        :param scenario: cr scenario
        """
        self._scenario = scenario

    @property
    def planning_problem(self) -> PlanningProblem:
        """
        :return: cr planning problem
        """
        return self._planning_problem

    @planning_problem.setter
    def planning_problem(self, planning_problem: PlanningProblem) -> None:
        """
        :param planning_problem: cr planning problem
        """
        self._planning_problem = planning_problem

    def plan_global_trajectory(
        self,
        retrieve_shortest: bool = True,
        consider_least_lance_changes: bool = True,
        velocity_planner: ImplementedPlanners = ImplementedPlanners.QPPlanner,
        use_regulatory_stop_elements: bool = False,
        regulatory_elements_time_step: int = 0,
    ) -> GlobalTrajectory:
        """
        Plans reference path considering one or more route options
        :param retrieve_shortest: if true, shortest route will be used
        :param consider_least_lance_changes: if true, fewer lane changes will be preferred.
        :param velocity_planner: velocity planner to be used
        :param use_regulatory_stop_elements: if true, traffic lights and stop lines will be considered
        :param regulatory_elements_time_step: if use_regulatory_stop_elements, this time step will be used for
        :return: global trajectory
        """
        routes: List[LaneletSequence] = self.plan_routes()
        reference_path: ReferencePath = self.plan_reference_path(
            routes=routes,
            retrieve_shortest=retrieve_shortest,
            consider_least_lance_changes=consider_least_lance_changes,
        )
        return self.plan_velocity_profile(
            reference_path=reference_path,
            velocity_planner=velocity_planner,
            use_regulatory_stop_elements=use_regulatory_stop_elements,
            regulatory_elements_time_step=regulatory_elements_time_step,
        )

    def plan_routes(self) -> List[LaneletSequence]:
        """
        Plan routes, defined as sequence of lanelets
        :return: list of different routes, aka lanelet sequences
        """
        route_planner = RoutePlanner(
            lanelet_network=self._scenario.lanelet_network,
            planning_problem=self._planning_problem,
        )
        return route_planner.plan_routes()

    def plan_reference_path(
        self,
        routes: List[LaneletSequence],
        retrieve_shortest: bool = True,
        consider_least_lance_changes: bool = True,
    ) -> ReferencePath:
        """
        Plans reference path considering one or more route options
        :param routes: route options
        :param retrieve_shortest: if true, will return shortest reference path
        :param consider_least_lance_changes: if true, will return reference path with leas lane changes
        :return: reference path
        """

        ref_path_planner: ReferencePathPlanner = ReferencePathPlanner(
            lanelet_network=self._scenario.lanelet_network,
            planning_problem=self._planning_problem,
            routes=routes,
        )

        return ref_path_planner.plan_shortest_reference_path(
            retrieve_shortest=retrieve_shortest,
            consider_least_lance_changes=consider_least_lance_changes,
        )

    def plan_velocity_profile(
        self,
        reference_path: ReferencePath,
        velocity_planner: ImplementedPlanners = ImplementedPlanners.QPPlanner,
        use_regulatory_stop_elements: bool = False,
        regulatory_elements_time_step: int = 0,
    ) -> GlobalTrajectory:
        """
        Plan velocity profile given a reference path
        :param reference_path: cr reference path
        :param velocity_planner: velocity planner to be used
        :param use_regulatory_stop_elements: if true, traffic lights and stop lines will be considered
        :param regulatory_elements_time_step: if use_regulatory_stop_elements, this time step will be used for
        traffic lights
        :return: global trajectory
        """
        return (
            velocity_api.global_trajectory_from_cr_reference_path_and_planning_problem(
                cr_reference_path=reference_path,
                planning_problem=self._planning_problem,
                lanelet_network=self._scenario.lanelet_network,
                velocity_planner=velocity_planner,
                use_regulatory_elements=use_regulatory_stop_elements,
                regulatory_elements_time_step=regulatory_elements_time_step,
            )
        )

planning_problem property writable

Returns:

Type Description
PlanningProblem

cr planning problem

scenario property writable

Returns:

Type Description
Scenario

cr scenario

__init__(scenario, planning_problem)

CommonRoad global planner. The global planner can generate a route, reference path and velocity profile. It is essentially a wrapper for the commonroad-route-planner and the commonroad-velocity-planner.

Parameters:

Name Type Description Default
scenario Scenario

cr scenario object

required
planning_problem PlanningProblem

cr planning problem

required
Source code in commonroad_global_planner/global_planner.py
22
23
24
25
26
27
28
29
30
31
32
33
34
def __init__(
    self,
    scenario: Scenario,
    planning_problem: PlanningProblem,
) -> None:
    """
    CommonRoad global planner. The global planner can generate a route, reference path and velocity profile.
    It is essentially a wrapper for the commonroad-route-planner and the commonroad-velocity-planner.
    :param scenario: cr scenario object
    :param planning_problem: cr planning problem
    """
    self._scenario: Scenario = scenario
    self._planning_problem: PlanningProblem = planning_problem

plan_global_trajectory(retrieve_shortest=True, consider_least_lance_changes=True, velocity_planner=ImplementedPlanners.QPPlanner, use_regulatory_stop_elements=False, regulatory_elements_time_step=0)

Plans reference path considering one or more route options

Parameters:

Name Type Description Default
retrieve_shortest bool

if true, shortest route will be used

True
consider_least_lance_changes bool

if true, fewer lane changes will be preferred.

True
velocity_planner ImplementedPlanners

velocity planner to be used

QPPlanner
use_regulatory_stop_elements bool

if true, traffic lights and stop lines will be considered

False
regulatory_elements_time_step int

if use_regulatory_stop_elements, this time step will be used for

0

Returns:

Type Description
GlobalTrajectory

global trajectory

Source code in commonroad_global_planner/global_planner.py
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
def plan_global_trajectory(
    self,
    retrieve_shortest: bool = True,
    consider_least_lance_changes: bool = True,
    velocity_planner: ImplementedPlanners = ImplementedPlanners.QPPlanner,
    use_regulatory_stop_elements: bool = False,
    regulatory_elements_time_step: int = 0,
) -> GlobalTrajectory:
    """
    Plans reference path considering one or more route options
    :param retrieve_shortest: if true, shortest route will be used
    :param consider_least_lance_changes: if true, fewer lane changes will be preferred.
    :param velocity_planner: velocity planner to be used
    :param use_regulatory_stop_elements: if true, traffic lights and stop lines will be considered
    :param regulatory_elements_time_step: if use_regulatory_stop_elements, this time step will be used for
    :return: global trajectory
    """
    routes: List[LaneletSequence] = self.plan_routes()
    reference_path: ReferencePath = self.plan_reference_path(
        routes=routes,
        retrieve_shortest=retrieve_shortest,
        consider_least_lance_changes=consider_least_lance_changes,
    )
    return self.plan_velocity_profile(
        reference_path=reference_path,
        velocity_planner=velocity_planner,
        use_regulatory_stop_elements=use_regulatory_stop_elements,
        regulatory_elements_time_step=regulatory_elements_time_step,
    )

plan_reference_path(routes, retrieve_shortest=True, consider_least_lance_changes=True)

Plans reference path considering one or more route options

Parameters:

Name Type Description Default
routes List[LaneletSequence]

route options

required
retrieve_shortest bool

if true, will return shortest reference path

True
consider_least_lance_changes bool

if true, will return reference path with leas lane changes

True

Returns:

Type Description
ReferencePath

reference path

Source code in commonroad_global_planner/global_planner.py
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
def plan_reference_path(
    self,
    routes: List[LaneletSequence],
    retrieve_shortest: bool = True,
    consider_least_lance_changes: bool = True,
) -> ReferencePath:
    """
    Plans reference path considering one or more route options
    :param routes: route options
    :param retrieve_shortest: if true, will return shortest reference path
    :param consider_least_lance_changes: if true, will return reference path with leas lane changes
    :return: reference path
    """

    ref_path_planner: ReferencePathPlanner = ReferencePathPlanner(
        lanelet_network=self._scenario.lanelet_network,
        planning_problem=self._planning_problem,
        routes=routes,
    )

    return ref_path_planner.plan_shortest_reference_path(
        retrieve_shortest=retrieve_shortest,
        consider_least_lance_changes=consider_least_lance_changes,
    )

plan_routes()

Plan routes, defined as sequence of lanelets

Returns:

Type Description
List[LaneletSequence]

list of different routes, aka lanelet sequences

Source code in commonroad_global_planner/global_planner.py
 94
 95
 96
 97
 98
 99
100
101
102
103
def plan_routes(self) -> List[LaneletSequence]:
    """
    Plan routes, defined as sequence of lanelets
    :return: list of different routes, aka lanelet sequences
    """
    route_planner = RoutePlanner(
        lanelet_network=self._scenario.lanelet_network,
        planning_problem=self._planning_problem,
    )
    return route_planner.plan_routes()

plan_velocity_profile(reference_path, velocity_planner=ImplementedPlanners.QPPlanner, use_regulatory_stop_elements=False, regulatory_elements_time_step=0)

Plan velocity profile given a reference path

Parameters:

Name Type Description Default
reference_path ReferencePath

cr reference path

required
velocity_planner ImplementedPlanners

velocity planner to be used

QPPlanner
use_regulatory_stop_elements bool

if true, traffic lights and stop lines will be considered

False
regulatory_elements_time_step int

if use_regulatory_stop_elements, this time step will be used for traffic lights

0

Returns:

Type Description
GlobalTrajectory

global trajectory

Source code in commonroad_global_planner/global_planner.py
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
def plan_velocity_profile(
    self,
    reference_path: ReferencePath,
    velocity_planner: ImplementedPlanners = ImplementedPlanners.QPPlanner,
    use_regulatory_stop_elements: bool = False,
    regulatory_elements_time_step: int = 0,
) -> GlobalTrajectory:
    """
    Plan velocity profile given a reference path
    :param reference_path: cr reference path
    :param velocity_planner: velocity planner to be used
    :param use_regulatory_stop_elements: if true, traffic lights and stop lines will be considered
    :param regulatory_elements_time_step: if use_regulatory_stop_elements, this time step will be used for
    traffic lights
    :return: global trajectory
    """
    return (
        velocity_api.global_trajectory_from_cr_reference_path_and_planning_problem(
            cr_reference_path=reference_path,
            planning_problem=self._planning_problem,
            lanelet_network=self._scenario.lanelet_network,
            velocity_planner=velocity_planner,
            use_regulatory_elements=use_regulatory_stop_elements,
            regulatory_elements_time_step=regulatory_elements_time_step,
        )
    )