Skip to content

Commit

Permalink
Merge branch 'master' into secoc-long
Browse files Browse the repository at this point in the history
  • Loading branch information
chrispypatt authored Jan 15, 2025
2 parents 287da0b + acdaaa1 commit 9399509
Show file tree
Hide file tree
Showing 46 changed files with 1,137 additions and 176 deletions.
10 changes: 5 additions & 5 deletions docs/CARS.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
|Acura|ILX 2016-19|AcuraWatch Plus|[Upstream](#upstream)|
|Acura|Integra 2024|All|[Community](#community)|
|Acura|RDX 2016-18|AcuraWatch Plus|[Upstream](#upstream)|
|Acura|RDX 2019-22|All|[Upstream](#upstream)|
|Acura|RDX 2019-21|All|[Upstream](#upstream)|
|Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)|
|Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)|
|Audi|A4 2016-24|All|[Not compatible](#flexray)|
Expand Down Expand Up @@ -100,7 +100,7 @@
|Hyundai|Elantra 2017-18|Smart Cruise Control (SCC)|[Upstream](#upstream)|
|Hyundai|Elantra 2019|Smart Cruise Control (SCC)|[Upstream](#upstream)|
|Hyundai|Elantra 2021-23|Smart Cruise Control (SCC)|[Upstream](#upstream)|
|Hyundai|Elantra GT 2017-19|Smart Cruise Control (SCC)|[Upstream](#upstream)|
|Hyundai|Elantra GT 2017-20|Smart Cruise Control (SCC)|[Upstream](#upstream)|
|Hyundai|Elantra Hybrid 2021-23|Smart Cruise Control (SCC)|[Upstream](#upstream)|
|Hyundai|Genesis 2015-16|Smart Cruise Control (SCC)|[Upstream](#upstream)|
|Hyundai|i30 2017-19|Smart Cruise Control (SCC)|[Upstream](#upstream)|
Expand Down Expand Up @@ -141,7 +141,7 @@
|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control (ACC)|[Upstream](#upstream)|
|Kia|Carnival 2022-24|Smart Cruise Control (SCC)|[Upstream](#upstream)|
|Kia|Carnival (China only) 2023|Smart Cruise Control (SCC)|[Upstream](#upstream)|
|Kia|Ceed 2019|Smart Cruise Control (SCC)|[Upstream](#upstream)|
|Kia|Ceed 2019-21|Smart Cruise Control (SCC)|[Upstream](#upstream)|
|Kia|EV6 (Southeast Asia only) 2022-24|All|[Upstream](#upstream)|
|Kia|EV6 (with HDA II) 2022-24|Highway Driving Assist II|[Upstream](#upstream)|
|Kia|EV6 (without HDA II) 2022-24|Highway Driving Assist|[Upstream](#upstream)|
Expand Down Expand Up @@ -250,8 +250,8 @@
|Škoda|Octavia Scout 2017-19|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)|
|Škoda|Scala 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)|
|Škoda|Superb 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)|
|Tesla|Model 3|All|[Dashcam mode](#dashcam)|
|Tesla|Model Y|All|[Dashcam mode](#dashcam)|
|Tesla|Model 3 2019-24|Traffic Aware Cruise Control|[Dashcam mode](#dashcam)|
|Tesla|Model Y 2020-24|Traffic Aware Cruise Control|[Dashcam mode](#dashcam)|
|Toyota|Alphard 2019-20|All|[Upstream](#upstream)|
|Toyota|Alphard Hybrid 2021|All|[Upstream](#upstream)|
|Toyota|Avalon 2016|Toyota Safety Sense P|[Upstream](#upstream)|
Expand Down
26 changes: 13 additions & 13 deletions opendbc/car/__init__.py
Original file line number Diff line number Diff line change
@@ -1,15 +1,14 @@
# functions common among cars
import logging
import numpy as np
from collections import namedtuple
from dataclasses import dataclass, field
from enum import IntFlag, ReprEnum, StrEnum, EnumType, auto
from dataclasses import replace

from panda import uds
from opendbc.car import structs
from opendbc.car import structs, uds
from opendbc.car.can_definitions import CanData
from opendbc.car.docs_definitions import CarDocs, ExtraCarDocs
from opendbc.car.common.numpy_fast import clip, interp

# set up logging
carlog = logging.getLogger('carlog')
Expand Down Expand Up @@ -107,14 +106,14 @@ def apply_driver_steer_torque_limits(apply_torque, apply_torque_last, driver_tor
driver_min_torque = -LIMITS.STEER_MAX + (-LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER
max_steer_allowed = max(min(LIMITS.STEER_MAX, driver_max_torque), 0)
min_steer_allowed = min(max(-LIMITS.STEER_MAX, driver_min_torque), 0)
apply_torque = clip(apply_torque, min_steer_allowed, max_steer_allowed)
apply_torque = np.clip(apply_torque, min_steer_allowed, max_steer_allowed)

# slow rate if steer torque increases in magnitude
if apply_torque_last > 0:
apply_torque = clip(apply_torque, max(apply_torque_last - LIMITS.STEER_DELTA_DOWN, -LIMITS.STEER_DELTA_UP),
apply_torque = np.clip(apply_torque, max(apply_torque_last - LIMITS.STEER_DELTA_DOWN, -LIMITS.STEER_DELTA_UP),
apply_torque_last + LIMITS.STEER_DELTA_UP)
else:
apply_torque = clip(apply_torque, apply_torque_last - LIMITS.STEER_DELTA_UP,
apply_torque = np.clip(apply_torque, apply_torque_last - LIMITS.STEER_DELTA_UP,
min(apply_torque_last + LIMITS.STEER_DELTA_DOWN, LIMITS.STEER_DELTA_UP))

return int(round(float(apply_torque)))
Expand All @@ -127,15 +126,15 @@ def apply_dist_to_meas_limits(val, val_last, val_meas,
max_lim = min(max(val_meas + STEER_ERROR_MAX, STEER_ERROR_MAX), STEER_MAX)
min_lim = max(min(val_meas - STEER_ERROR_MAX, -STEER_ERROR_MAX), -STEER_MAX)

val = clip(val, min_lim, max_lim)
val = np.clip(val, min_lim, max_lim)

# slow rate if val increases in magnitude
if val_last > 0:
val = clip(val,
val = np.clip(val,
max(val_last - STEER_DELTA_DOWN, -STEER_DELTA_UP),
val_last + STEER_DELTA_UP)
else:
val = clip(val,
val = np.clip(val,
val_last - STEER_DELTA_UP,
min(val_last + STEER_DELTA_DOWN, STEER_DELTA_UP))

Expand All @@ -153,8 +152,9 @@ def apply_std_steer_angle_limits(apply_angle, apply_angle_last, v_ego, LIMITS):
steer_up = apply_angle_last * apply_angle >= 0. and abs(apply_angle) > abs(apply_angle_last)
rate_limits = LIMITS.ANGLE_RATE_LIMIT_UP if steer_up else LIMITS.ANGLE_RATE_LIMIT_DOWN

angle_rate_lim = interp(v_ego, rate_limits.speed_bp, rate_limits.angle_v)
return clip(apply_angle, apply_angle_last - angle_rate_lim, apply_angle_last + angle_rate_lim)
angle_rate_lim = np.interp(v_ego, rate_limits.speed_bp, rate_limits.angle_v)
angle_rate_lim = float(angle_rate_lim)
return float(np.clip(apply_angle, apply_angle_last - angle_rate_lim, apply_angle_last + angle_rate_lim))


def common_fault_avoidance(fault_condition: bool, request: bool, above_limit_frames: int,
Expand Down Expand Up @@ -188,12 +188,12 @@ def apply_center_deadzone(error, deadzone):


def rate_limit(new_value, last_value, dw_step, up_step):
return clip(new_value, last_value + dw_step, last_value + up_step)
return float(np.clip(new_value, last_value + dw_step, last_value + up_step))


def get_friction(lateral_accel_error: float, lateral_accel_deadzone: float, friction_threshold: float,
torque_params: structs.CarParams.LateralTorqueTuning, friction_compensation: bool) -> float:
friction_interp = interp(
friction_interp = np.interp(
apply_center_deadzone(lateral_accel_error, lateral_accel_deadzone),
[-friction_threshold, friction_threshold],
[-torque_params.friction, torque_params.friction]
Expand Down
4 changes: 3 additions & 1 deletion opendbc/car/car.capnp
Original file line number Diff line number Diff line change
Expand Up @@ -389,13 +389,15 @@ struct CarControl {
lanesVisible @2: Bool;
leadVisible @3: Bool;
visualAlert @4: VisualAlert;
audibleAlert @5: AudibleAlert;
rightLaneVisible @6: Bool;
leftLaneVisible @7: Bool;
rightLaneDepart @8: Bool;
leftLaneDepart @9: Bool;
leadDistanceBars @10: Int8; # 1-3: 1 is closest, 3 is farthest. some ports may utilize 2-4 bars instead

# not used with the dash, TODO: separate structs for dash UI and device UI
audibleAlert @5: AudibleAlert;

enum VisualAlert {
# these are the choices from the Honda
# map as good as you can for your car
Expand Down
9 changes: 9 additions & 0 deletions opendbc/car/chrysler/fingerprints.py
Original file line number Diff line number Diff line change
Expand Up @@ -253,6 +253,7 @@
b'05185116AF',
b'05185116AJ',
b'05185116AK',
b'05185116AL',
b'05190240AP',
b'05190240AQ',
b'05190240AR',
Expand All @@ -272,6 +273,7 @@
b'68243549AG',
b'68302211AC',
b'68302212AD',
b'68302214AC',
b'68302223AC',
b'68302246AC',
b'68331511AC',
Expand Down Expand Up @@ -414,6 +416,7 @@
b'68434846AC',
b'68434847AC',
b'68434849AC',
b'68434850AC',
b'68434856AC',
b'68434858AC',
b'68434859AC',
Expand All @@ -425,6 +428,7 @@
b'68453491AC',
b'68453491AD',
b'68453499AD',
b'68453502AC',
b'68453503AC',
b'68453503AD',
b'68453505AC',
Expand Down Expand Up @@ -521,6 +525,7 @@
b'68466110AB',
b'68466113AA',
b'68469901AA',
b'68469904AA',
b'68469907AA',
b'68522583AA',
b'68522583AB',
Expand Down Expand Up @@ -561,6 +566,7 @@
b'05149848AA ',
b'05149848AC ',
b'05190341AD',
b'05190346AD',
b'68378695AI ',
b'68378695AJ ',
b'68378696AJ ',
Expand All @@ -583,6 +589,7 @@
b'68455111AC ',
b'68455119AC ',
b'68455137AC ',
b'68455142AC ',
b'68455145AC ',
b'68455145AE ',
b'68455146AC ',
Expand Down Expand Up @@ -611,6 +618,7 @@
b'68586105AB ',
b'68629917AC ',
b'68629919AC ',
b'68629919AD ',
b'68629922AC ',
b'68629925AC ',
b'68629926AC ',
Expand Down Expand Up @@ -648,6 +656,7 @@
b'68484466AC',
b'68484467AC',
b'68484471AC',
b'68502994AC',
b'68502994AD',
b'68502996AD',
b'68520867AE',
Expand Down
3 changes: 1 addition & 2 deletions opendbc/car/chrysler/values.py
Original file line number Diff line number Diff line change
@@ -1,8 +1,7 @@
from enum import IntFlag
from dataclasses import dataclass, field

from panda import uds
from opendbc.car import Bus, CarSpecs, DbcDict, PlatformConfig, Platforms
from opendbc.car import Bus, CarSpecs, DbcDict, PlatformConfig, Platforms, uds
from opendbc.car.structs import CarParams
from opendbc.car.docs_definitions import CarHarness, CarDocs, CarParts
from opendbc.car.fw_query_definitions import FwQueryConfig, Request, p16
Expand Down
22 changes: 0 additions & 22 deletions opendbc/car/common/numpy_fast.py

This file was deleted.

15 changes: 6 additions & 9 deletions opendbc/car/common/pid.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,6 @@
import numpy as np
from numbers import Number

from opendbc.car.common.numpy_fast import clip, interp


class PIDController:
def __init__(self, k_p, k_i, k_f=0., k_d=0., pos_limit=1e308, neg_limit=-1e308, rate=100):
self._k_p = k_p
Expand All @@ -28,15 +25,15 @@ def __init__(self, k_p, k_i, k_f=0., k_d=0., pos_limit=1e308, neg_limit=-1e308,

@property
def k_p(self):
return interp(self.speed, self._k_p[0], self._k_p[1])
return np.interp(self.speed, self._k_p[0], self._k_p[1])

@property
def k_i(self):
return interp(self.speed, self._k_i[0], self._k_i[1])
return np.interp(self.speed, self._k_i[0], self._k_i[1])

@property
def k_d(self):
return interp(self.speed, self._k_d[0], self._k_d[1])
return np.interp(self.speed, self._k_d[0], self._k_d[1])

@property
def error_integral(self):
Expand Down Expand Up @@ -64,10 +61,10 @@ def update(self, error, error_rate=0.0, speed=0.0, override=False, feedforward=0

# Clip i to prevent exceeding control limits
control_no_i = self.p + self.d + self.f
control_no_i = clip(control_no_i, self.neg_limit, self.pos_limit)
self.i = clip(self.i, self.neg_limit - control_no_i, self.pos_limit - control_no_i)
control_no_i = np.clip(control_no_i, self.neg_limit, self.pos_limit)
self.i = np.clip(self.i, self.neg_limit - control_no_i, self.pos_limit - control_no_i)

control = self.p + self.i + self.d + self.f

self.control = clip(control, self.neg_limit, self.pos_limit)
self.control = np.clip(control, self.neg_limit, self.pos_limit)
return self.control
3 changes: 1 addition & 2 deletions opendbc/car/ecu_addrs.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
import time

from panda import uds
from opendbc.car import make_tester_present_msg, carlog
from opendbc.car import make_tester_present_msg, carlog, uds
from opendbc.car.can_definitions import CanData, CanRecvCallable, CanSendCallable
from opendbc.car.fw_query_definitions import EcuAddrBusType

Expand Down
14 changes: 7 additions & 7 deletions opendbc/car/ford/carcontroller.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
import math
import numpy as np
from opendbc.can.packer import CANPacker
from opendbc.car import ACCELERATION_DUE_TO_GRAVITY, Bus, DT_CTRL, apply_std_steer_angle_limits, structs
from opendbc.car.ford import fordcan
from opendbc.car.ford.values import CarControllerParams, FordFlags
from opendbc.car.common.numpy_fast import clip, interp
from opendbc.car.interfaces import CarControllerBase, V_CRUISE_MAX

LongCtrlState = structs.CarControl.Actuators.LongControlState
Expand All @@ -13,20 +13,20 @@
def apply_ford_curvature_limits(apply_curvature, apply_curvature_last, current_curvature, v_ego_raw):
# No blending at low speed due to lack of torque wind-up and inaccurate current curvature
if v_ego_raw > 9:
apply_curvature = clip(apply_curvature, current_curvature - CarControllerParams.CURVATURE_ERROR,
apply_curvature = np.clip(apply_curvature, current_curvature - CarControllerParams.CURVATURE_ERROR,
current_curvature + CarControllerParams.CURVATURE_ERROR)

# Curvature rate limit after driver torque limit
apply_curvature = apply_std_steer_angle_limits(apply_curvature, apply_curvature_last, v_ego_raw, CarControllerParams)

return clip(apply_curvature, -CarControllerParams.CURVATURE_MAX, CarControllerParams.CURVATURE_MAX)
return float(np.clip(apply_curvature, -CarControllerParams.CURVATURE_MAX, CarControllerParams.CURVATURE_MAX))


def apply_creep_compensation(accel: float, v_ego: float) -> float:
creep_accel = interp(v_ego, [1., 3.], [0.6, 0.])
creep_accel = interp(accel, [0., 0.2], [creep_accel, 0.])
creep_accel = np.interp(v_ego, [1., 3.], [0.6, 0.])
creep_accel = np.interp(accel, [0., 0.2], [creep_accel, 0.])
accel -= creep_accel
return accel
return float(accel)


class CarController(CarControllerBase):
Expand Down Expand Up @@ -112,7 +112,7 @@ def update(self, CC, CS, now_nanos):
# however even 3.5 m/s^3 causes some overshoot with a step response.
accel = max(accel, self.accel - (3.5 * CarControllerParams.ACC_CONTROL_STEP * DT_CTRL))

accel = clip(accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX)
accel = float(np.clip(accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX))

# Both gas and accel are in m/s^2, accel is used solely for braking
if not CC.longActive or gas < CarControllerParams.MIN_GAS:
Expand Down
4 changes: 2 additions & 2 deletions opendbc/car/ford/interface.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
import numpy as np
from panda import Panda
from opendbc.car.common.numpy_fast import interp
from opendbc.car import Bus, get_safety_config, structs
from opendbc.car.common.conversions import Conversions as CV
from opendbc.car.ford.fordcan import CanBus
Expand All @@ -16,7 +16,7 @@ def get_pid_accel_limits(CP, current_speed, cruise_speed):
# so limit limits of pid to prevent windup
ACCEL_MAX_VALS = [CarControllerParams.ACCEL_MAX, 0.2]
ACCEL_MAX_BP = [cruise_speed - 2., cruise_speed - .4]
return CarControllerParams.ACCEL_MIN, interp(current_speed, ACCEL_MAX_BP, ACCEL_MAX_VALS)
return CarControllerParams.ACCEL_MIN, np.interp(current_speed, ACCEL_MAX_BP, ACCEL_MAX_VALS)

@staticmethod
def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams:
Expand Down
7 changes: 7 additions & 0 deletions opendbc/car/ford/radar_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,7 @@ def __init__(self, CP):
self.updated_messages = set()
self.track_id = 0
self.radar = DBC[CP.carFingerprint].get(Bus.radar)
self.invalid_cnt = 0
if CP.radarUnavailable:
self.rcp = None
elif self.radar == RADAR.DELPHI_ESR:
Expand Down Expand Up @@ -177,6 +178,12 @@ def _update_delphi_mrr(self):

errors = []
if DELPHI_MRR_RADAR_RANGE_COVERAGE[headerScanIndex] != int(self.rcp.vl["MRR_Header_SensorCoverage"]["CAN_RANGE_COVERAGE"]):
self.invalid_cnt += 1
else:
self.invalid_cnt = 0

# Rarely MRR_Header_InformationDetections can fail to send a message. The scan index is skipped in this case
if self.invalid_cnt >= 5:
errors.append("wrongConfig")

for ii in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1):
Expand Down
3 changes: 1 addition & 2 deletions opendbc/car/ford/values.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,7 @@
from dataclasses import dataclass, field, replace
from enum import Enum, IntFlag

from panda import uds
from opendbc.car import AngleRateLimit, Bus, CarSpecs, DbcDict, PlatformConfig, Platforms
from opendbc.car import AngleRateLimit, Bus, CarSpecs, DbcDict, PlatformConfig, Platforms, uds
from opendbc.car.structs import CarParams
from opendbc.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, \
Device, SupportType
Expand Down
3 changes: 1 addition & 2 deletions opendbc/car/fw_query_definitions.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,7 @@
import struct
from collections.abc import Callable

from panda import uds

from opendbc.car import uds
from opendbc.car.structs import CarParams

AddrType = tuple[int, int | None]
Expand Down
Loading

0 comments on commit 9399509

Please sign in to comment.