Skip to content

Global Trajectory

GlobalTrajectory dataclass

Output class, containing the reference path, with velocity and acceleration profile as well as all information of the CR reference_path it was generated with.

Source code in commonroad_velocity_planner/global_trajectory.py
 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
@dataclass
class GlobalTrajectory:
    """
    Output class, containing the reference path, with velocity and acceleration profile as well as all information
    of the CR reference_path it was generated with.
    """

    lanelet_network: LaneletNetwork
    initial_state: InitialState

    lanelet_ids: List[int]
    sections: List[LaneletSection]
    prohibited_lanelet_ids: List[int]

    lane_change_method: LaneChangeMethod
    num_lane_change_actions: int

    reference_path: np.ndarray
    velocity_profile: np.ndarray
    acceleration_profile: np.ndarray
    planning_problem_start_idx: int
    planning_problem_goal_idx: int

    interpoint_distance: np.ndarray
    path_length_per_point: np.ndarray
    path_orientation: np.ndarray
    path_curvature: np.ndarray
    length_reference_path: float
    average_velocity: float
    maximum_velocity: float
    minimum_velocity: float

    def __post_init__(self):
        self.check_integrity()

    def check_integrity(self) -> None:
        """
        Checks integrity of data class
        """
        if self.minimum_velocity < 0:
            _logger = logging.getLogger(name="IVelocityPlanner.global_trajectory")
            _logger.error(
                f"Velocity profile contains entries < 0. Min val is {self.minimum_velocity}"
            )
            raise ValueError(
                f"Velocity profile contains entries < 0. Min val is {self.minimum_velocity}"
            )

    def get_closest_idx(self, point: np.ndarray) -> int:
        """
        Get idx of closest point on global trajectory
        :param point: (2,) numpy array
        :return: index
        """
        kd_tree: KDTree = KDTree(self.reference_path)
        _, idx = kd_tree.query(point)
        return idx

    def get_closest_point(self, point: np.ndarray) -> Tuple[int, np.ndarray]:
        """
        Get idx and coords of closest point on global trajectory
        :param point:
        :return:
        """
        idx: int = self.get_closest_idx(point)
        return (idx, self.reference_path[idx])

    def get_velocity_at_position_with_lookahead(
        self, position: np.ndarray, lookahead_s: float = 2.0
    ) -> float:
        """
        Get velocity at position. Uses closest point of global trajectory
        :param position: (2,) position array
        :return: velocity
        """
        idx_0: int = self.get_closest_idx(position)
        v_0: float = self.velocity_profile[idx_0]
        s_0: float = self.path_length_per_point[idx_0]

        for idx in range(self.velocity_profile[idx_0:].shape[0]):
            idx_1 = idx_0 + idx
            v_1: float = self.velocity_profile[idx_1]
            s_1: np.ndarray = self.path_length_per_point[idx_1]

            delta_s = s_1 - s_0
            delta_v = v_0 + (v_1 - v_0) / 2

            if delta_v == 0:
                delta_t: float = delta_s / v_0
            else:
                delta_t: float = (s_1 - s_0) / (v_0 + (v_1 - v_0) / 2)

            if delta_t >= lookahead_s:
                break

        return self.velocity_profile[idx_1]

check_integrity()

Checks integrity of data class

Source code in commonroad_velocity_planner/global_trajectory.py
62
63
64
65
66
67
68
69
70
71
72
73
def check_integrity(self) -> None:
    """
    Checks integrity of data class
    """
    if self.minimum_velocity < 0:
        _logger = logging.getLogger(name="IVelocityPlanner.global_trajectory")
        _logger.error(
            f"Velocity profile contains entries < 0. Min val is {self.minimum_velocity}"
        )
        raise ValueError(
            f"Velocity profile contains entries < 0. Min val is {self.minimum_velocity}"
        )

get_closest_idx(point)

Get idx of closest point on global trajectory

Parameters:

Name Type Description Default
point ndarray

(2,) numpy array

required

Returns:

Type Description
int

index

Source code in commonroad_velocity_planner/global_trajectory.py
75
76
77
78
79
80
81
82
83
def get_closest_idx(self, point: np.ndarray) -> int:
    """
    Get idx of closest point on global trajectory
    :param point: (2,) numpy array
    :return: index
    """
    kd_tree: KDTree = KDTree(self.reference_path)
    _, idx = kd_tree.query(point)
    return idx

get_closest_point(point)

Get idx and coords of closest point on global trajectory

Parameters:

Name Type Description Default
point ndarray
required

Returns:

Type Description
Tuple[int, ndarray]
Source code in commonroad_velocity_planner/global_trajectory.py
85
86
87
88
89
90
91
92
def get_closest_point(self, point: np.ndarray) -> Tuple[int, np.ndarray]:
    """
    Get idx and coords of closest point on global trajectory
    :param point:
    :return:
    """
    idx: int = self.get_closest_idx(point)
    return (idx, self.reference_path[idx])

get_velocity_at_position_with_lookahead(position, lookahead_s=2.0)

Get velocity at position. Uses closest point of global trajectory

Parameters:

Name Type Description Default
position ndarray

(2,) position array

required

Returns:

Type Description
float

velocity

Source code in commonroad_velocity_planner/global_trajectory.py
 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
def get_velocity_at_position_with_lookahead(
    self, position: np.ndarray, lookahead_s: float = 2.0
) -> float:
    """
    Get velocity at position. Uses closest point of global trajectory
    :param position: (2,) position array
    :return: velocity
    """
    idx_0: int = self.get_closest_idx(position)
    v_0: float = self.velocity_profile[idx_0]
    s_0: float = self.path_length_per_point[idx_0]

    for idx in range(self.velocity_profile[idx_0:].shape[0]):
        idx_1 = idx_0 + idx
        v_1: float = self.velocity_profile[idx_1]
        s_1: np.ndarray = self.path_length_per_point[idx_1]

        delta_s = s_1 - s_0
        delta_v = v_0 + (v_1 - v_0) / 2

        if delta_v == 0:
            delta_t: float = delta_s / v_0
        else:
            delta_t: float = (s_1 - s_0) / (v_0 + (v_1 - v_0) / 2)

        if delta_t >= lookahead_s:
            break

    return self.velocity_profile[idx_1]

factory_from_reference_path_and_velocity_profile(reference_path, velocity_planning_problem, velocity_profile)

Factory method from cr reference_path and velocity profile.

Parameters:

Name Type Description Default
reference_path ReferencePath
required
velocity_planning_problem VelocityPlanningProblem
required
velocity_profile SplineProfile
required

Returns:

Type Description
GlobalTrajectory
Source code in commonroad_velocity_planner/global_trajectory.py
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
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
def factory_from_reference_path_and_velocity_profile(
    reference_path: ReferencePath,
    velocity_planning_problem: VelocityPlanningProblem,
    velocity_profile: SplineProfile,
) -> GlobalTrajectory:
    """
    Factory method from cr reference_path and velocity profile.
    :param reference_path:
    :param velocity_planning_problem:
    :param velocity_profile:
    :return:
    """

    # As optimization is only done inside the planning problem, we have to calculate the shift to the start
    vpp_start_point: np.ndarray = velocity_planning_problem.sampled_ref_path[
        velocity_planning_problem.sampled_start_idx
    ]
    vpp_end_point: np.ndarray = velocity_planning_problem.sampled_ref_path[
        velocity_planning_problem.sampled_goal_idx
    ]
    route_start_idx: int = project_point_on_ref_path(
        reference_path=reference_path.reference_path, point=vpp_start_point
    )
    route_goal_idx: int = project_point_on_ref_path(
        reference_path=reference_path.reference_path, point=vpp_end_point
    )
    arclength_to_start: float = reference_path.path_length_per_point[route_start_idx]

    velocity_array: np.ndarray = velocity_profile.interpolate_velocity_at_arc_lenth(
        reference_path.path_length_per_point - arclength_to_start
    )
    acceleration_array: np.ndarray = (
        velocity_profile.interpolate_acceleration_at_arc_lenth(
            reference_path.path_length_per_point - arclength_to_start
        )
    )

    # set velocity and acceleration before start and after goal manually
    velocity_array[:route_start_idx] = (
        np.ones_like(velocity_array[:route_start_idx]) * velocity_array[route_start_idx]
    )
    acceleration_array[:route_start_idx] = np.zeros_like(
        acceleration_array[:route_start_idx]
    )
    velocity_array[route_goal_idx:] = (
        np.ones_like(velocity_array[route_goal_idx:]) * velocity_array[route_goal_idx]
    )
    acceleration_array[route_goal_idx:] = np.zeros_like(
        acceleration_array[route_goal_idx:]
    )

    average_velocity: float = np.average(velocity_array, axis=0)
    maximum_velocity: float = np.max(velocity_array)
    minimum_velocity: float = np.min(velocity_array)

    return GlobalTrajectory(
        lanelet_network=reference_path.lanelet_network,
        initial_state=reference_path.initial_state,
        lanelet_ids=reference_path.lanelet_ids,
        sections=reference_path.sections,
        prohibited_lanelet_ids=reference_path.prohibited_lanelet_ids,
        lane_change_method=reference_path.lane_change_method,
        reference_path=reference_path.reference_path,
        num_lane_change_actions=reference_path.num_lane_change_actions,
        velocity_profile=velocity_array,
        acceleration_profile=acceleration_array,
        interpoint_distance=reference_path.interpoint_distances,
        path_length_per_point=reference_path.path_length_per_point,
        path_orientation=reference_path.path_orientation,
        path_curvature=reference_path.path_curvature,
        length_reference_path=reference_path.length_reference_path,
        average_velocity=average_velocity,
        maximum_velocity=maximum_velocity,
        minimum_velocity=minimum_velocity,
        planning_problem_start_idx=route_start_idx,
        planning_problem_goal_idx=route_goal_idx,
    )