Skip to content

Velocity Planning Problem

VelocityPlanningProblem dataclass

Transforms planning problem in velocity planning problem

Source code in commonroad_velocity_planner/velocity_planning_problem.py
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
@dataclass
class VelocityPlanningProblem:
    """
    Transforms planning problem in velocity planning problem
    """

    planning_problem: PlanningProblem

    sampled_ref_path: np.ndarray

    sampled_start_idx: int
    sampled_goal_idx: int

    interpoint_distance: float
    path_length_per_point: np.ndarray
    path_curvature: np.ndarray
    speed_limits: np.ndarray

    v_initial: float
    v_stop: float
    a_initial: float
    a_stop: float

    def __post_init__(self):
        _ = self.sanity_check()

    def debug_print(self):
        _logger = logging.getLogger(
            name="IVelocityPlanner.velocity_planning_problem.VelocityPlanningProblem"
        )
        _logger.info(f"VPP: a={self.a_initial}")
        _logger.info(f"VPP: v={self.v_initial}")

    def sanity_check(self) -> bool:
        """
        Sanity check for velocity problem dimensions
        :return: true, if correct, else false
        """

        if not (
            self.sampled_ref_path.shape[0]
            == self.path_length_per_point.shape[0]
            == self.path_curvature.shape[0]
            == self.speed_limits.shape[0]
        ):
            _logger = logging.getLogger(
                name="IVelocityPlanner.velocity_planning_problem.VelocityPlanningProblem"
            )
            _logger.warning(
                "\n \n sanity check for velcoty planning problem failed! \n\n"
                f"len sampled refpath: {self.sampled_ref_path.shape[0]} \n"
                f"len sampled path length per proint: {self.path_length_per_point.shape[0]} \n"
                f"len sampled path curvature per proint: {self.path_curvature.shape[0]} \n"
                f"len sampled speed limits: {self.speed_limits.shape[0]} \n"
            )
            retval = False
        else:
            retval = True

        return retval

sanity_check()

Sanity check for velocity problem dimensions

Returns:

Type Description
bool

true, if correct, else false

Source code in commonroad_velocity_planner/velocity_planning_problem.py
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
def sanity_check(self) -> bool:
    """
    Sanity check for velocity problem dimensions
    :return: true, if correct, else false
    """

    if not (
        self.sampled_ref_path.shape[0]
        == self.path_length_per_point.shape[0]
        == self.path_curvature.shape[0]
        == self.speed_limits.shape[0]
    ):
        _logger = logging.getLogger(
            name="IVelocityPlanner.velocity_planning_problem.VelocityPlanningProblem"
        )
        _logger.warning(
            "\n \n sanity check for velcoty planning problem failed! \n\n"
            f"len sampled refpath: {self.sampled_ref_path.shape[0]} \n"
            f"len sampled path length per proint: {self.path_length_per_point.shape[0]} \n"
            f"len sampled path curvature per proint: {self.path_curvature.shape[0]} \n"
            f"len sampled speed limits: {self.speed_limits.shape[0]} \n"
        )
        retval = False
    else:
        retval = True

    return retval

VppBuilder

Builds the velocity planning problem, smoothes and downsamples reference path.

Source code in commonroad_velocity_planner/velocity_planning_problem.py
 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
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
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
class VppBuilder:
    """
    Builds the velocity planning problem, smoothes and downsamples reference path.
    """

    @staticmethod
    def build_vpp(
        reference_path: ReferencePath,
        planning_problem: PlanningProblem,
        resampling_distance: float = 2,
        smoothing_strategy: SmoothingStrategy = SmoothingStrategy.ELASTIC_BAND,
        default_goal_velocity: float = 0.0,
        default_goal_acceleration: float = 0.0,
        offset_start_idx: int = 2,
        offset_end_idx: int = 2,
    ) -> VelocityPlanningProblem:
        """
        Build velocity planning problem by downsampling and smoothing the reference path first
        :param reference_path: cr reference_path object
        :param planning_problem: cr planning problem
        :param resampling_distance: resampling distance
        :param planning_horizon: planning horizon
        :param smoothing_strategy: smoothing strategy
        :param default_goal_velocity: default goal velocity if problem does not contain one
        :param default_goal_acceleration: default goal velocity, if problem does not contain one.
        :return: velocity planning problem object
        """
        if resampling_distance is None:
            interpoint_distance = reference_path.average_interpoint_distance
        else:
            interpoint_distance = resampling_distance

        start_index = np.argmin(
            np.linalg.norm(
                reference_path.reference_path - reference_path.initial_state.position,
                axis=1,
            )
        )

        # get start and stop index of initial reference path
        start_distance = reference_path.path_length_per_point[start_index]
        stop_distance = reference_path.length_reference_path

        # resample before smoothing
        resampled_reference_path, path_length_per_point = (
            cubic_spline_arc_interpolation_2D(
                polyline=reference_path.reference_path,
                start_distance=start_distance,
                stop_distance=stop_distance,
                resampling_distance=resampling_distance,
            )
        )

        # smooth reference path
        smoothing_interface = ICurvatureSmoother()
        smoothed_reference_path = smoothing_interface.smooth(
            smoothing_strategy=smoothing_strategy,
            reference_path=resampled_reference_path,
            path_length_per_point=path_length_per_point,
        )

        # resample after smoothing
        resampled_reference_path, path_length_per_point = (
            cubic_spline_arc_interpolation_2D(polyline=smoothed_reference_path)
        )
        resampled_curvature = compute_scalar_curvature_from_polyline(
            resampled_reference_path
        )

        # curvature
        curvature_spline = CubicSpline(path_length_per_point, resampled_curvature)
        path_curvature = curvature_spline(path_length_per_point)

        # get speed limits
        speed_limits = get_speed_limits_from_lanelet_network(
            resampled_reference_path, reference_path.lanelet_network
        )
        initial_idx = project_initial_state_on_ref_path(
            resampled_reference_path, planning_problem.initial_state
        )
        goal_idx = project_goal_on_ref_path(
            resampled_reference_path, planning_problem.goal
        )

        if initial_idx >= goal_idx:
            _logger = logging.getLogger(
                name="IVelocityPlanner.velocity_planning_problem.VppBuilder"
            )
            _logger.warning(
                "The planning problem is malformed, choosing last point of reference path as goal idx"
            )
            goal_idx = resampled_reference_path.shape[0] - 1

        if initial_idx + offset_start_idx >= goal_idx - offset_end_idx:
            _logger = logging.getLogger(
                name="IVelocityPlanner.velocity_planning_problem.VppBuilder"
            )
            _logger.warning(
                "Accounting for offsets, v_min constraint: initial_idx + offset_start >= goal_idx - offset_end cannot be computed"
            )

        return VelocityPlanningProblem(
            planning_problem=planning_problem,
            sampled_ref_path=resampled_reference_path,
            sampled_start_idx=initial_idx,
            sampled_goal_idx=goal_idx,
            interpoint_distance=interpoint_distance,
            path_length_per_point=path_length_per_point,
            path_curvature=path_curvature,
            speed_limits=speed_limits,
            v_initial=reference_path.initial_state.velocity,
            v_stop=get_goal_velocity(
                goal_region=planning_problem.goal,
                default_velocity=default_goal_velocity,
            ),
            a_initial=reference_path.initial_state.acceleration,
            a_stop=get_goal_acceleration(
                goal_region=planning_problem.goal,
                default_acceleration=default_goal_acceleration,
            ),
        )

build_vpp(reference_path, planning_problem, resampling_distance=2, smoothing_strategy=SmoothingStrategy.ELASTIC_BAND, default_goal_velocity=0.0, default_goal_acceleration=0.0, offset_start_idx=2, offset_end_idx=2) staticmethod

Build velocity planning problem by downsampling and smoothing the reference path first

Parameters:

Name Type Description Default
reference_path ReferencePath

cr reference_path object

required
planning_problem PlanningProblem

cr planning problem

required
resampling_distance float

resampling distance

2
planning_horizon

planning horizon

required
smoothing_strategy SmoothingStrategy

smoothing strategy

ELASTIC_BAND
default_goal_velocity float

default goal velocity if problem does not contain one

0.0
default_goal_acceleration float

default goal velocity, if problem does not contain one.

0.0

Returns:

Type Description
VelocityPlanningProblem

velocity planning problem object

Source code in commonroad_velocity_planner/velocity_planning_problem.py
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
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
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
@staticmethod
def build_vpp(
    reference_path: ReferencePath,
    planning_problem: PlanningProblem,
    resampling_distance: float = 2,
    smoothing_strategy: SmoothingStrategy = SmoothingStrategy.ELASTIC_BAND,
    default_goal_velocity: float = 0.0,
    default_goal_acceleration: float = 0.0,
    offset_start_idx: int = 2,
    offset_end_idx: int = 2,
) -> VelocityPlanningProblem:
    """
    Build velocity planning problem by downsampling and smoothing the reference path first
    :param reference_path: cr reference_path object
    :param planning_problem: cr planning problem
    :param resampling_distance: resampling distance
    :param planning_horizon: planning horizon
    :param smoothing_strategy: smoothing strategy
    :param default_goal_velocity: default goal velocity if problem does not contain one
    :param default_goal_acceleration: default goal velocity, if problem does not contain one.
    :return: velocity planning problem object
    """
    if resampling_distance is None:
        interpoint_distance = reference_path.average_interpoint_distance
    else:
        interpoint_distance = resampling_distance

    start_index = np.argmin(
        np.linalg.norm(
            reference_path.reference_path - reference_path.initial_state.position,
            axis=1,
        )
    )

    # get start and stop index of initial reference path
    start_distance = reference_path.path_length_per_point[start_index]
    stop_distance = reference_path.length_reference_path

    # resample before smoothing
    resampled_reference_path, path_length_per_point = (
        cubic_spline_arc_interpolation_2D(
            polyline=reference_path.reference_path,
            start_distance=start_distance,
            stop_distance=stop_distance,
            resampling_distance=resampling_distance,
        )
    )

    # smooth reference path
    smoothing_interface = ICurvatureSmoother()
    smoothed_reference_path = smoothing_interface.smooth(
        smoothing_strategy=smoothing_strategy,
        reference_path=resampled_reference_path,
        path_length_per_point=path_length_per_point,
    )

    # resample after smoothing
    resampled_reference_path, path_length_per_point = (
        cubic_spline_arc_interpolation_2D(polyline=smoothed_reference_path)
    )
    resampled_curvature = compute_scalar_curvature_from_polyline(
        resampled_reference_path
    )

    # curvature
    curvature_spline = CubicSpline(path_length_per_point, resampled_curvature)
    path_curvature = curvature_spline(path_length_per_point)

    # get speed limits
    speed_limits = get_speed_limits_from_lanelet_network(
        resampled_reference_path, reference_path.lanelet_network
    )
    initial_idx = project_initial_state_on_ref_path(
        resampled_reference_path, planning_problem.initial_state
    )
    goal_idx = project_goal_on_ref_path(
        resampled_reference_path, planning_problem.goal
    )

    if initial_idx >= goal_idx:
        _logger = logging.getLogger(
            name="IVelocityPlanner.velocity_planning_problem.VppBuilder"
        )
        _logger.warning(
            "The planning problem is malformed, choosing last point of reference path as goal idx"
        )
        goal_idx = resampled_reference_path.shape[0] - 1

    if initial_idx + offset_start_idx >= goal_idx - offset_end_idx:
        _logger = logging.getLogger(
            name="IVelocityPlanner.velocity_planning_problem.VppBuilder"
        )
        _logger.warning(
            "Accounting for offsets, v_min constraint: initial_idx + offset_start >= goal_idx - offset_end cannot be computed"
        )

    return VelocityPlanningProblem(
        planning_problem=planning_problem,
        sampled_ref_path=resampled_reference_path,
        sampled_start_idx=initial_idx,
        sampled_goal_idx=goal_idx,
        interpoint_distance=interpoint_distance,
        path_length_per_point=path_length_per_point,
        path_curvature=path_curvature,
        speed_limits=speed_limits,
        v_initial=reference_path.initial_state.velocity,
        v_stop=get_goal_velocity(
            goal_region=planning_problem.goal,
            default_velocity=default_goal_velocity,
        ),
        a_initial=reference_path.initial_state.acceleration,
        a_stop=get_goal_acceleration(
            goal_region=planning_problem.goal,
            default_acceleration=default_goal_acceleration,
        ),
    )