Merge remote-tracking branch 'upstream/master' into hkg-fuzzy

pull/26939/head
Shane Smiskol 2 years ago
commit 37f23e9e03
  1. 5
      RELEASES.md
  2. 2
      cereal
  3. 1
      common/params.cc
  4. 2
      panda
  5. 16
      poetry.lock
  6. 2
      pyproject.toml
  7. 6
      selfdrive/car/chrysler/values.py
  8. 2
      selfdrive/car/ford/values.py
  9. 29
      selfdrive/car/fw_versions.py
  10. 2
      selfdrive/car/hyundai/values.py
  11. 38
      selfdrive/car/tests/test_fw_fingerprint.py
  12. 12
      selfdrive/car/volkswagen/values.py
  13. 49
      selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
  14. 20
      selfdrive/controls/lib/longitudinal_planner.py
  15. 2
      selfdrive/debug/run_process_on_route.py
  16. 2
      selfdrive/manager/manager.py
  17. 1
      selfdrive/test/process_replay/__init__.py
  18. 11
      selfdrive/test/process_replay/compare_logs.py
  19. 3
      selfdrive/test/process_replay/model_replay.py
  20. 25
      selfdrive/test/process_replay/process_replay.py
  21. 2
      selfdrive/test/process_replay/ref_commit
  22. 4
      selfdrive/test/process_replay/regen.py
  23. 7
      selfdrive/test/process_replay/test_processes.py
  24. 11
      selfdrive/ui/qt/offroad/settings.cc
  25. 14
      selfdrive/ui/qt/offroad/software_settings.cc
  26. 64
      selfdrive/ui/qt/widgets/controls.h
  27. 40
      selfdrive/ui/translations/main_de.ts
  28. 40
      selfdrive/ui/translations/main_ja.ts
  29. 40
      selfdrive/ui/translations/main_ko.ts
  30. 40
      selfdrive/ui/translations/main_pt-BR.ts
  31. 40
      selfdrive/ui/translations/main_zh-CHS.ts
  32. 56
      selfdrive/ui/translations/main_zh-CHT.ts
  33. 20
      system/hardware/tici/tests/test_power_draw.py
  34. 4
      tools/cabana/binaryview.cc
  35. 12
      tools/cabana/chart/chart.cc
  36. 5
      tools/cabana/historylog.cc
  37. 5
      tools/cabana/signalview.cc
  38. 12
      tools/lib/helpers.py
  39. 2
      tools/plotjuggler/juggle.py

@ -1,6 +1,11 @@
Version 0.9.3 (2023-06-XX) Version 0.9.3 (2023-06-XX)
======================== ========================
* New driving model * New driving model
* New driving personality setting
* Three settings: aggressive, standard, and relaxed
* Standard is recommended and the default
* In aggressive mode lead follow distance is shorter and quicker gas/brake response
* In relaxed mode lead follow distance is longer
Version 0.9.2 (2023-05-22) Version 0.9.2 (2023-05-22)
======================== ========================

@ -1 +1 @@
Subproject commit 8af4582508dd7acef082c40ede11eb7018415d9a Subproject commit c331e76b966d324a4f8d56b48db44f59601423dc

@ -104,6 +104,7 @@ std::unordered_map<std::string, uint32_t> keys = {
{"DisablePowerDown", PERSISTENT}, {"DisablePowerDown", PERSISTENT},
{"ExperimentalMode", PERSISTENT}, {"ExperimentalMode", PERSISTENT},
{"ExperimentalModeConfirmed", PERSISTENT}, {"ExperimentalModeConfirmed", PERSISTENT},
{"LongitudinalPersonality", PERSISTENT},
{"ExperimentalLongitudinalEnabled", PERSISTENT}, {"ExperimentalLongitudinalEnabled", PERSISTENT},
{"DisableUpdates", PERSISTENT}, {"DisableUpdates", PERSISTENT},
{"DisengageOnAccelerator", PERSISTENT}, {"DisengageOnAccelerator", PERSISTENT},

@ -1 +1 @@
Subproject commit 5847d7dbc05df3bc76243b6704b9d98544eb53df Subproject commit bf2c0071036bae4e0c00c37ae43237fce6063e31

16
poetry.lock generated

@ -190,7 +190,7 @@ tests = ["pytest"]
name = "astroid" name = "astroid"
version = "2.15.5" version = "2.15.5"
description = "An abstract syntax tree for Python with inference support." description = "An abstract syntax tree for Python with inference support."
category = "main" category = "dev"
optional = false optional = false
python-versions = ">=3.7.2" python-versions = ">=3.7.2"
@ -837,7 +837,7 @@ tests = ["check-manifest (>=0.42)", "mock (>=1.3.0)", "pytest (==5.4.3)", "pytes
name = "dill" name = "dill"
version = "0.3.5.1" version = "0.3.5.1"
description = "serialize all of python" description = "serialize all of python"
category = "main" category = "dev"
optional = false optional = false
python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*, !=3.4.*, !=3.5.*, !=3.6.*" python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*, !=3.4.*, !=3.5.*, !=3.6.*"
@ -1631,7 +1631,7 @@ six = "*"
name = "isort" name = "isort"
version = "5.10.1" version = "5.10.1"
description = "A Python utility / library to sort Python imports." description = "A Python utility / library to sort Python imports."
category = "main" category = "dev"
optional = false optional = false
python-versions = ">=3.6.1,<4.0" python-versions = ">=3.6.1,<4.0"
@ -1982,7 +1982,7 @@ tabulate = "*"
name = "lazy-object-proxy" name = "lazy-object-proxy"
version = "1.7.1" version = "1.7.1"
description = "A fast and thorough lazy object proxy." description = "A fast and thorough lazy object proxy."
category = "main" category = "dev"
optional = false optional = false
python-versions = ">=3.6" python-versions = ">=3.6"
@ -3255,7 +3255,7 @@ python-versions = "*"
name = "pylint" name = "pylint"
version = "2.17.4" version = "2.17.4"
description = "python code static checker" description = "python code static checker"
category = "main" category = "dev"
optional = false optional = false
python-versions = ">=3.7.2" python-versions = ">=3.7.2"
@ -4403,7 +4403,7 @@ python-versions = ">=2.6, !=3.0.*, !=3.1.*, !=3.2.*"
name = "tomli" name = "tomli"
version = "2.0.1" version = "2.0.1"
description = "A lil' TOML parser" description = "A lil' TOML parser"
category = "main" category = "dev"
optional = false optional = false
python-versions = ">=3.7" python-versions = ">=3.7"
@ -4709,7 +4709,7 @@ python-versions = ">=3.7"
name = "wrapt" name = "wrapt"
version = "1.14.1" version = "1.14.1"
description = "Module for decorators, wrappers and monkey patching." description = "Module for decorators, wrappers and monkey patching."
category = "main" category = "dev"
optional = false optional = false
python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*,>=2.7" python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*,>=2.7"
@ -4804,7 +4804,7 @@ testing = ["coverage (>=5.0.3)", "zope.event", "zope.testing"]
[metadata] [metadata]
lock-version = "1.1" lock-version = "1.1"
python-versions = "~3.8" python-versions = "~3.8"
content-hash = "454ab16c681fa1754b26156f767ca0701eac357b66c146d71d61b39cbed42f5a" content-hash = "8c0419671beb3e8c8f0add750929f5be32be6fa3f077d44614cbd598b4cadc00"
[metadata.files] [metadata.files]
adal = [ adal = [

@ -37,7 +37,6 @@ psutil = "^5.9.1"
pycapnp = "==1.1.0" pycapnp = "==1.1.0"
pycryptodome = "^3.15.0" pycryptodome = "^3.15.0"
PyJWT = "^2.5.0" PyJWT = "^2.5.0"
pylint = "^2.15.4"
pyopencl = "^2022.2.4" pyopencl = "^2022.2.4"
pyserial = "^3.5" pyserial = "^3.5"
python-dateutil = "^2.8.2" python-dateutil = "^2.8.2"
@ -92,6 +91,7 @@ pprofile = "^2.1.0"
pre-commit = "^2.19.0" pre-commit = "^2.19.0"
pycurl = "^7.45.1" pycurl = "^7.45.1"
pygame = "^2.1.2" pygame = "^2.1.2"
pylint = "^2.17.4"
pyprof2calltree = "^1.4.5" pyprof2calltree = "^1.4.5"
pytest = "^7.1.2" pytest = "^7.1.2"
pytest-xdist = "^2.5.0" pytest-xdist = "^2.5.0"

@ -227,6 +227,7 @@ FW_VERSIONS = {
b'68510283AG', b'68510283AG',
b'68527346AE', b'68527346AE',
b'68527375AD', b'68527375AD',
b'68527382AE',
], ],
(Ecu.srs, 0x744, None): [ (Ecu.srs, 0x744, None): [
b'68428609AB', b'68428609AB',
@ -254,6 +255,7 @@ FW_VERSIONS = {
(Ecu.fwdRadar, 0x753, None): [ (Ecu.fwdRadar, 0x753, None): [
b'04672892AB', b'04672892AB',
b'04672932AB', b'04672932AB',
b'22DTRHD_AA',
b'68320950AH', b'68320950AH',
b'68320950AI', b'68320950AI',
b'68320950AJ', b'68320950AJ',
@ -265,8 +267,10 @@ FW_VERSIONS = {
b'68475160AG', b'68475160AG',
], ],
(Ecu.eps, 0x75A, None): [ (Ecu.eps, 0x75A, None): [
b'21590101AA',
b'68273275AF', b'68273275AF',
b'68273275AG', b'68273275AG',
b'68273275AH',
b'68312176AE', b'68312176AE',
b'68312176AG', b'68312176AG',
b'68440789AC', b'68440789AC',
@ -283,7 +287,9 @@ FW_VERSIONS = {
b'05036065AE ', b'05036065AE ',
b'05036066AE ', b'05036066AE ',
b'05149846AA ', b'05149846AA ',
b'05149848AA ',
b'68378701AI ', b'68378701AI ',
b'68378748AL ',
b'68378758AM ', b'68378758AM ',
b'68448163AJ', b'68448163AJ',
b'68448165AK', b'68448165AK',

@ -213,8 +213,6 @@ FW_VERSIONS = {
(Ecu.engine, 0x7E0, None): [ (Ecu.engine, 0x7E0, None): [
b'JX6A-14C204-BPL\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'JX6A-14C204-BPL\x00\x00\x00\x00\x00\x00\x00\x00\x00',
], ],
(Ecu.shiftByWire, 0x732, None): [
],
}, },
CAR.MAVERICK_MK1: { CAR.MAVERICK_MK1: {
(Ecu.eps, 0x730, None): [ (Ecu.eps, 0x730, None): [

@ -15,6 +15,7 @@ from system.swaglog import cloudlog
Ecu = car.CarParams.Ecu Ecu = car.CarParams.Ecu
ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa] ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa]
FUZZY_EXCLUDE_ECUS = [Ecu.fwdCamera, Ecu.fwdRadar, Ecu.eps, Ecu.debug]
FW_QUERY_CONFIGS = get_interface_attr('FW_QUERY_CONFIG', ignore_none=True) FW_QUERY_CONFIGS = get_interface_attr('FW_QUERY_CONFIG', ignore_none=True)
VERSIONS = get_interface_attr('FW_VERSIONS', ignore_none=True) VERSIONS = get_interface_attr('FW_VERSIONS', ignore_none=True)
@ -28,11 +29,16 @@ def chunks(l, n=128):
yield l[i:i + n] yield l[i:i + n]
def is_brand(brand: str, filter_brand: Optional[str]) -> bool:
"""Returns if brand matches filter_brand or no brand filter is specified"""
return filter_brand is None or brand == filter_brand
def build_fw_dict(fw_versions: List[capnp.lib.capnp._DynamicStructBuilder], def build_fw_dict(fw_versions: List[capnp.lib.capnp._DynamicStructBuilder],
filter_brand: Optional[str] = None) -> Dict[Tuple[int, Optional[int]], Set[bytes]]: filter_brand: Optional[str] = None) -> Dict[Tuple[int, Optional[int]], Set[bytes]]:
fw_versions_dict = defaultdict(set) fw_versions_dict = defaultdict(set)
for fw in fw_versions: for fw in fw_versions:
if (filter_brand is None or fw.brand == filter_brand) and not fw.logging: if is_brand(fw.brand, filter_brand) and not fw.logging:
sub_addr = fw.subAddress if fw.subAddress != 0 else None sub_addr = fw.subAddress if fw.subAddress != 0 else None
fw_versions_dict[(fw.address, sub_addr)].add(fw.fwVersion) fw_versions_dict[(fw.address, sub_addr)].add(fw.fwVersion)
return dict(fw_versions_dict) return dict(fw_versions_dict)
@ -99,12 +105,6 @@ def match_fw_to_car_fuzzy(fw_versions_dict, config, log=True, exclude=None):
that were matched uniquely to that specific car. If multiple ECUs uniquely match to different cars that were matched uniquely to that specific car. If multiple ECUs uniquely match to different cars
the match is rejected.""" the match is rejected."""
# These ECUs are known to be shared between models (EPS only between hybrid/ICE version)
# Getting this exactly right isn't crucial, but excluding camera and radar makes it almost
# impossible to get 3 matching versions, even if two models with shared parts are released at the same
# time and only one is in our database.
exclude_types = [Ecu.fwdCamera, Ecu.fwdRadar, Ecu.eps, Ecu.debug]
# Build lookup table from (addr, sub_addr, fw) to list of candidate cars # Build lookup table from (addr, sub_addr, fw) to list of candidate cars
# TODO: actually fine to be a set. we never assumed that there would be duplicate fw versions, # TODO: actually fine to be a set. we never assumed that there would be duplicate fw versions,
# but now there can be duplicate platform codes for a platform. well we now get the set of platform codes for a # but now there can be duplicate platform codes for a platform. well we now get the set of platform codes for a
@ -116,7 +116,11 @@ def match_fw_to_car_fuzzy(fw_versions_dict, config, log=True, exclude=None):
continue continue
for addr, fws in fw_by_addr.items(): for addr, fws in fw_by_addr.items():
if addr[0] not in exclude_types: # These ECUs are known to be shared between models (EPS only between hybrid/ICE version)
# Getting this exactly right isn't crucial, but excluding camera and radar makes it almost
# impossible to get 3 matching versions, even if two models with shared parts are released at the same
# time and only one is in our database.
if addr[0] not in FUZZY_EXCLUDE_ECUS:
for f in fws: for f in fws:
all_fw_versions[(addr[1], addr[2], f)].append(candidate) all_fw_versions[(addr[1], addr[2], f)].append(candidate)
@ -128,6 +132,7 @@ def match_fw_to_car_fuzzy(fw_versions_dict, config, log=True, exclude=None):
matched_ecus = set() matched_ecus = set()
candidate = None candidate = None
for addr, versions in fw_versions_dict.items(): for addr, versions in fw_versions_dict.items():
ecu_key = (addr[0], addr[1])
for version in versions: for version in versions:
# All cars that have this FW response on the specified address # All cars that have this FW response on the specified address
ecu_key = (addr[0], addr[1]) ecu_key = (addr[0], addr[1])
@ -162,7 +167,7 @@ def match_fw_to_car_fuzzy(fw_versions_dict, config, log=True, exclude=None):
return set() return set()
def match_fw_to_car_exact(fw_versions_dict, _=None) -> Set[str]: def match_fw_to_car_exact(fw_versions_dict, _=None, log=True) -> Set[str]:
"""Do an exact FW match. Returns all cars that match the given """Do an exact FW match. Returns all cars that match the given
FW versions for a list of "essential" ECUs. If an ECU is not considered FW versions for a list of "essential" ECUs. If an ECU is not considered
essential the FW version can be missing to get a fingerprint, but if it's present it essential the FW version can be missing to get a fingerprint, but if it's present it
@ -218,7 +223,7 @@ def match_fw_to_car_orig(fw_versions, allow_exact=True, allow_fuzzy=True):
return True, set() return True, set()
def match_fw_to_car(fw_versions, allow_exact=True, allow_fuzzy=True): def match_fw_to_car(fw_versions, allow_exact=True, allow_fuzzy=True, log=True):
# Try exact matching first # Try exact matching first
exact_matches = [] exact_matches = []
if allow_exact: if allow_exact:
@ -231,7 +236,7 @@ def match_fw_to_car(fw_versions, allow_exact=True, allow_fuzzy=True):
matches = set() matches = set()
for brand in VERSIONS.keys(): for brand in VERSIONS.keys():
fw_versions_dict = build_fw_dict(fw_versions, filter_brand=brand) fw_versions_dict = build_fw_dict(fw_versions, filter_brand=brand)
matches |= match_func(fw_versions_dict, FW_QUERY_CONFIGS[brand]) matches |= match_func(fw_versions_dict, FW_QUERY_CONFIGS[brand], log=log)
if len(matches): if len(matches):
return exact_match, matches return exact_match, matches
@ -366,7 +371,7 @@ def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1,
# Get versions and build capnp list to put into CarParams # Get versions and build capnp list to put into CarParams
car_fw = [] car_fw = []
requests = [(brand, config, r) for brand, config, r in REQUESTS if query_brand is None or brand == query_brand] requests = [(brand, config, r) for brand, config, r in REQUESTS if is_brand(brand, query_brand)]
for addr in tqdm(addrs, disable=not progress): for addr in tqdm(addrs, disable=not progress):
for addr_chunk in chunks(addr): for addr_chunk in chunks(addr):
for brand, config, r in requests: for brand, config, r in requests:

@ -865,12 +865,14 @@ FW_VERSIONS = {
], ],
(Ecu.eps, 0x7d4, None): [ (Ecu.eps, 0x7d4, None): [
b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102',
b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLEC0 4TSHC102',
b'\xf1\x00TM MDPS R 1.00 1.05 57700-CL000 4TSHP105', b'\xf1\x00TM MDPS R 1.00 1.05 57700-CL000 4TSHP105',
b'\xf1\x00TM MDPS C 1.00 1.02 56310-GA000 4TSHA100', b'\xf1\x00TM MDPS C 1.00 1.02 56310-GA000 4TSHA100',
], ],
(Ecu.fwdCamera, 0x7c4, None): [ (Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00TMH MFC AT EUR LHD 1.00 1.06 99211-S1500 220727', b'\xf1\x00TMH MFC AT EUR LHD 1.00 1.06 99211-S1500 220727',
b'\xf1\x00TMH MFC AT USA LHD 1.00 1.03 99211-S1500 210224', b'\xf1\x00TMH MFC AT USA LHD 1.00 1.03 99211-S1500 210224',
b'\xf1\x00TMH MFC AT USA LHD 1.00 1.06 99211-S1500 220727'
b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414', b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414',
], ],
(Ecu.transmission, 0x7e1, None): [ (Ecu.transmission, 0x7e1, None): [

@ -10,7 +10,7 @@ from cereal import car
from common.params import Params from common.params import Params
from selfdrive.car.car_helpers import interfaces from selfdrive.car.car_helpers import interfaces
from selfdrive.car.fingerprints import FW_VERSIONS from selfdrive.car.fingerprints import FW_VERSIONS
from selfdrive.car.fw_versions import FW_QUERY_CONFIGS, VERSIONS, match_fw_to_car, get_fw_versions from selfdrive.car.fw_versions import FW_QUERY_CONFIGS, FUZZY_EXCLUDE_ECUS, VERSIONS, match_fw_to_car, get_fw_versions
CarFw = car.CarParams.CarFw CarFw = car.CarParams.CarFw
Ecu = car.CarParams.Ecu Ecu = car.CarParams.Ecu
@ -33,27 +33,51 @@ class TestFwFingerprint(unittest.TestCase):
self.assertEqual(candidates[0], expected) self.assertEqual(candidates[0], expected)
@parameterized.expand([(b, c, e[c]) for b, e in VERSIONS.items() for c in e]) @parameterized.expand([(b, c, e[c]) for b, e in VERSIONS.items() for c in e])
def test_fw_fingerprint(self, brand, car_model, ecus): def test_exact_match(self, brand, car_model, ecus):
CP = car.CarParams.new_message() CP = car.CarParams.new_message()
for _ in range(200): for _ in range(200):
fw = [] fw = []
for ecu, fw_versions in ecus.items(): for ecu, fw_versions in ecus.items():
if not len(fw_versions):
raise unittest.SkipTest("Car model has no FW versions")
ecu_name, addr, sub_addr = ecu ecu_name, addr, sub_addr = ecu
fw.append({"ecu": ecu_name, "fwVersion": random.choice(fw_versions), 'brand': brand, fw.append({"ecu": ecu_name, "fwVersion": random.choice(fw_versions), 'brand': brand,
"address": addr, "subAddress": 0 if sub_addr is None else sub_addr}) "address": addr, "subAddress": 0 if sub_addr is None else sub_addr})
CP.carFw = fw CP.carFw = fw
_, matches = match_fw_to_car(CP.carFw) _, matches = match_fw_to_car(CP.carFw, allow_fuzzy=False)
self.assertFingerprints(matches, car_model) self.assertFingerprints(matches, car_model)
def test_no_duplicate_fw_versions(self): @parameterized.expand([(b, c, e[c]) for b, e in VERSIONS.items() for c in e])
def test_fuzzy_match_ecu_count(self, brand, car_model, ecus):
# Asserts that fuzzy matching does not count matching FW, but ECU address keys
valid_ecus = [e for e in ecus if e[0] not in FUZZY_EXCLUDE_ECUS]
if not len(valid_ecus):
raise unittest.SkipTest("Car model has no compatible ECUs for fuzzy matching")
fw = []
for ecu in valid_ecus:
ecu_name, addr, sub_addr = ecu
for _ in range(5):
# Add multiple FW versions to simulate ECU returning to multiple queries in a brand
fw.append({"ecu": ecu_name, "fwVersion": random.choice(ecus[ecu]), 'brand': brand,
"address": addr, "subAddress": 0 if sub_addr is None else sub_addr})
CP = car.CarParams.new_message(carFw=fw)
_, matches = match_fw_to_car(CP.carFw, allow_exact=False, log=False)
# Assert no match if there are not enough unique ECUs
unique_ecus = {(f['address'], f['subAddress']) for f in fw}
if len(unique_ecus) < 2:
self.assertEqual(len(matches), 0, car_model)
# There won't always be a match due to shared FW, but if there is it should be correct
elif len(matches):
self.assertFingerprints(matches, car_model)
def test_fw_version_lists(self):
for car_model, ecus in FW_VERSIONS.items(): for car_model, ecus in FW_VERSIONS.items():
with self.subTest(car_model=car_model): with self.subTest(car_model=car_model):
for ecu, ecu_fw in ecus.items(): for ecu, ecu_fw in ecus.items():
with self.subTest(ecu): with self.subTest(ecu):
duplicates = {fw for fw in ecu_fw if ecu_fw.count(fw) > 1} duplicates = {fw for fw in ecu_fw if ecu_fw.count(fw) > 1}
self.assertFalse(len(duplicates), f"{car_model}: Duplicate FW versions: Ecu.{ECU_NAME[ecu[0]]}, {duplicates}") self.assertFalse(len(duplicates), f'{car_model}: Duplicate FW versions: Ecu.{ECU_NAME[ecu[0]]}, {duplicates}')
self.assertGreater(len(ecu_fw), 0, f'{car_model}: No FW versions: Ecu.{ECU_NAME[ecu[0]]}')
def test_all_addrs_map_to_one_ecu(self): def test_all_addrs_map_to_one_ecu(self):
for brand, cars in VERSIONS.items(): for brand, cars in VERSIONS.items():

@ -923,6 +923,7 @@ FW_VERSIONS = {
b'\xf1\x8704E906027CJ\xf1\x897798', b'\xf1\x8704E906027CJ\xf1\x897798',
b'\xf1\x8704L997022N \xf1\x899459', b'\xf1\x8704L997022N \xf1\x899459',
b'\xf1\x875G0906259A \xf1\x890004', b'\xf1\x875G0906259A \xf1\x890004',
b'\xf1\x875G0906259D \xf1\x890002',
b'\xf1\x875G0906259L \xf1\x890002', b'\xf1\x875G0906259L \xf1\x890002',
b'\xf1\x875G0906259Q \xf1\x890002', b'\xf1\x875G0906259Q \xf1\x890002',
b'\xf1\x878V0906259F \xf1\x890002', b'\xf1\x878V0906259F \xf1\x890002',
@ -932,7 +933,7 @@ FW_VERSIONS = {
b'\xf1\x878V0906264B \xf1\x890003', b'\xf1\x878V0906264B \xf1\x890003',
b'\xf1\x878V0907115B \xf1\x890007', b'\xf1\x878V0907115B \xf1\x890007',
b'\xf1\x878V0907404A \xf1\x890005', b'\xf1\x878V0907404A \xf1\x890005',
b'\xf1\x875G0906259D \xf1\x890002', b'\xf1\x878V0907404G \xf1\x890005',
], ],
(Ecu.transmission, 0x7e1, None): [ (Ecu.transmission, 0x7e1, None): [
b'\xf1\x870CW300044T \xf1\x895245', b'\xf1\x870CW300044T \xf1\x895245',
@ -949,6 +950,7 @@ FW_VERSIONS = {
b'\xf1\x870DD300046F \xf1\x891602', b'\xf1\x870DD300046F \xf1\x891602',
b'\xf1\x870DD300046G \xf1\x891601', b'\xf1\x870DD300046G \xf1\x891601',
b'\xf1\x870DL300012E \xf1\x892012', b'\xf1\x870DL300012E \xf1\x892012',
b'\xf1\x870DL300012H \xf1\x892112',
b'\xf1\x870GC300011 \xf1\x890403', b'\xf1\x870GC300011 \xf1\x890403',
b'\xf1\x870GC300013M \xf1\x892402', b'\xf1\x870GC300013M \xf1\x892402',
b'\xf1\x870GC300042J \xf1\x891402', b'\xf1\x870GC300042J \xf1\x891402',
@ -961,9 +963,9 @@ FW_VERSIONS = {
b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1311110011131100311111011731179321342100', b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1311110011131100311111011731179321342100',
b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--241115141112221291163221', b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--241115141112221291163221',
b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\023111112111111--171115141112221291163221', b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\023111112111111--171115141112221291163221',
b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\023121111111211--261117141112231291163221',
b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13111112111111--241115141112221291163221', b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13111112111111--241115141112221291163221',
b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111111--341117141212231291163221', b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111111--341117141212231291163221',
b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111211--261117141112231291163221',
b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\0211212001112110004110411111421149114', b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\0211212001112110004110411111421149114',
b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\0211212001112111104110411111521159114', b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\0211212001112111104110411111521159114',
], ],
@ -972,6 +974,7 @@ FW_VERSIONS = {
b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566G0HA14A1', b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566G0HA14A1',
b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G01A16A1', b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G01A16A1',
b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0HA16A1', b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0HA16A1',
b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0JA13A1',
b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571G0JA14A1', b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571G0JA14A1',
b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521G0G809A1', b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521G0G809A1',
b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\00503G00303A0', b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\00503G00303A0',
@ -1154,6 +1157,7 @@ FW_VERSIONS = {
CAR.SKODA_KODIAQ_MK1: { CAR.SKODA_KODIAQ_MK1: {
(Ecu.engine, 0x7e0, None): [ (Ecu.engine, 0x7e0, None): [
b'\xf1\x8704E906027DD\xf1\x893123', b'\xf1\x8704E906027DD\xf1\x893123',
b'\xf1\x8704E906027NB\xf1\x896517',
b'\xf1\x8704L906026DE\xf1\x895418', b'\xf1\x8704L906026DE\xf1\x895418',
b'\xf1\x8704L906026EJ\xf1\x893661', b'\xf1\x8704L906026EJ\xf1\x893661',
b'\xf1\x8704L906026HT\xf1\x893617', b'\xf1\x8704L906026HT\xf1\x893617',
@ -1162,6 +1166,7 @@ FW_VERSIONS = {
b'\xf1\x8705E906018DJ\xf1\x891903', b'\xf1\x8705E906018DJ\xf1\x891903',
b'\xf1\x875NA907115E \xf1\x890003', b'\xf1\x875NA907115E \xf1\x890003',
b'\xf1\x875NA907115E \xf1\x890005', b'\xf1\x875NA907115E \xf1\x890005',
b'\xf1\x875NA906259E \xf1\x890003',
], ],
(Ecu.transmission, 0x7e1, None): [ (Ecu.transmission, 0x7e1, None): [
b'\xf1\x870D9300043 \xf1\x895202', b'\xf1\x870D9300043 \xf1\x895202',
@ -1170,6 +1175,7 @@ FW_VERSIONS = {
b'\xf1\x870DL300012N \xf1\x892110', b'\xf1\x870DL300012N \xf1\x892110',
b'\xf1\x870DL300013G \xf1\x892119', b'\xf1\x870DL300013G \xf1\x892119',
b'\xf1\x870GC300014N \xf1\x892801', b'\xf1\x870GC300014N \xf1\x892801',
b'\xf1\x870GC300019H \xf1\x892806',
b'\xf1\x870GC300046Q \xf1\x892802', b'\xf1\x870GC300046Q \xf1\x892802',
], ],
(Ecu.srs, 0x715, None): [ (Ecu.srs, 0x715, None): [
@ -1179,6 +1185,7 @@ FW_VERSIONS = {
b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e1213001211001205212112052100', b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e1213001211001205212112052100',
b'\xf1\x873Q0959655CQ\xf1\x890720\xf1\x82\x0e1213111211001205212112052111', b'\xf1\x873Q0959655CQ\xf1\x890720\xf1\x82\x0e1213111211001205212112052111',
b'\xf1\x873Q0959655DJ\xf1\x890731\xf1\x82\x0e1513001511001205232113052J00', b'\xf1\x873Q0959655DJ\xf1\x890731\xf1\x82\x0e1513001511001205232113052J00',
b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100010200--1121240749',
], ],
(Ecu.eps, 0x712, None): [ (Ecu.eps, 0x712, None): [
b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6050405', b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6050405',
@ -1186,6 +1193,7 @@ FW_VERSIONS = {
b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6070405', b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6070405',
b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G500', b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G500',
b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G600', b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G600',
b'\xf1\x875TA907145F \xf1\x891063\xf1\x82\x002LT61A2LOM',
], ],
(Ecu.fwdRadar, 0x757, None): [ (Ecu.fwdRadar, 0x757, None): [
b'\xf1\x872Q0907572Q \xf1\x890342', b'\xf1\x872Q0907572Q \xf1\x890342',

@ -1,7 +1,7 @@
#!/usr/bin/env python3 #!/usr/bin/env python3
import os import os
import numpy as np import numpy as np
from cereal import log
from common.realtime import sec_since_boot from common.realtime import sec_since_boot
from common.numpy_fast import clip from common.numpy_fast import clip
from system.swaglog import cloudlog from system.swaglog import cloudlog
@ -54,18 +54,38 @@ FCW_IDXS = T_IDXS < 5.0
T_DIFFS = np.diff(T_IDXS, prepend=[0.]) T_DIFFS = np.diff(T_IDXS, prepend=[0.])
MIN_ACCEL = -3.5 MIN_ACCEL = -3.5
MAX_ACCEL = 2.0 MAX_ACCEL = 2.0
T_FOLLOW = 1.45
COMFORT_BRAKE = 2.5 COMFORT_BRAKE = 2.5
STOP_DISTANCE = 6.0 STOP_DISTANCE = 6.0
def get_jerk_factor(personality=log.LongitudinalPersonality.standard):
if personality==log.LongitudinalPersonality.relaxed:
return 1.0
elif personality==log.LongitudinalPersonality.standard:
return 1.0
elif personality==log.LongitudinalPersonality.aggressive:
return 0.5
else:
raise NotImplementedError("Longitudinal personality not supported")
def get_T_FOLLOW(personality=log.LongitudinalPersonality.standard):
if personality==log.LongitudinalPersonality.relaxed:
return 1.75
elif personality==log.LongitudinalPersonality.standard:
return 1.45
elif personality==log.LongitudinalPersonality.aggressive:
return 1.25
else:
raise NotImplementedError("Longitudinal personality not supported")
def get_stopped_equivalence_factor(v_lead): def get_stopped_equivalence_factor(v_lead):
return (v_lead**2) / (2 * COMFORT_BRAKE) return (v_lead**2) / (2 * COMFORT_BRAKE)
def get_safe_obstacle_distance(v_ego, t_follow=T_FOLLOW): def get_safe_obstacle_distance(v_ego, t_follow):
return (v_ego**2) / (2 * COMFORT_BRAKE) + t_follow * v_ego + STOP_DISTANCE return (v_ego**2) / (2 * COMFORT_BRAKE) + t_follow * v_ego + STOP_DISTANCE
def desired_follow_distance(v_ego, v_lead): def desired_follow_distance(v_ego, v_lead, t_follow=get_T_FOLLOW()):
return get_safe_obstacle_distance(v_ego) - get_stopped_equivalence_factor(v_lead) return get_safe_obstacle_distance(v_ego, t_follow) - get_stopped_equivalence_factor(v_lead)
def gen_long_model(): def gen_long_model():
@ -161,7 +181,8 @@ def gen_long_ocp():
x0 = np.zeros(X_DIM) x0 = np.zeros(X_DIM)
ocp.constraints.x0 = x0 ocp.constraints.x0 = x0
ocp.parameter_values = np.array([-1.2, 1.2, 0.0, 0.0, T_FOLLOW, LEAD_DANGER_FACTOR]) ocp.parameter_values = np.array([-1.2, 1.2, 0.0, 0.0, get_T_FOLLOW(), LEAD_DANGER_FACTOR])
# We put all constraint cost weights to 0 and only set them at runtime # We put all constraint cost weights to 0 and only set them at runtime
cost_weights = np.zeros(CONSTR_DIM) cost_weights = np.zeros(CONSTR_DIM)
@ -249,10 +270,11 @@ class LongitudinalMpc:
for i in range(N): for i in range(N):
self.solver.cost_set(i, 'Zl', Zl) self.solver.cost_set(i, 'Zl', Zl)
def set_weights(self, prev_accel_constraint=True): def set_weights(self, prev_accel_constraint=True, personality=log.LongitudinalPersonality.standard):
jerk_factor = get_jerk_factor(personality)
if self.mode == 'acc': if self.mode == 'acc':
a_change_cost = A_CHANGE_COST if prev_accel_constraint else 0 a_change_cost = A_CHANGE_COST if prev_accel_constraint else 0
cost_weights = [X_EGO_OBSTACLE_COST, X_EGO_COST, V_EGO_COST, A_EGO_COST, a_change_cost, J_EGO_COST] cost_weights = [X_EGO_OBSTACLE_COST, X_EGO_COST, V_EGO_COST, A_EGO_COST, jerk_factor * a_change_cost, jerk_factor * J_EGO_COST]
constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, DANGER_ZONE_COST] constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, DANGER_ZONE_COST]
elif self.mode == 'blended': elif self.mode == 'blended':
a_change_cost = 40.0 if prev_accel_constraint else 0 a_change_cost = 40.0 if prev_accel_constraint else 0
@ -307,7 +329,8 @@ class LongitudinalMpc:
self.cruise_min_a = min_a self.cruise_min_a = min_a
self.max_a = max_a self.max_a = max_a
def update(self, radarstate, v_cruise, x, v, a, j): def update(self, radarstate, v_cruise, x, v, a, j, personality=log.LongitudinalPersonality.standard):
t_follow = get_T_FOLLOW(personality)
v_ego = self.x0[1] v_ego = self.x0[1]
self.status = radarstate.leadOne.status or radarstate.leadTwo.status self.status = radarstate.leadOne.status or radarstate.leadTwo.status
@ -334,7 +357,7 @@ class LongitudinalMpc:
v_cruise_clipped = np.clip(v_cruise * np.ones(N+1), v_cruise_clipped = np.clip(v_cruise * np.ones(N+1),
v_lower, v_lower,
v_upper) v_upper)
cruise_obstacle = np.cumsum(T_DIFFS * v_cruise_clipped) + get_safe_obstacle_distance(v_cruise_clipped) cruise_obstacle = np.cumsum(T_DIFFS * v_cruise_clipped) + get_safe_obstacle_distance(v_cruise_clipped, get_T_FOLLOW())
x_obstacles = np.column_stack([lead_0_obstacle, lead_1_obstacle, cruise_obstacle]) x_obstacles = np.column_stack([lead_0_obstacle, lead_1_obstacle, cruise_obstacle])
self.source = SOURCES[np.argmin(x_obstacles[0])] self.source = SOURCES[np.argmin(x_obstacles[0])]
@ -368,7 +391,7 @@ class LongitudinalMpc:
self.params[:,2] = np.min(x_obstacles, axis=1) self.params[:,2] = np.min(x_obstacles, axis=1)
self.params[:,3] = np.copy(self.prev_a) self.params[:,3] = np.copy(self.prev_a)
self.params[:,4] = T_FOLLOW self.params[:,4] = t_follow
self.run() self.run()
if (np.any(lead_xv_0[FCW_IDXS,0] - self.x_sol[FCW_IDXS,0] < CRASH_DISTANCE) and if (np.any(lead_xv_0[FCW_IDXS,0] - self.x_sol[FCW_IDXS,0] < CRASH_DISTANCE) and
@ -380,9 +403,9 @@ class LongitudinalMpc:
# Check if it got within lead comfort range # Check if it got within lead comfort range
# TODO This should be done cleaner # TODO This should be done cleaner
if self.mode == 'blended': if self.mode == 'blended':
if any((lead_0_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], T_FOLLOW))- self.x_sol[:,0] < 0.0): if any((lead_0_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], t_follow))- self.x_sol[:,0] < 0.0):
self.source = 'lead0' self.source = 'lead0'
if any((lead_1_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], T_FOLLOW))- self.x_sol[:,0] < 0.0) and \ if any((lead_1_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], t_follow))- self.x_sol[:,0] < 0.0) and \
(lead_1_obstacle[0] - lead_0_obstacle[0]): (lead_1_obstacle[0] - lead_0_obstacle[0]):
self.source = 'lead1' self.source = 'lead1'

@ -2,6 +2,8 @@
import math import math
import numpy as np import numpy as np
from common.numpy_fast import clip, interp from common.numpy_fast import clip, interp
from common.params import Params
from cereal import log
import cereal.messaging as messaging import cereal.messaging as messaging
from common.conversions import Conversions as CV from common.conversions import Conversions as CV
@ -57,6 +59,16 @@ class LongitudinalPlanner:
self.a_desired_trajectory = np.zeros(CONTROL_N) self.a_desired_trajectory = np.zeros(CONTROL_N)
self.j_desired_trajectory = np.zeros(CONTROL_N) self.j_desired_trajectory = np.zeros(CONTROL_N)
self.solverExecutionTime = 0.0 self.solverExecutionTime = 0.0
self.params = Params()
self.param_read_counter = 0
self.read_param()
self.personality = log.LongitudinalPersonality.standard
def read_param(self):
try:
self.personality = int(self.params.get('LongitudinalPersonality'))
except (ValueError, TypeError):
self.personality = log.LongitudinalPersonality.standard
@staticmethod @staticmethod
def parse_model(model_msg, model_error): def parse_model(model_msg, model_error):
@ -75,6 +87,9 @@ class LongitudinalPlanner:
return x, v, a, j return x, v, a, j
def update(self, sm): def update(self, sm):
if self.param_read_counter % 50 == 0:
self.read_param()
self.param_read_counter += 1
self.mpc.mode = 'blended' if sm['controlsState'].experimentalMode else 'acc' self.mpc.mode = 'blended' if sm['controlsState'].experimentalMode else 'acc'
v_ego = sm['carState'].vEgo v_ego = sm['carState'].vEgo
@ -114,11 +129,11 @@ class LongitudinalPlanner:
accel_limits_turns[0] = min(accel_limits_turns[0], self.a_desired + 0.05) accel_limits_turns[0] = min(accel_limits_turns[0], self.a_desired + 0.05)
accel_limits_turns[1] = max(accel_limits_turns[1], self.a_desired - 0.05) accel_limits_turns[1] = max(accel_limits_turns[1], self.a_desired - 0.05)
self.mpc.set_weights(prev_accel_constraint) self.mpc.set_weights(prev_accel_constraint, personality=self.personality)
self.mpc.set_accel_limits(accel_limits_turns[0], accel_limits_turns[1]) self.mpc.set_accel_limits(accel_limits_turns[0], accel_limits_turns[1])
self.mpc.set_cur_state(self.v_desired_filter.x, self.a_desired) self.mpc.set_cur_state(self.v_desired_filter.x, self.a_desired)
x, v, a, j = self.parse_model(sm['modelV2'], self.v_model_error) x, v, a, j = self.parse_model(sm['modelV2'], self.v_model_error)
self.mpc.update(sm['radarState'], v_cruise, x, v, a, j) self.mpc.update(sm['radarState'], v_cruise, x, v, a, j, personality=self.personality)
self.v_desired_trajectory_full = np.interp(T_IDXS, T_IDXS_MPC, self.mpc.v_solution) self.v_desired_trajectory_full = np.interp(T_IDXS, T_IDXS_MPC, self.mpc.v_solution)
self.a_desired_trajectory_full = np.interp(T_IDXS, T_IDXS_MPC, self.mpc.a_solution) self.a_desired_trajectory_full = np.interp(T_IDXS, T_IDXS_MPC, self.mpc.a_solution)
@ -154,5 +169,6 @@ class LongitudinalPlanner:
longitudinalPlan.fcw = self.fcw longitudinalPlan.fcw = self.fcw
longitudinalPlan.solverExecutionTime = self.mpc.solve_time longitudinalPlan.solverExecutionTime = self.mpc.solve_time
longitudinalPlan.personality = self.personality
pm.send('longitudinalPlan', plan_send) pm.send('longitudinalPlan', plan_send)

@ -2,10 +2,10 @@
import argparse import argparse
from selfdrive.test.process_replay.compare_logs import save_log
from selfdrive.test.process_replay.process_replay import CONFIGS, replay_process from selfdrive.test.process_replay.process_replay import CONFIGS, replay_process
from tools.lib.logreader import MultiLogIterator from tools.lib.logreader import MultiLogIterator
from tools.lib.route import Route from tools.lib.route import Route
from tools.lib.helpers import save_log
if __name__ == "__main__": if __name__ == "__main__":
parser = argparse.ArgumentParser(description="Run process on route and create new logs", parser = argparse.ArgumentParser(description="Run process on route and create new logs",

@ -7,6 +7,7 @@ import sys
import traceback import traceback
from typing import List, Tuple, Union from typing import List, Tuple, Union
from cereal import log
import cereal.messaging as messaging import cereal.messaging as messaging
import selfdrive.sentry as sentry import selfdrive.sentry as sentry
from common.basedir import BASEDIR from common.basedir import BASEDIR
@ -44,6 +45,7 @@ def manager_init() -> None:
("HasAcceptedTerms", "0"), ("HasAcceptedTerms", "0"),
("LanguageSetting", "main_en"), ("LanguageSetting", "main_en"),
("OpenpilotEnabledToggle", "1"), ("OpenpilotEnabledToggle", "1"),
("LongitudinalPersonality", str(log.LongitudinalPersonality.standard)),
] ]
if not PC: if not PC:
default_params.append(("LastUpdateTime", datetime.datetime.utcnow().isoformat().encode('utf8'))) default_params.append(("LastUpdateTime", datetime.datetime.utcnow().isoformat().encode('utf8')))

@ -0,0 +1 @@
from selfdrive.test.process_replay.process_replay import CONFIGS, get_process_config, replay_process, replay_process_with_name # noqa: F401

@ -1,5 +1,4 @@
#!/usr/bin/env python3 #!/usr/bin/env python3
import bz2
import sys import sys
import math import math
import capnp import capnp
@ -12,16 +11,6 @@ from tools.lib.logreader import LogReader
EPSILON = sys.float_info.epsilon EPSILON = sys.float_info.epsilon
def save_log(dest, log_msgs, compress=True):
dat = b"".join(msg.as_builder().to_bytes() for msg in log_msgs)
if compress:
dat = bz2.compress(dat)
with open(dest, "wb") as f:
f.write(dat)
def remove_ignored_fields(msg, ignore): def remove_ignored_fields(msg, ignore):
msg = msg.as_builder() msg = msg.as_builder()
for key in ignore: for key in ignore:

@ -14,11 +14,12 @@ from common.transformations.camera import tici_f_frame_size, tici_d_frame_size
from system.hardware import PC from system.hardware import PC
from selfdrive.manager.process_config import managed_processes from selfdrive.manager.process_config import managed_processes
from selfdrive.test.openpilotci import BASE_URL, get_url from selfdrive.test.openpilotci import BASE_URL, get_url
from selfdrive.test.process_replay.compare_logs import compare_logs, save_log from selfdrive.test.process_replay.compare_logs import compare_logs
from selfdrive.test.process_replay.test_processes import format_diff from selfdrive.test.process_replay.test_processes import format_diff
from system.version import get_commit from system.version import get_commit
from tools.lib.framereader import FrameReader from tools.lib.framereader import FrameReader
from tools.lib.logreader import LogReader from tools.lib.logreader import LogReader
from tools.lib.helpers import save_log
TEST_ROUTE = "2f4452b03ccb98f0|2022-12-03--13-45-30" TEST_ROUTE = "2f4452b03ccb98f0|2022-12-03--13-45-30"
SEGMENT = 6 SEGMENT = 6

@ -333,7 +333,28 @@ def get_process_config(name):
raise Exception(f"Cannot find process config with name: {name}") from ex raise Exception(f"Cannot find process config with name: {name}") from ex
def replay_process(cfg, lr, fingerprint=None): def replay_process_with_name(name, lr, *args, **kwargs):
cfg = get_process_config(name)
return replay_process(cfg, lr, *args, **kwargs)
def replay_process(cfg, lr, fingerprint=None, return_all_logs=False):
all_msgs = list(lr)
process_logs = _replay_single_process(cfg, all_msgs, fingerprint)
if return_all_logs:
keys = set(cfg.subs)
modified_logs = [m for m in all_msgs if m.which() not in keys]
modified_logs.extend(process_logs)
modified_logs.sort(key=lambda m: m.logMonoTime)
log_msgs = modified_logs
else:
log_msgs = process_logs
return log_msgs
def _replay_single_process(cfg, lr, fingerprint):
with OpenpilotPrefix(): with OpenpilotPrefix():
controlsState = None controlsState = None
initialized = False initialized = False
@ -484,7 +505,7 @@ def setup_env(CP=None, cfg=None, controlsState=None, lr=None, fingerprint=None,
params.put_bool("ExperimentalLongitudinalEnabled", True) params.put_bool("ExperimentalLongitudinalEnabled", True)
def check_enabled(msgs): def check_openpilot_enabled(msgs):
cur_enabled_count = 0 cur_enabled_count = 0
max_enabled_count = 0 max_enabled_count = 0
for msg in msgs: for msg in msgs:

@ -1 +1 @@
dfe1e4a5fd7a464c91c0d2e70592b4b1470fda8d 3e684aef4483b8d311d71bab3bb543d7bad26563

@ -19,7 +19,7 @@ from panda.python import Panda
from selfdrive.car.toyota.values import EPS_SCALE from selfdrive.car.toyota.values import EPS_SCALE
from selfdrive.manager.process import ensure_running from selfdrive.manager.process import ensure_running
from selfdrive.manager.process_config import managed_processes from selfdrive.manager.process_config import managed_processes
from selfdrive.test.process_replay.process_replay import CONFIGS, FAKEDATA, setup_env, check_enabled from selfdrive.test.process_replay.process_replay import CONFIGS, FAKEDATA, setup_env, check_openpilot_enabled
from selfdrive.test.update_ci_routes import upload_route from selfdrive.test.update_ci_routes import upload_route
from tools.lib.route import Route from tools.lib.route import Route
from tools.lib.framereader import FrameReader from tools.lib.framereader import FrameReader
@ -343,7 +343,7 @@ def regen_segment(lr, frs=None, daemons="all", outdir=FAKEDATA, disable_tqdm=Fal
segment = params.get("CurrentRoute", encoding='utf-8') + "--0" segment = params.get("CurrentRoute", encoding='utf-8') + "--0"
seg_path = os.path.join(outdir, segment) seg_path = os.path.join(outdir, segment)
# check to make sure openpilot is engaged in the route # check to make sure openpilot is engaged in the route
if not check_enabled(LogReader(os.path.join(seg_path, "rlog"))): if not check_openpilot_enabled(LogReader(os.path.join(seg_path, "rlog"))):
raise Exception(f"Route did not engage for long enough: {segment}") raise Exception(f"Route did not engage for long enough: {segment}")
return seg_path return seg_path

@ -9,11 +9,12 @@ from typing import Any, DefaultDict, Dict
from selfdrive.car.car_helpers import interface_names from selfdrive.car.car_helpers import interface_names
from selfdrive.test.openpilotci import get_url, upload_file from selfdrive.test.openpilotci import get_url, upload_file
from selfdrive.test.process_replay.compare_logs import compare_logs, save_log from selfdrive.test.process_replay.compare_logs import compare_logs
from selfdrive.test.process_replay.process_replay import CONFIGS, PROC_REPLAY_DIR, FAKEDATA, check_enabled, replay_process from selfdrive.test.process_replay.process_replay import CONFIGS, PROC_REPLAY_DIR, FAKEDATA, check_openpilot_enabled, replay_process
from system.version import get_commit from system.version import get_commit
from tools.lib.filereader import FileReader from tools.lib.filereader import FileReader
from tools.lib.logreader import LogReader from tools.lib.logreader import LogReader
from tools.lib.helpers import save_log
source_segments = [ source_segments = [
("BODY", "937ccb7243511b65|2022-05-24--16-03-09--1"), # COMMA.BODY ("BODY", "937ccb7243511b65|2022-05-24--16-03-09--1"), # COMMA.BODY
@ -104,7 +105,7 @@ def test_process(cfg, lr, segment, ref_log_path, new_log_path, ignore_fields=Non
# check to make sure openpilot is engaged in the route # check to make sure openpilot is engaged in the route
if cfg.proc_name == "controlsd": if cfg.proc_name == "controlsd":
if not check_enabled(log_msgs): if not check_openpilot_enabled(log_msgs):
return f"Route did not enable at all or for long enough: {new_log_path}", log_msgs return f"Route did not enable at all or for long enough: {new_log_path}", log_msgs
try: try:

@ -89,6 +89,12 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) {
#endif #endif
}; };
std::vector<QString> longi_button_texts{tr("Aggressive"), tr("Standard"), tr("Relaxed")};
ButtonParamControl* long_personality_setting = new ButtonParamControl("LongitudinalPersonality", tr("Driving Personality"),
tr("Standard is recommended. In aggressive mode, openpilot will follow lead cars closer and be more aggressive with the gas and brake. In relaxed mode openpilot will stay further away from lead cars."),
"../assets/offroad/icon_speed_limit.png",
longi_button_texts);
for (auto &[param, title, desc, icon] : toggle_defs) { for (auto &[param, title, desc, icon] : toggle_defs) {
auto toggle = new ParamControl(param, title, desc, icon, this); auto toggle = new ParamControl(param, title, desc, icon, this);
@ -97,6 +103,11 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) {
addItem(toggle); addItem(toggle);
toggles[param.toStdString()] = toggle; toggles[param.toStdString()] = toggle;
// insert longitudinal personality after NDOG toggle
if (param == "DisengageOnAccelerator") {
addItem(long_personality_setting);
}
} }
// Toggles with confirmation dialogs // Toggles with confirmation dialogs

@ -126,19 +126,19 @@ void SoftwarePanel::updateLabels() {
downloadBtn->setValue(updater_state); downloadBtn->setValue(updater_state);
} else { } else {
if (failed) { if (failed) {
downloadBtn->setText("CHECK"); downloadBtn->setText(tr("CHECK"));
downloadBtn->setValue("failed to check for update"); downloadBtn->setValue(tr("failed to check for update"));
} else if (params.getBool("UpdaterFetchAvailable")) { } else if (params.getBool("UpdaterFetchAvailable")) {
downloadBtn->setText("DOWNLOAD"); downloadBtn->setText(tr("DOWNLOAD"));
downloadBtn->setValue("update available"); downloadBtn->setValue(tr("update available"));
} else { } else {
QString lastUpdate = "never"; QString lastUpdate = tr("never");
auto tm = params.get("LastUpdateTime"); auto tm = params.get("LastUpdateTime");
if (!tm.empty()) { if (!tm.empty()) {
lastUpdate = timeAgo(QDateTime::fromString(QString::fromStdString(tm + "Z"), Qt::ISODate)); lastUpdate = timeAgo(QDateTime::fromString(QString::fromStdString(tm + "Z"), Qt::ISODate));
} }
downloadBtn->setText("CHECK"); downloadBtn->setText(tr("CHECK"));
downloadBtn->setValue("up to date, last checked " + lastUpdate); downloadBtn->setValue(tr("up to date, last checked %1").arg(lastUpdate));
} }
downloadBtn->setEnabled(true); downloadBtn->setEnabled(true);
} }

@ -1,5 +1,6 @@
#pragma once #pragma once
#include <QButtonGroup>
#include <QFrame> #include <QFrame>
#include <QHBoxLayout> #include <QHBoxLayout>
#include <QLabel> #include <QLabel>
@ -60,7 +61,7 @@ public:
public slots: public slots:
void showDescription() { void showDescription() {
description->setVisible(true); description->setVisible(true);
}; }
signals: signals:
void showDescriptionEvent(); void showDescriptionEvent();
@ -106,7 +107,7 @@ signals:
void clicked(); void clicked();
public slots: public slots:
void setEnabled(bool enabled) { btn.setEnabled(enabled); }; void setEnabled(bool enabled) { btn.setEnabled(enabled); }
private: private:
QPushButton btn; QPushButton btn;
@ -163,7 +164,7 @@ public:
void setConfirmation(bool _confirm, bool _store_confirm) { void setConfirmation(bool _confirm, bool _store_confirm) {
confirm = _confirm; confirm = _confirm;
store_confirm = _store_confirm; store_confirm = _store_confirm;
}; }
void setActiveIcon(const QString &icon) { void setActiveIcon(const QString &icon) {
active_icon_pixmap = QPixmap(icon).scaledToWidth(80, Qt::SmoothTransformation); active_icon_pixmap = QPixmap(icon).scaledToWidth(80, Qt::SmoothTransformation);
@ -175,11 +176,11 @@ public:
toggle.togglePosition(); toggle.togglePosition();
setIcon(state); setIcon(state);
} }
}; }
void showEvent(QShowEvent *event) override { void showEvent(QShowEvent *event) override {
refresh(); refresh();
}; }
private: private:
void setIcon(bool state) { void setIcon(bool state) {
@ -188,7 +189,7 @@ private:
} else if (!icon_pixmap.isNull()) { } else if (!icon_pixmap.isNull()) {
icon_label->setPixmap(icon_pixmap); icon_label->setPixmap(icon_pixmap);
} }
}; }
std::string key; std::string key;
Params params; Params params;
@ -197,6 +198,55 @@ private:
bool store_confirm = false; bool store_confirm = false;
}; };
class ButtonParamControl : public AbstractControl {
Q_OBJECT
public:
ButtonParamControl(const QString &param, const QString &title, const QString &desc, const QString &icon,
const std::vector<QString> &button_texts, const int minimum_button_width = 225) : AbstractControl(title, desc, icon) {
const QString style = R"(
QPushButton {
border-radius: 50px;
font-size: 40px;
font-weight: 500;
height:100px;
padding: 0 25 0 25;
color: #E4E4E4;
background-color: #393939;
}
QPushButton:pressed {
background-color: #4a4a4a;
}
QPushButton:checked {
background-color: #33Ab4C;
}
)";
key = param.toStdString();
int value = atoi(params.get(key).c_str());
QButtonGroup *button_group = new QButtonGroup(this);
button_group->setExclusive(true);
for (int i = 0; i < button_texts.size(); i++) {
QPushButton *button = new QPushButton(button_texts[i], this);
button->setCheckable(true);
button->setChecked(i == value);
button->setStyleSheet(style);
button->setMinimumWidth(minimum_button_width);
hlayout->addWidget(button);
button_group->addButton(button, i);
}
QObject::connect(button_group, QOverload<int, bool>::of(&QButtonGroup::buttonToggled), [=](int id, bool checked) {
if (checked) {
params.put(key, std::to_string(id));
}
});
}
private:
std::string key;
Params params;
};
class ListWidget : public QWidget { class ListWidget : public QWidget {
Q_OBJECT Q_OBJECT
public: public:
@ -236,7 +286,7 @@ class LayoutWidget : public QWidget {
public: public:
LayoutWidget(QLayout *l, QWidget *parent = nullptr) : QWidget(parent) { LayoutWidget(QLayout *l, QWidget *parent = nullptr) : QWidget(parent) {
setLayout(l); setLayout(l);
}; }
}; };
class ClickableWidget : public QWidget { class ClickableWidget : public QWidget {

@ -858,6 +858,26 @@ This may take up to a minute.</source>
<source>Uninstall</source> <source>Uninstall</source>
<translation>Deinstallieren</translation> <translation>Deinstallieren</translation>
</message> </message>
<message>
<source>failed to check for update</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>up to date, last checked %1</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>DOWNLOAD</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>update available</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>never</source>
<translation type="unfinished"></translation>
</message>
</context> </context>
<context> <context>
<name>SshControl</name> <name>SshControl</name>
@ -1036,6 +1056,26 @@ This may take up to a minute.</source>
<source>On this car, openpilot defaults to the car&apos;s built-in ACC instead of openpilot&apos;s longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha.</source> <source>On this car, openpilot defaults to the car&apos;s built-in ACC instead of openpilot&apos;s longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha.</source>
<translation type="unfinished"></translation> <translation type="unfinished"></translation>
</message> </message>
<message>
<source>Aggressive</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Standard</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Relaxed</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Driving Personality</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Standard is recommended. In aggressive mode, openpilot will follow lead cars closer and be more aggressive with the gas and brake. In relaxed mode openpilot will stay further away from lead cars.</source>
<translation type="unfinished"></translation>
</message>
</context> </context>
<context> <context>
<name>Updater</name> <name>Updater</name>

@ -854,6 +854,26 @@ This may take up to a minute.</source>
<source>Uninstall</source> <source>Uninstall</source>
<translation></translation> <translation></translation>
</message> </message>
<message>
<source>failed to check for update</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>up to date, last checked %1</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>DOWNLOAD</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>update available</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>never</source>
<translation type="unfinished"></translation>
</message>
</context> </context>
<context> <context>
<name>SshControl</name> <name>SshControl</name>
@ -1030,6 +1050,26 @@ This may take up to a minute.</source>
<source>On this car, openpilot defaults to the car&apos;s built-in ACC instead of openpilot&apos;s longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha.</source> <source>On this car, openpilot defaults to the car&apos;s built-in ACC instead of openpilot&apos;s longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha.</source>
<translation type="unfinished"></translation> <translation type="unfinished"></translation>
</message> </message>
<message>
<source>Aggressive</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Standard</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Relaxed</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Driving Personality</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Standard is recommended. In aggressive mode, openpilot will follow lead cars closer and be more aggressive with the gas and brake. In relaxed mode openpilot will stay further away from lead cars.</source>
<translation type="unfinished"></translation>
</message>
</context> </context>
<context> <context>
<name>Updater</name> <name>Updater</name>

@ -855,6 +855,26 @@ This may take up to a minute.</source>
<source>Uninstall</source> <source>Uninstall</source>
<translation></translation> <translation></translation>
</message> </message>
<message>
<source>failed to check for update</source>
<translation> </translation>
</message>
<message>
<source>up to date, last checked %1</source>
<translation> , %1</translation>
</message>
<message>
<source>DOWNLOAD</source>
<translation></translation>
</message>
<message>
<source>update available</source>
<translation> </translation>
</message>
<message>
<source>never</source>
<translation> </translation>
</message>
</context> </context>
<context> <context>
<name>SshControl</name> <name>SshControl</name>
@ -1031,6 +1051,26 @@ This may take up to a minute.</source>
<source>On this car, openpilot defaults to the car&apos;s built-in ACC instead of openpilot&apos;s longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha.</source> <source>On this car, openpilot defaults to the car&apos;s built-in ACC instead of openpilot&apos;s longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha.</source>
<translation> openpilot ACC로 . openpilot . openpilot .</translation> <translation> openpilot ACC로 . openpilot . openpilot .</translation>
</message> </message>
<message>
<source>Aggressive</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Standard</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Relaxed</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Driving Personality</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Standard is recommended. In aggressive mode, openpilot will follow lead cars closer and be more aggressive with the gas and brake. In relaxed mode openpilot will stay further away from lead cars.</source>
<translation type="unfinished"></translation>
</message>
</context> </context>
<context> <context>
<name>Updater</name> <name>Updater</name>

@ -859,6 +859,26 @@ Isso pode levar até um minuto.</translation>
<source>Uninstall</source> <source>Uninstall</source>
<translation>Desinstalar</translation> <translation>Desinstalar</translation>
</message> </message>
<message>
<source>failed to check for update</source>
<translation>falha ao verificar por atualizações</translation>
</message>
<message>
<source>up to date, last checked %1</source>
<translation>atualizado, última verificação %1</translation>
</message>
<message>
<source>DOWNLOAD</source>
<translation>BAIXAR</translation>
</message>
<message>
<source>update available</source>
<translation>atualização disponível</translation>
</message>
<message>
<source>never</source>
<translation>nunca</translation>
</message>
</context> </context>
<context> <context>
<name>SshControl</name> <name>SshControl</name>
@ -1035,6 +1055,26 @@ Isso pode levar até um minuto.</translation>
<source>On this car, openpilot defaults to the car&apos;s built-in ACC instead of openpilot&apos;s longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha.</source> <source>On this car, openpilot defaults to the car&apos;s built-in ACC instead of openpilot&apos;s longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha.</source>
<translation>Neste carro, o openpilot tem como padrão o ACC embutido do carro em vez do controle longitudinal do openpilot. Habilite isso para alternar para o controle longitudinal openpilot. Recomenda-se ativar o modo Experimental ao ativar o alfa de controle longitudinal openpilot.</translation> <translation>Neste carro, o openpilot tem como padrão o ACC embutido do carro em vez do controle longitudinal do openpilot. Habilite isso para alternar para o controle longitudinal openpilot. Recomenda-se ativar o modo Experimental ao ativar o alfa de controle longitudinal openpilot.</translation>
</message> </message>
<message>
<source>Aggressive</source>
<translation>Disputador</translation>
</message>
<message>
<source>Standard</source>
<translation>Neutro</translation>
</message>
<message>
<source>Relaxed</source>
<translation>Calmo</translation>
</message>
<message>
<source>Driving Personality</source>
<translation>Personalidade de Condução</translation>
</message>
<message>
<source>Standard is recommended. In aggressive mode, openpilot will follow lead cars closer and be more aggressive with the gas and brake. In relaxed mode openpilot will stay further away from lead cars.</source>
<translation>Neutro é o recomendado. No modo disputador o openpilot seguirá o carro da frente mais de perto e será mais agressivo com a aceleração e frenagem. No modo calmo o openpilot se manterá mais longe do carro da frente.</translation>
</message>
</context> </context>
<context> <context>
<name>Updater</name> <name>Updater</name>

@ -852,6 +852,26 @@ This may take up to a minute.</source>
<source>Uninstall</source> <source>Uninstall</source>
<translation></translation> <translation></translation>
</message> </message>
<message>
<source>failed to check for update</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>up to date, last checked %1</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>DOWNLOAD</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>update available</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>never</source>
<translation type="unfinished"></translation>
</message>
</context> </context>
<context> <context>
<name>SshControl</name> <name>SshControl</name>
@ -1028,6 +1048,26 @@ This may take up to a minute.</source>
<source>On this car, openpilot defaults to the car&apos;s built-in ACC instead of openpilot&apos;s longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha.</source> <source>On this car, openpilot defaults to the car&apos;s built-in ACC instead of openpilot&apos;s longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha.</source>
<translation type="unfinished"></translation> <translation type="unfinished"></translation>
</message> </message>
<message>
<source>Aggressive</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Standard</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Relaxed</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Driving Personality</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Standard is recommended. In aggressive mode, openpilot will follow lead cars closer and be more aggressive with the gas and brake. In relaxed mode openpilot will stay further away from lead cars.</source>
<translation type="unfinished"></translation>
</message>
</context> </context>
<context> <context>
<name>Updater</name> <name>Updater</name>

@ -854,6 +854,26 @@ This may take up to a minute.</source>
<source>Uninstall</source> <source>Uninstall</source>
<translation></translation> <translation></translation>
</message> </message>
<message>
<source>failed to check for update</source>
<translation></translation>
</message>
<message>
<source>up to date, last checked %1</source>
<translation> %1</translation>
</message>
<message>
<source>DOWNLOAD</source>
<translation></translation>
</message>
<message>
<source>update available</source>
<translation></translation>
</message>
<message>
<source>never</source>
<translation></translation>
</message>
</context> </context>
<context> <context>
<name>SshControl</name> <name>SshControl</name>
@ -1020,15 +1040,35 @@ This may take up to a minute.</source>
</message> </message>
<message> <message>
<source>openpilot Longitudinal Control (Alpha)</source> <source>openpilot Longitudinal Control (Alpha)</source>
<translation type="unfinished"></translation> <translation>openpilot (Alpha )</translation>
</message> </message>
<message> <message>
<source>WARNING: openpilot longitudinal control is in alpha for this car and will disable Automatic Emergency Braking (AEB).</source> <source>WARNING: openpilot longitudinal control is in alpha for this car and will disable Automatic Emergency Braking (AEB).</source>
<translation type="unfinished"></translation> <translation> Openpilot Alpha 使AEB</translation>
</message> </message>
<message> <message>
<source>On this car, openpilot defaults to the car&apos;s built-in ACC instead of openpilot&apos;s longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha.</source> <source>On this car, openpilot defaults to the car&apos;s built-in ACC instead of openpilot&apos;s longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha.</source>
<translation type="unfinished"></translation> <translation>Openpilot 使ACC Openpilot Openpilot Openpilot Alpha Experimental mode</translation>
</message>
<message>
<source>Aggressive</source>
<translation></translation>
</message>
<message>
<source>Standard</source>
<translation></translation>
</message>
<message>
<source>Relaxed</source>
<translation></translation>
</message>
<message>
<source>Driving Personality</source>
<translation></translation>
</message>
<message>
<source>Standard is recommended. In aggressive mode, openpilot will follow lead cars closer and be more aggressive with the gas and brake. In relaxed mode openpilot will stay further away from lead cars.</source>
<translation>使openpilot openpilot </translation>
</message> </message>
</context> </context>
<context> <context>
@ -1070,23 +1110,23 @@ This may take up to a minute.</source>
<name>WiFiPromptWidget</name> <name>WiFiPromptWidget</name>
<message> <message>
<source>Setup Wi-Fi</source> <source>Setup Wi-Fi</source>
<translation type="unfinished"></translation> <translation> Wi-Fi </translation>
</message> </message>
<message> <message>
<source>Connect to Wi-Fi to upload driving data and help improve openpilot</source> <source>Connect to Wi-Fi to upload driving data and help improve openpilot</source>
<translation type="unfinished"></translation> <translation> Wi-Fi openpilot</translation>
</message> </message>
<message> <message>
<source>Open Settings</source> <source>Open Settings</source>
<translation type="unfinished"></translation> <translation></translation>
</message> </message>
<message> <message>
<source>Uploading training data</source> <source>Uploading training data</source>
<translation type="unfinished"></translation> <translation></translation>
</message> </message>
<message> <message>
<source>Your data is used to train driving models and help improve openpilot</source> <source>Your data is used to train driving models and help improve openpilot</source>
<translation type="unfinished"></translation> <translation> openpilot</translation>
</message> </message>
</context> </context>
<context> <context>

@ -2,9 +2,11 @@
import unittest import unittest
import time import time
import math import math
import threading
from dataclasses import dataclass from dataclasses import dataclass
from tabulate import tabulate from tabulate import tabulate
import cereal.messaging as messaging
from system.hardware import HARDWARE, TICI from system.hardware import HARDWARE, TICI
from system.hardware.tici.power_monitor import get_power from system.hardware.tici.power_monitor import get_power
from selfdrive.manager.process_config import managed_processes from selfdrive.manager.process_config import managed_processes
@ -24,8 +26,22 @@ PROCS = [
Proc('modeld', 0.93, atol=0.2), Proc('modeld', 0.93, atol=0.2),
Proc('dmonitoringmodeld', 0.4), Proc('dmonitoringmodeld', 0.4),
Proc('encoderd', 0.23), Proc('encoderd', 0.23),
Proc('mapsd', 0.05),
Proc('navmodeld', 0.05),
] ]
def send_llk_msg(done):
pm = messaging.PubMaster(['liveLocationKalman'])
msg = messaging.new_message('liveLocationKalman')
msg.liveLocationKalman.positionGeodetic = {'value': [32.7174, -117.16277, 0], 'std': [0., 0., 0.], 'valid': True}
msg.liveLocationKalman.calibratedOrientationNED = {'value': [0., 0., 0.], 'std': [0., 0., 0.], 'valid': True}
msg.liveLocationKalman.status = 'valid'
# Send liveLocationKalman at 20hz
while not done.is_set():
pm.send('liveLocationKalman', msg)
time.sleep(1/20)
class TestPowerDraw(unittest.TestCase): class TestPowerDraw(unittest.TestCase):
@ -46,6 +62,9 @@ class TestPowerDraw(unittest.TestCase):
def test_camera_procs(self): def test_camera_procs(self):
baseline = get_power() baseline = get_power()
done = threading.Event()
thread = threading.Thread(target=send_llk_msg, args=(done,), daemon=True)
thread.start()
prev = baseline prev = baseline
used = {} used = {}
@ -57,6 +76,7 @@ class TestPowerDraw(unittest.TestCase):
used[proc.name] = now - prev used[proc.name] = now - prev
prev = now prev = now
done.set()
manager_cleanup() manager_cleanup()
tab = [] tab = []

@ -437,9 +437,11 @@ void BinaryItemDelegate::drawSignalCell(QPainter *painter, const QStyleOptionVie
auto sig_color = getColor(sig); auto sig_color = getColor(sig);
QColor color = sig_color; QColor color = sig_color;
color.setAlpha(item->bg_color.alpha()); color.setAlpha(item->bg_color.alpha());
painter->fillRect(rc, Qt::white); // Mixing the signal colour with the Base background color to fade it
painter->fillRect(rc, QApplication::palette().color(QPalette::Base));
painter->fillRect(rc, color); painter->fillRect(rc, color);
// Draw edges
color = sig_color.darker(125); color = sig_color.darker(125);
painter->setPen(QPen(color, 1)); painter->setPen(QPen(color, 1));
if (draw_left) painter->drawLine(rc.topLeft(), rc.bottomLeft()); if (draw_left) painter->drawLine(rc.topLeft(), rc.bottomLeft());

@ -213,9 +213,19 @@ void ChartView::updateTitle() {
for (QLegendMarker *marker : chart()->legend()->markers()) { for (QLegendMarker *marker : chart()->legend()->markers()) {
QObject::connect(marker, &QLegendMarker::clicked, this, &ChartView::handleMarkerClicked, Qt::UniqueConnection); QObject::connect(marker, &QLegendMarker::clicked, this, &ChartView::handleMarkerClicked, Qt::UniqueConnection);
} }
// Use CSS to draw titles in the WindowText color
auto tmp = palette().color(QPalette::WindowText);
auto titleColorCss = tmp.name(QColor::HexArgb);
// Draw message details in similar color, but slightly fade it to the background
tmp.setAlpha(180);
auto msgColorCss = tmp.name(QColor::HexArgb);
for (auto &s : sigs) { for (auto &s : sigs) {
auto decoration = s.series->isVisible() ? "none" : "line-through"; auto decoration = s.series->isVisible() ? "none" : "line-through";
s.series->setName(QString("<span style=\"text-decoration:%1\"><b>%2</b> <font color=\"gray\">%3 %4</font></span>").arg(decoration, s.sig->name, msgName(s.msg_id), s.msg_id.toString())); s.series->setName(QString("<span style=\"text-decoration:%1; color:%2\"><b>%3</b> <font color=\"%4\">%5 %6</font></span>")
.arg(decoration, titleColorCss, s.sig->name,
msgColorCss, msgName(s.msg_id), s.msg_id.toString()));
} }
split_chart_act->setEnabled(sigs.size() > 1); split_chart_act->setEnabled(sigs.size() > 1);
resetChartCache(); resetChartCache();

@ -63,7 +63,10 @@ QVariant HistoryLogModel::headerData(int section, Qt::Orientation orientation, i
return "Data"; return "Data";
} }
} else if (role == Qt::BackgroundRole && section > 0 && show_signals) { } else if (role == Qt::BackgroundRole && section > 0 && show_signals) {
return QBrush(getColor(sigs[section - 1])); // Alpha-blend the signal color with the background to ensure contrast
QColor sigColor = getColor(sigs[section - 1]);
sigColor.setAlpha(128);
return QBrush(sigColor);
} }
} }
return {}; return {};

@ -459,7 +459,10 @@ SignalView::SignalView(ChartsWidget *charts, QWidget *parent) : charts(charts),
tree->header()->setSectionResizeMode(0, QHeaderView::ResizeToContents); tree->header()->setSectionResizeMode(0, QHeaderView::ResizeToContents);
tree->header()->setStretchLastSection(true); tree->header()->setStretchLastSection(true);
tree->setMinimumHeight(300); tree->setMinimumHeight(300);
tree->setStyleSheet("QSpinBox{background-color:white;border:none;} QLineEdit{background-color:white;}");
// Use a distinctive background for the whole row containing a QSpinBox or QLineEdit
QString nodeBgColor = palette().color(QPalette::AlternateBase).name(QColor::HexArgb);
tree->setStyleSheet(QString("QSpinBox{background-color:%1;border:none;} QLineEdit{background-color:%1;}").arg(nodeBgColor));
QVBoxLayout *main_layout = new QVBoxLayout(this); QVBoxLayout *main_layout = new QVBoxLayout(this);
main_layout->setContentsMargins(0, 0, 0, 0); main_layout->setContentsMargins(0, 0, 0, 0);

@ -1,3 +1,4 @@
import bz2
import datetime import datetime
TIME_FMT = "%Y-%m-%d--%H-%M-%S" TIME_FMT = "%Y-%m-%d--%H-%M-%S"
@ -13,8 +14,19 @@ class RE:
EXPLORER_FILE = r'^(?P<segment_name>{})--(?P<file_name>[a-z]+\.[a-z0-9]+)$'.format(SEGMENT_NAME) EXPLORER_FILE = r'^(?P<segment_name>{})--(?P<file_name>[a-z]+\.[a-z0-9]+)$'.format(SEGMENT_NAME)
OP_SEGMENT_DIR = r'^(?P<segment_name>{})$'.format(SEGMENT_NAME) OP_SEGMENT_DIR = r'^(?P<segment_name>{})$'.format(SEGMENT_NAME)
def timestamp_to_datetime(t: str) -> datetime.datetime: def timestamp_to_datetime(t: str) -> datetime.datetime:
""" """
Convert an openpilot route timestamp to a python datetime Convert an openpilot route timestamp to a python datetime
""" """
return datetime.datetime.strptime(t, TIME_FMT) return datetime.datetime.strptime(t, TIME_FMT)
def save_log(dest, log_msgs, compress=True):
dat = b"".join(msg.as_builder().to_bytes() for msg in log_msgs)
if compress:
dat = bz2.compress(dat)
with open(dest, "wb") as f:
f.write(dat)

@ -11,10 +11,10 @@ import requests
import argparse import argparse
from common.basedir import BASEDIR from common.basedir import BASEDIR
from selfdrive.test.process_replay.compare_logs import save_log
from selfdrive.test.openpilotci import get_url from selfdrive.test.openpilotci import get_url
from tools.lib.logreader import LogReader from tools.lib.logreader import LogReader
from tools.lib.route import Route, SegmentName from tools.lib.route import Route, SegmentName
from tools.lib.helpers import save_log
from urllib.parse import urlparse, parse_qs from urllib.parse import urlparse, parse_qs
juggle_dir = os.path.dirname(os.path.realpath(__file__)) juggle_dir = os.path.dirname(os.path.realpath(__file__))

Loading…
Cancel
Save