1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 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 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 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459
| import math import copy import logging from typing import List, Type, Optional, Tuple
import sympy as sp import numpy as np import numpy.typing as npt
from nuplan.common.actor_state.oriented_box import in_collision from nuplan.common.actor_state.state_representation import StateVector2D, TimePoint from nuplan.common.actor_state.vehicle_parameters import get_pacifica_parameters from nuplan.planning.simulation.controller.motion_model.kinematic_bicycle import ( KinematicBicycleModel, ) from nuplan.planning.simulation.observation.observation_type import ( DetectionsTracks, Observation, ) from nuplan.planning.simulation.planner.abstract_planner import ( AbstractPlanner, PlannerInitialization, PlannerInput, ) from nuplan.planning.simulation.trajectory.abstract_trajectory import AbstractTrajectory from nuplan.common.maps.abstract_map import AbstractMap from nuplan.planning.simulation.planner.project2.bfs_router import BFSRouter from nuplan.planning.simulation.planner.project2.reference_line_provider import ( ReferenceLineProvider, ) from nuplan.planning.simulation.planner.project2.simple_predictor import SimplePredictor from nuplan.planning.simulation.planner.project2.abstract_predictor import ( AbstractPredictor, ) from nuplan.planning.simulation.planner.project2.frame_transform import cartesian2frenet
from nuplan.planning.simulation.planner.project2.merge_path_speed import ( transform_path_planning, cal_dynamic_state, cal_pose, ) from nuplan.common.actor_state.ego_state import DynamicCarState, EgoState from nuplan.planning.simulation.trajectory.interpolated_trajectory import ( InterpolatedTrajectory, ) from nuplan.common.actor_state.state_representation import StateSE2, StateVector2D from nuplan.common.actor_state.agent import Agent from nuplan.common.actor_state.tracked_objects import TrackedObject, TrackedObjects
logger = logging.getLogger(__name__)
MAX_SPEED = 50.0 / 3.6 MAX_ACCEL = 2.0 MAX_KAPPA = 1.0 MAX_ROAD_WIDTH = 7.0 D_ROAD_W = 1.0 DT = 0.2 MAX_T = 5.0 MIN_T = 4.0 TARGET_SPEED = 30.0 / 3.6 D_T_S = 5.0 / 3.6 N_S_SAMPLE = 1
K_J = 0.1 K_T = 0.1 K_D = 1.0 K_LAT = 1.0 K_LON = 1.0
class FrenetPath: def __init__(self): self.t = [] self.d = [] self.d_d = [] self.d_dd = [] self.d_ddd = [] self.s = [] self.s_d = [] self.s_dd = [] self.s_ddd = [] self.d_cost = 0.0 self.s_cost = 0.0 self.cost = 0.0
self.idx2s = [] self.x = [] self.y = [] self.heading = [] self.kappa = []
class QuinticPolynomial: def __init__(self, strat_state, end_state): t_0, x_0, dx_0, ddx_0 = strat_state t_1, x_1, dx_1, ddx_1 = end_state A = np.array( [ [1, t_0, t_0**2, t_0**3, t_0**4, t_0**5], [0, 1, 2 * t_0, 3 * t_0**2, 4 * t_0**3, 5 * t_0**4], [0, 0, 2, 6 * t_0, 12 * t_0**2, 20 * t_0**3], [1, t_1, t_1**2, t_1**3, t_1**4, t_1**5], [0, 1, 2 * t_1, 3 * t_1**2, 4 * t_1**3, 5 * t_1**4], [0, 0, 2, 6 * t_1, 12 * t_1**2, 20 * t_1**3], ] ) b = np.array([x_0, dx_0, ddx_0, x_1, dx_1, ddx_1]) self.K = np.linalg.solve(A, b) self.k_0, self.k_1, self.k_2, self.k_3, self.k_4, self.k_5 = self.K
def calc_points(self, t): return ( self.k_0 + self.k_1 * t + self.k_2 * t**2 + self.k_3 * t**3 + self.k_4 * t**4 + self.k_5 * t**5 )
def calc_first_derivative(self, t): return ( self.k_1 + 2 * self.k_2 * t + 3 * self.k_3 * t**2 + 4 * self.k_4 * t**3 + 5 * self.k_5 * t**4 )
def calc_second_derivative(self, t): return ( 2 * self.k_2 + 6 * self.k_3 * t + 12 * self.k_4 * t**2 + 20 * self.k_5 * t**3 )
def calc_third_derivative(self, t): return 6 * self.k_3 + 24 * self.k_4 * t + 60 * self.k_5 * t**2
class QuarticPolynomial: def __init__(self, strat_state, end_state):
t_0, x_0, dx_0, ddx_0 = strat_state t_1, dx_1, ddx_1 = end_state A = np.array( [ [1, t_0, t_0**2, t_0**3, t_0**4], [0, 1, 2 * t_0, 3 * t_0**2, 4 * t_0**3], [0, 0, 2, 6 * t_0, 12 * t_0**2], [0, 1, 2 * t_1, 3 * t_1**2, 4 * t_1**3], [0, 0, 2, 6 * t_1, 12 * t_1**2], ] ) b = np.array([x_0, dx_0, ddx_0, dx_1, ddx_1]) self.K = np.linalg.solve(A, b) self.k_0, self.k_1, self.k_2, self.k_3, self.k_4 = self.K
def calc_points(self, t): return self.k_0 + self.k_1 * t + self.k_2 * t**2 + self.k_3 * t**3
def calc_first_derivative(self, t): return self.k_1 + 2 * self.k_2 * t + 3 * self.k_3 * t**2
def calc_second_derivative(self, t): return 2 * self.k_2 + 6 * self.k_3 * t
def calc_third_derivative(self, t): return 6 * self.k_3
def calc_frenet_paths(d_start_state: list, s_start_state: list) -> list: frenet_paths = []
for di in range(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): for Ti in np.arange(MIN_T, MAX_T, DT): fp = FrenetPath()
d_end_state = [Ti, di, 0, 0] lat = QuinticPolynomial(d_start_state, d_end_state) fp.t = [t for t in np.arange(0.0, Ti, DT)] fp.d = [lat.calc_points(t) for t in fp.t] fp.d_d = [lat.calc_first_derivative(t) for t in fp.t] fp.d_dd = [lat.calc_second_derivative(t) for t in fp.t] fp.d_ddd = [lat.calc_third_derivative(t) for t in fp.t]
for tv in np.arange( TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S, ): tfp = copy.deepcopy(fp) s_end_state = [Ti, tv, 0] lon = QuarticPolynomial(s_start_state, s_end_state)
tfp.s = [lon.calc_points(t) for t in tfp.t] tfp.s_d = [lon.calc_first_derivative(t) for t in tfp.t] tfp.s_dd = [lon.calc_second_derivative(t) for t in tfp.t] tfp.s_ddd = [lon.calc_third_derivative(t) for t in tfp.t]
Jd = sum(np.power(tfp.d_ddd, 2)) Js = sum(np.power(tfp.s_ddd, 2))
ds = (TARGET_SPEED - tfp.s_d[-1]) ** 2
tfp.d_cost = K_J * Jd + K_T * Ti + K_D * tfp.d[-1] ** 2 tfp.s_cost = K_J * Js + K_T * Ti + K_D * ds tfp.cost = K_LAT * tfp.d_cost + K_LON * tfp.s_cost
frenet_paths.append(tfp)
return frenet_paths
def calc_global_paths( fplist: FrenetPath, ref_line: ReferenceLineProvider ) -> FrenetPath: for fp in fplist: fp.idx2s, fp.x, fp.y, fp.heading, fp.kappa = transform_path_planning( fp.s, fp.d, fp.d_d, fp.d_dd, ref_line )
return fplist
def check_paths(fplist: FrenetPath) -> bool: ok_ind = [] for i, _ in enumerate(fplist): if any([v > MAX_SPEED] for v in fplist[i].s_d): continue elif any([abs(a) > MAX_ACCEL] for a in fplist[i].s_dd): continue elif any([abs(c) > MAX_KAPPA for c in fplist[i].kappa]): continue
ok_ind.append(i)
return [fplist[i] for i in ok_ind]
def path_planning( ego_state: EgoState, reference_path_provider: ReferenceLineProvider ) -> FrenetPath: ( s_set, l_set, s_dot_set, l_dot_set, dl_set, l_dot2_set, s_dot2_set, ddl_set, ) = cartesian2frenet( [ego_state.car_footprint.center.x], [ego_state.car_footprint.center.y], [ego_state.dynamic_car_state.center_velocity_2d.x], [ego_state.dynamic_car_state.center_velocity_2d.y], [ego_state.dynamic_car_state.center_acceleration_2d.x], [ego_state.dynamic_car_state.center_acceleration_2d.y], reference_path_provider._x_of_reference_line, reference_path_provider._y_of_reference_line, reference_path_provider._heading_of_reference_line, reference_path_provider._kappa_of_reference_line, reference_path_provider._s_of_reference_line, ) d_start_state = [ ego_state.time_point.time_us / 1e6, l_set[0], l_dot_set[0], l_dot2_set[0], ] s_start_state = [ ego_state.time_point.time_us / 1e6, s_set[0], s_dot_set[0], s_dot2_set[0], ] fplist = calc_frenet_paths(d_start_state, s_start_state) fplist = calc_global_paths(fplist, reference_path_provider) fplist = check_paths(fplist)
min_cost = float("inf") best_path = None for fp in fplist: if min_cost >= fp.cost: min_cost = fp.cost best_path = fp
return best_path
class MyPlanner(AbstractPlanner): """ Planner going straight. """
def __init__( self, horizon_seconds: float, sampling_time: float, max_velocity: float = 5.0, ): """ Constructor for SimplePlanner. :param horizon_seconds: [s] time horizon being run. :param sampling_time: [s] sampling timestep. :param max_velocity: [m/s] ego max velocity. """ self.horizon_time = TimePoint(int(horizon_seconds * 1e6)) self.sampling_time = TimePoint(int(sampling_time * 1e6)) self.max_velocity = max_velocity
self._router: Optional[BFSRouter] = None self._predictor: AbstractPredictor = None self._reference_path_provider: Optional[ReferenceLineProvider] = None self._routing_complete = False
def initialize(self, initialization: PlannerInitialization) -> None: """Inherited, see superclass.""" self._router = BFSRouter(initialization.map_api) self._router._initialize_route_plan(initialization.route_roadblock_ids)
def name(self) -> str: """Inherited, see superclass.""" return self.__class__.__name__
def observation_type(self) -> Type[Observation]: """Inherited, see superclass.""" return DetectionsTracks
def compute_planner_trajectory( self, current_input: PlannerInput ) -> AbstractTrajectory: """ Implement a trajectory that goes straight. Inherited, see superclass. """
ego_state, observations = current_input.history.current_state if not self._routing_complete: self._router._initialize_ego_path(ego_state, self.max_velocity) self._routing_complete = True
self._reference_path_provider = ReferenceLineProvider(self._router) self._reference_path_provider._reference_line_generate(ego_state)
self._predictor = SimplePredictor( ego_state, observations, self.horizon_time.time_s, self.sampling_time.time_s ) objects = self._predictor.predict()
trajectory: List[EgoState] = self.planning( ego_state, self._reference_path_provider, objects, self.horizon_time, self.sampling_time, self.max_velocity, )
return InterpolatedTrajectory(trajectory)
def planning( self, ego_state: EgoState, reference_path_provider: ReferenceLineProvider, object: List[TrackedObjects], horizon_time: TimePoint, sampling_time: TimePoint, max_velocity: float, ) -> List[EgoState]: s trajectory = []
optimal_path = path_planning(ego_state, reference_path_provider)
( optimal_path_t, optimal_path_l, optimal_path_dl, optimal_path_ddl, optimal_path_s, optimal_path_ds, optimal_path_dds, optimal_path_idx2s, optimal_path_x, optimal_path_y, optimal_path_heading, optimal_path_kappa, ) = ( optimal_path.t, optimal_path.d, optimal_path.d_d, optimal_path.d_dd, optimal_path.s, optimal_path.s_d, optimal_path.s_dd, optimal_path.idx2s, optimal_path.x, optimal_path.y, optimal_path.heading, optimal_path.kappa, )
for iter in range(int(horizon_time.time_us / sampling_time.time_us)): relative_time = (iter + 1) * sampling_time.time_s s, velocity, accelerate = cal_dynamic_state( relative_time, optimal_path_t, optimal_path_s, optimal_path_ds, optimal_path_dds, ) x, y, heading, _ = cal_pose( s, optimal_path_idx2s, optimal_path_x, optimal_path_y, optimal_path_heading, optimal_path_kappa, )
state = EgoState.build_from_rear_axle( rear_axle_pose=StateSE2(x, y, heading), rear_axle_velocity_2d=StateVector2D(velocity, 0), rear_axle_acceleration_2d=StateVector2D(accelerate, 0), tire_steering_angle=heading, time_point=state.time_point + sampling_time, vehicle_parameters=state.car_footprint.vehicle_parameters, is_in_auto_mode=True, angular_vel=0, angular_accel=0, )
trajectory.append(state)
return trajectory
|