From bd9966c4777a7b4393d65cc0f62d726a9fdf1ff1 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 31 Aug 2022 17:54:21 -0700 Subject: [PATCH 001/152] test_fw_query_on_routes: find first non-none path (#25628) find first non-none path --- selfdrive/debug/test_fw_query_on_routes.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/debug/test_fw_query_on_routes.py b/selfdrive/debug/test_fw_query_on_routes.py index 6cc7da5f1b..595e25e8c3 100755 --- a/selfdrive/debug/test_fw_query_on_routes.py +++ b/selfdrive/debug/test_fw_query_on_routes.py @@ -56,7 +56,7 @@ if __name__ == "__main__": qlog_path = f"cd:/{dongle_id}/{time}/0/qlog.bz2" else: route = Route(route) - qlog_path = route.qlog_paths()[0] + qlog_path = next((p for p in route.qlog_paths() if p is not None), None) if qlog_path is None: continue From 28cb1897cb8be80b35b1ce7573066fb36b01d2d7 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 31 Aug 2022 21:13:53 -0700 Subject: [PATCH 002/152] USB power mode cleanup (#25619) * first pass at usb power mode cleanup * fix build * a sneaky one * little more * fix build * bump pnada * remove that * power monitoring cleanup * fix tests * bump submodules --- cereal | 2 +- panda | 2 +- selfdrive/boardd/boardd.cc | 32 ++----------------- selfdrive/boardd/panda.cc | 4 --- selfdrive/boardd/panda.h | 1 - selfdrive/thermald/power_monitoring.py | 29 +++++------------ .../thermald/tests/test_power_monitoring.py | 20 ++++++------ selfdrive/thermald/thermald.py | 9 +----- system/hardware/base.py | 4 --- system/hardware/pc/hardware.py | 5 +-- system/hardware/tici/hardware.py | 1 - 11 files changed, 24 insertions(+), 85 deletions(-) diff --git a/cereal b/cereal index d05d3cbd0e..d3a943ef66 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit d05d3cbd0e1243c3fef63c58ab15aeb7508159a7 +Subproject commit d3a943ef660dd29f73700806ee0baf1d5aff6834 diff --git a/panda b/panda index 6d2e2bde86..13d64d4cc3 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 6d2e2bde861a237593740526b466d17d43849a17 +Subproject commit 13d64d4cc38295401ff1ffcf6a233a4b9625fd9f diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 59579a7fcf..47bff1c5b6 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -197,12 +197,6 @@ Panda *usb_connect(std::string serial="", uint32_t index=0) { } //panda->enable_deepsleep(); - // power on charging, only the first time. Panda can also change mode and it causes a brief disconneciton -#ifndef __x86_64__ - static std::once_flag connected_once; - std::call_once(connected_once, &Panda::set_usb_power_mode, panda, cereal::PeripheralState::UsbPowerMode::CDP); -#endif - sync_time(panda.get(), SyncTimeDir::FROM_PANDA); return panda.release(); } @@ -391,13 +385,6 @@ std::optional send_panda_states(PubMaster *pm, const std::vector } void send_peripheral_state(PubMaster *pm, Panda *panda) { - auto pandaState_opt = panda->get_state(); - if (!pandaState_opt) { - return; - } - - health_t pandaState = *pandaState_opt; - // build msg MessageBuilder msg; auto evt = msg.initEvent(); @@ -415,7 +402,6 @@ void send_peripheral_state(PubMaster *pm, Panda *panda) { } uint16_t fan_speed_rpm = panda->get_fan_speed(); - ps.setUsbPowerMode(cereal::PeripheralState::UsbPowerMode(pandaState.usb_power_mode_pkt)); ps.setFanSpeedRpm(fan_speed_rpm); pm->send("peripheralState", msg); @@ -491,7 +477,6 @@ void peripheral_control_thread(Panda *panda) { uint16_t prev_fan_speed = 999; uint16_t ir_pwr = 0; uint16_t prev_ir_pwr = 999; - bool prev_charging_disabled = false; unsigned int cnt = 0; FirstOrderFilter integ_lines_filter(0, 30.0, 0.05); @@ -500,23 +485,9 @@ void peripheral_control_thread(Panda *panda) { cnt++; sm.update(1000); // TODO: what happens if EINTR is sent while in sm.update? - if (!Hardware::PC() && sm.updated("deviceState")) { - // Charging mode - bool charging_disabled = sm["deviceState"].getDeviceState().getChargingDisabled(); - if (charging_disabled != prev_charging_disabled) { - if (charging_disabled) { - panda->set_usb_power_mode(cereal::PeripheralState::UsbPowerMode::CLIENT); - LOGW("TURN OFF CHARGING!\n"); - } else { - panda->set_usb_power_mode(cereal::PeripheralState::UsbPowerMode::CDP); - LOGW("TURN ON CHARGING!\n"); - } - prev_charging_disabled = charging_disabled; - } - } - // Other pandas don't have fan/IR to control if (panda->hw_type != cereal::PandaState::PandaType::UNO && panda->hw_type != cereal::PandaState::PandaType::DOS) continue; + if (sm.updated("deviceState")) { // Fan speed uint16_t fan_speed = sm["deviceState"].getDeviceState().getFanSpeedPercentDesired(); @@ -541,6 +512,7 @@ void peripheral_control_thread(Panda *panda) { ir_pwr = 100.0 * (MIN_IR_POWER + ((cur_integ_lines - CUTOFF_IL) * (MAX_IR_POWER - MIN_IR_POWER) / (SATURATE_IL - CUTOFF_IL))); } } + // Disable ir_pwr on front frame timeout uint64_t cur_t = nanos_since_boot(); if (cur_t - last_front_frame_t > 1e9) { diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index d90c4cdab2..685dabd873 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -342,10 +342,6 @@ void Panda::enable_deepsleep() { usb_write(0xfb, 0, 0); } -void Panda::set_usb_power_mode(cereal::PeripheralState::UsbPowerMode power_mode) { - usb_write(0xe6, (uint16_t)power_mode, 0); -} - void Panda::send_heartbeat(bool engaged) { usb_write(0xf3, engaged, 0); } diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h index 23a10d5850..1cefc3cb4d 100644 --- a/selfdrive/boardd/panda.h +++ b/selfdrive/boardd/panda.h @@ -86,7 +86,6 @@ class Panda { std::optional get_serial(); void set_power_saving(bool power_saving); void enable_deepsleep(); - void set_usb_power_mode(cereal::PeripheralState::UsbPowerMode power_mode); void send_heartbeat(bool engaged); void set_can_speed_kbps(uint16_t bus, uint16_t speed); void set_data_speed_kbps(uint16_t bus, uint16_t speed); diff --git a/selfdrive/thermald/power_monitoring.py b/selfdrive/thermald/power_monitoring.py index 9f009d3265..7834569088 100644 --- a/selfdrive/thermald/power_monitoring.py +++ b/selfdrive/thermald/power_monitoring.py @@ -108,32 +108,19 @@ class PowerMonitoring: def get_car_battery_capacity(self) -> int: return int(self.car_battery_capacity_uWh) - # See if we need to disable charging - def should_disable_charging(self, ignition: bool, in_car: bool, offroad_timestamp: Optional[float]) -> bool: - if offroad_timestamp is None: - return False - - now = sec_since_boot() - disable_charging = False - disable_charging |= (now - offroad_timestamp) > MAX_TIME_OFFROAD_S - disable_charging |= (self.car_voltage_mV < (VBATT_PAUSE_CHARGING * 1e3)) and (self.car_voltage_instant_mV > (VBATT_INSTANT_PAUSE_CHARGING * 1e3)) - disable_charging |= (self.car_battery_capacity_uWh <= 0) - disable_charging &= not ignition - disable_charging &= (not self.params.get_bool("DisablePowerDown")) - disable_charging &= in_car - disable_charging |= self.params.get_bool("ForcePowerDown") - return disable_charging - # See if we need to shutdown - def should_shutdown(self, peripheralState, ignition, in_car, offroad_timestamp, started_seen): + def should_shutdown(self, ignition: bool, in_car: bool, offroad_timestamp: Optional[float], started_seen: bool): if offroad_timestamp is None: return False now = sec_since_boot() - panda_charging = (peripheralState.usbPowerMode != log.PeripheralState.UsbPowerMode.client) - should_shutdown = False - # Wait until we have shut down charging before powering down - should_shutdown |= (not panda_charging and self.should_disable_charging(ignition, in_car, offroad_timestamp)) + should_shutdown |= (now - offroad_timestamp) > MAX_TIME_OFFROAD_S + should_shutdown |= (self.car_voltage_mV < (VBATT_PAUSE_CHARGING * 1e3)) and (self.car_voltage_instant_mV > (VBATT_INSTANT_PAUSE_CHARGING * 1e3)) + should_shutdown |= (self.car_battery_capacity_uWh <= 0) + should_shutdown &= not ignition + should_shutdown &= (not self.params.get_bool("DisablePowerDown")) + should_shutdown &= in_car + should_shutdown |= self.params.get_bool("ForcePowerDown") should_shutdown &= started_seen or (now > MIN_ON_TIME_S) return should_shutdown diff --git a/selfdrive/thermald/tests/test_power_monitoring.py b/selfdrive/thermald/tests/test_power_monitoring.py index adcdaf427d..5d7463d455 100755 --- a/selfdrive/thermald/tests/test_power_monitoring.py +++ b/selfdrive/thermald/tests/test_power_monitoring.py @@ -129,8 +129,8 @@ class TestPowerMonitoring(unittest.TestCase): while ssb <= start_time + MOCKED_MAX_OFFROAD_TIME: pm.calculate(peripheralState, ignition) if (ssb - start_time) % 1000 == 0 and ssb < start_time + MOCKED_MAX_OFFROAD_TIME: - self.assertFalse(pm.should_disable_charging(ignition, True, start_time)) - self.assertTrue(pm.should_disable_charging(ignition, True, start_time)) + self.assertFalse(pm.should_shutdown(ignition, True, start_time, False)) + self.assertTrue(pm.should_shutdown(ignition, True, start_time, False)) # Test to check policy of stopping charging when the car voltage is too low @parameterized.expand(ALL_PANDA_TYPES) @@ -145,8 +145,8 @@ class TestPowerMonitoring(unittest.TestCase): for i in range(TEST_TIME): pm.calculate(peripheralState, ignition) if i % 10 == 0: - self.assertEqual(pm.should_disable_charging(ignition, True, ssb), (pm.car_voltage_mV < VBATT_PAUSE_CHARGING*1e3)) - self.assertTrue(pm.should_disable_charging(ignition, True, ssb)) + self.assertEqual(pm.should_shutdown(ignition, True, ssb, True), (pm.car_voltage_mV < VBATT_PAUSE_CHARGING*1e3)) + self.assertTrue(pm.should_shutdown(ignition, True, ssb, True)) # Test to check policy of not stopping charging when DisablePowerDown is set def test_disable_power_down(self): @@ -161,8 +161,8 @@ class TestPowerMonitoring(unittest.TestCase): for i in range(TEST_TIME): pm.calculate(peripheralState, ignition) if i % 10 == 0: - self.assertFalse(pm.should_disable_charging(ignition, True, ssb)) - self.assertFalse(pm.should_disable_charging(ignition, True, ssb)) + self.assertFalse(pm.should_shutdown(ignition, True, ssb, False)) + self.assertFalse(pm.should_shutdown(ignition, True, ssb, False)) # Test to check policy of not stopping charging when ignition def test_ignition(self): @@ -176,8 +176,8 @@ class TestPowerMonitoring(unittest.TestCase): for i in range(TEST_TIME): pm.calculate(peripheralState, ignition) if i % 10 == 0: - self.assertFalse(pm.should_disable_charging(ignition, True, ssb)) - self.assertFalse(pm.should_disable_charging(ignition, True, ssb)) + self.assertFalse(pm.should_shutdown(ignition, True, ssb, False)) + self.assertFalse(pm.should_shutdown(ignition, True, ssb, False)) # Test to check policy of not stopping charging when harness is not connected def test_harness_connection(self): @@ -192,8 +192,8 @@ class TestPowerMonitoring(unittest.TestCase): for i in range(TEST_TIME): pm.calculate(peripheralState, ignition) if i % 10 == 0: - self.assertFalse(pm.should_disable_charging(ignition, False,ssb)) - self.assertFalse(pm.should_disable_charging(ignition, False, ssb)) + self.assertFalse(pm.should_shutdown(ignition, False, ssb, False)) + self.assertFalse(pm.should_shutdown(ignition, False, ssb, False)) if __name__ == "__main__": unittest.main() diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index c765af664f..5c2fbd6825 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -177,7 +177,6 @@ def thermald_thread(end_event, hw_queue): modem_temps=[], ) - current_filter = FirstOrderFilter(0., CURRENT_TAU, DT_TRML) temp_filter = FirstOrderFilter(0., TEMP_TAU, DT_TRML) should_start_prev = False in_car = False @@ -239,8 +238,6 @@ def thermald_thread(end_event, hw_queue): msg.deviceState.modemTempC = last_hw_state.modem_temps msg.deviceState.screenBrightnessPercent = HARDWARE.get_screen_brightness() - msg.deviceState.usbOnline = HARDWARE.get_usb_present() - current_filter.update(msg.deviceState.batteryCurrent / 1e6) max_comp_temp = temp_filter.update( max(max(msg.deviceState.cpuTempC), msg.deviceState.memoryTempC, max(msg.deviceState.gpuTempC)) @@ -350,15 +347,11 @@ def thermald_thread(end_event, hw_queue): statlog.sample("som_power_draw", som_power_draw) msg.deviceState.somPowerDrawW = som_power_draw - # Check if we need to disable charging (handled by boardd) - msg.deviceState.chargingDisabled = power_monitor.should_disable_charging(onroad_conditions["ignition"], in_car, off_ts) - # Check if we need to shut down - if power_monitor.should_shutdown(peripheralState, onroad_conditions["ignition"], in_car, off_ts, started_seen): + if power_monitor.should_shutdown(onroad_conditions["ignition"], in_car, off_ts, started_seen): cloudlog.warning(f"shutting device down, offroad since {off_ts}") params.put_bool("DoShutdown", True) - msg.deviceState.chargingError = current_filter.x > 0. and msg.deviceState.batteryPercent < 90 # if current is positive, then battery is being discharged msg.deviceState.started = started_ts is not None msg.deviceState.startedMonoTime = int(1e9*(started_ts or 0)) diff --git a/system/hardware/base.py b/system/hardware/base.py index c9c02f3a59..31df1babe0 100644 --- a/system/hardware/base.py +++ b/system/hardware/base.py @@ -78,10 +78,6 @@ class HardwareBase(ABC): def set_bandwidth_limit(upload_speed_kbps: int, download_speed_kbps: int) -> None: pass - @abstractmethod - def get_usb_present(self): - pass - @abstractmethod def get_current_power_draw(self): pass diff --git a/system/hardware/pc/hardware.py b/system/hardware/pc/hardware.py index 60d14e4a6b..564f9e483a 100644 --- a/system/hardware/pc/hardware.py +++ b/system/hardware/pc/hardware.py @@ -50,12 +50,9 @@ class Pc(HardwareBase): def get_network_strength(self, network_type): return NetworkStrength.unknown - def get_usb_present(self): - return False - def get_current_power_draw(self): return 0 - + def get_som_power_draw(self): return 0 diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py index 14a7101c61..340093b604 100644 --- a/system/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -372,7 +372,6 @@ class Tici(HardwareBase): return (self.read_param_file("/sys/class/power_supply/bms/voltage_now", int) * self.read_param_file("/sys/class/power_supply/bms/current_now", int) / 1e12) def shutdown(self): - # Note that for this to work and have the device stay powered off, the panda needs to be in UsbPowerMode::CLIENT! os.system("sudo poweroff") def get_thermal_config(self): From 4bb399ba3c13953680522707bba662527fa771b7 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 31 Aug 2022 23:12:26 -0700 Subject: [PATCH 003/152] pigeond tests (#25630) * start pigeond tests * sm checks * add some types * little more Co-authored-by: Comma Device --- Jenkinsfile | 3 +- common/gpio.py | 13 +++- selfdrive/sensord/{test => }/__init__.py | 0 selfdrive/sensord/pigeond.py | 59 ++++++++--------- selfdrive/sensord/tests/__init__.py | 0 selfdrive/sensord/tests/test_pigeond.py | 63 +++++++++++++++++++ .../sensord/{test => tests}/test_sensord.py | 0 .../sensord/{test => tests}/ttff_test.py | 0 8 files changed, 107 insertions(+), 31 deletions(-) rename selfdrive/sensord/{test => }/__init__.py (100%) create mode 100644 selfdrive/sensord/tests/__init__.py create mode 100755 selfdrive/sensord/tests/test_pigeond.py rename selfdrive/sensord/{test => tests}/test_sensord.py (100%) rename selfdrive/sensord/{test => tests}/ttff_test.py (100%) diff --git a/Jenkinsfile b/Jenkinsfile index 6b05e81d79..c4038090e1 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -131,7 +131,8 @@ pipeline { ["test boardd loopback", "python selfdrive/boardd/tests/test_boardd_loopback.py"], ["test loggerd", "python selfdrive/loggerd/tests/test_loggerd.py"], ["test encoder", "LD_LIBRARY_PATH=/usr/local/lib python selfdrive/loggerd/tests/test_encoder.py"], - ["test sensord", "python selfdrive/sensord/test/test_sensord.py"], + ["test sensord", "python selfdrive/sensord/tests/test_sensord.py"], + ["test pigeond", "python selfdrive/sensord/tests/test_pigeond.py"], ]) } } diff --git a/common/gpio.py b/common/gpio.py index 32e5ca86cc..260f8898a1 100644 --- a/common/gpio.py +++ b/common/gpio.py @@ -1,3 +1,5 @@ +from typing import Optional + def gpio_init(pin: int, output: bool) -> None: try: with open(f"/sys/class/gpio/gpio{pin}/direction", 'wb') as f: @@ -5,10 +7,19 @@ def gpio_init(pin: int, output: bool) -> None: except Exception as e: print(f"Failed to set gpio {pin} direction: {e}") - def gpio_set(pin: int, high: bool) -> None: try: with open(f"/sys/class/gpio/gpio{pin}/value", 'wb') as f: f.write(b"1" if high else b"0") except Exception as e: print(f"Failed to set gpio {pin} value: {e}") + +def gpio_read(pin: int) -> Optional[bool]: + val = None + try: + with open(f"/sys/class/gpio/gpio{pin}/value", 'rb') as f: + val = bool(int(f.read().strip())) + except Exception as e: + print(f"Failed to set gpio {pin} value: {e}") + + return val diff --git a/selfdrive/sensord/test/__init__.py b/selfdrive/sensord/__init__.py similarity index 100% rename from selfdrive/sensord/test/__init__.py rename to selfdrive/sensord/__init__.py diff --git a/selfdrive/sensord/pigeond.py b/selfdrive/sensord/pigeond.py index 95a27189d0..e38e2d4c33 100755 --- a/selfdrive/sensord/pigeond.py +++ b/selfdrive/sensord/pigeond.py @@ -1,5 +1,4 @@ #!/usr/bin/env python3 - import sys import time import signal @@ -8,6 +7,7 @@ import struct import requests import urllib.parse from datetime import datetime +from typing import List, Optional from cereal import messaging from common.params import Params @@ -25,7 +25,7 @@ UBLOX_SOS_NACK = b"\xb5\x62\x09\x14\x08\x00\x02\x00\x00\x00\x00\x00\x00\x00" UBLOX_BACKUP_RESTORE_MSG = b"\xb5\x62\x09\x14\x08\x00\x03" UBLOX_ASSIST_ACK = b"\xb5\x62\x13\x60\x08\x00" -def set_power(enabled): +def set_power(enabled: bool) -> None: gpio_init(GPIO.UBLOX_SAFEBOOT_N, True) gpio_init(GPIO.UBLOX_PWR_EN, True) gpio_init(GPIO.UBLOX_RST_N, True) @@ -35,14 +35,14 @@ def set_power(enabled): gpio_set(GPIO.UBLOX_RST_N, enabled) -def add_ubx_checksum(msg): +def add_ubx_checksum(msg: bytes) -> bytes: A = B = 0 for b in msg[2:]: A = (A + b) % 256 B = (B + A) % 256 return msg + bytes([A, B]) -def get_assistnow_messages(token): +def get_assistnow_messages(token: bytes) -> List[bytes]: # make request # TODO: implement adding the last known location r = requests.get("https://online-live2.services.u-blox.com/GetOnlineData.ashx", params=urllib.parse.urlencode({ @@ -64,14 +64,13 @@ def get_assistnow_messages(token): class TTYPigeon(): - def __init__(self, path): - self.path = path + def __init__(self): self.tty = serial.VTIMESerial(UBLOX_TTY, baudrate=9600, timeout=0) - def send(self, dat): + def send(self, dat: bytes) -> None: self.tty.write(dat) - def receive(self): + def receive(self) -> bytes: dat = b'' while len(dat) < 0x1000: d = self.tty.read(0x40) @@ -80,10 +79,10 @@ class TTYPigeon(): break return dat - def set_baud(self, baud): + def set_baud(self, baud: int) -> None: self.tty.baudrate = baud - def wait_for_ack(self, ack=UBLOX_ACK, nack=UBLOX_NACK, timeout=0.5): + def wait_for_ack(self, ack: bytes = UBLOX_ACK, nack: bytes = UBLOX_NACK, timeout: float = 0.5) -> bool: dat = b'' st = time.monotonic() while True: @@ -99,11 +98,11 @@ class TTYPigeon(): raise TimeoutError('No response from ublox') time.sleep(0.001) - def send_with_ack(self, dat, ack=UBLOX_ACK, nack=UBLOX_NACK): + def send_with_ack(self, dat: bytes, ack: bytes = UBLOX_ACK, nack: bytes = UBLOX_NACK) -> None: self.send(dat) self.wait_for_ack(ack, nack) - def wait_for_backup_restore_status(self, timeout=1): + def wait_for_backup_restore_status(self, timeout: float = 1.) -> int: dat = b'' st = time.monotonic() while True: @@ -117,7 +116,7 @@ class TTYPigeon(): time.sleep(0.001) -def initialize_pigeon(pigeon): +def initialize_pigeon(pigeon: TTYPigeon) -> None: # try initializing a few times for _ in range(10): try: @@ -200,21 +199,22 @@ def initialize_pigeon(pigeon): except TimeoutError: cloudlog.warning("Initialization failed, trying again!") -def deinitialize_and_exit(pigeon): +def deinitialize_and_exit(pigeon: Optional[TTYPigeon]): cloudlog.warning("Storing almanac in ublox flash") - # controlled GNSS stop - pigeon.send(b"\xB5\x62\x06\x04\x04\x00\x00\x00\x08\x00\x16\x74") + if pigeon is not None: + # controlled GNSS stop + pigeon.send(b"\xB5\x62\x06\x04\x04\x00\x00\x00\x08\x00\x16\x74") - # store almanac in flash - pigeon.send(b"\xB5\x62\x09\x14\x04\x00\x00\x00\x00\x00\x21\xEC") - try: - if pigeon.wait_for_ack(ack=UBLOX_SOS_ACK, nack=UBLOX_SOS_NACK): - cloudlog.warning("Done storing almanac") - else: - cloudlog.error("Error storing almanac") - except TimeoutError: - pass + # store almanac in flash + pigeon.send(b"\xB5\x62\x09\x14\x04\x00\x00\x00\x00\x00\x21\xEC") + try: + if pigeon.wait_for_ack(ack=UBLOX_SOS_ACK, nack=UBLOX_SOS_NACK): + cloudlog.warning("Done storing almanac") + else: + cloudlog.error("Error storing almanac") + except TimeoutError: + pass # turn off power and exit cleanly set_power(False) @@ -223,6 +223,10 @@ def deinitialize_and_exit(pigeon): def main(): assert TICI, "unsupported hardware for pigeond" + # register exit handler + pigeon = None + signal.signal(signal.SIGINT, lambda sig, frame: deinitialize_and_exit(pigeon)) + pm = messaging.PubMaster(['ubloxRaw']) # power cycle ublox @@ -231,12 +235,9 @@ def main(): set_power(True) time.sleep(0.5) - pigeon = TTYPigeon(UBLOX_TTY) + pigeon = TTYPigeon() initialize_pigeon(pigeon) - # register exit handler - signal.signal(signal.SIGINT, lambda sig, frame: deinitialize_and_exit(pigeon)) - # start receiving data while True: dat = pigeon.receive() diff --git a/selfdrive/sensord/tests/__init__.py b/selfdrive/sensord/tests/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/sensord/tests/test_pigeond.py b/selfdrive/sensord/tests/test_pigeond.py new file mode 100755 index 0000000000..d15b731d0c --- /dev/null +++ b/selfdrive/sensord/tests/test_pigeond.py @@ -0,0 +1,63 @@ +#!/usr/bin/env python3 +import time +import unittest + +import cereal.messaging as messaging +from cereal.services import service_list +from common.gpio import gpio_read +from selfdrive.test.helpers import with_processes +from selfdrive.manager.process_config import managed_processes +from system.hardware import TICI +from system.hardware.tici.pins import GPIO + + +# TODO: test TTFF when we have good A-GNSS +class TestPigeond(unittest.TestCase): + @classmethod + def setUpClass(cls): + if not TICI: + raise unittest.SkipTest + + def tearDown(self): + managed_processes['pigeond'].stop() + + @with_processes(['pigeond']) + def test_frequency(self): + sm = messaging.SubMaster(['ubloxRaw']) + + # setup time + time.sleep(2) + sm.update() + + for _ in range(int(10 * service_list['ubloxRaw'].frequency)): + sm.update() + assert sm.all_checks() + + def test_startup_time(self): + for _ in range(5): + sm = messaging.SubMaster(['ubloxRaw']) + managed_processes['pigeond'].start() + + start_time = time.monotonic() + for __ in range(10): + sm.update(1 * 1000) + if sm.updated['ubloxRaw']: + break + assert sm.rcv_frame['ubloxRaw'] > 0, "pigeond didn't start outputting messages in time" + + et = time.monotonic() - start_time + assert et < 5, f"pigeond took {et:.1f}s to start" + managed_processes['pigeond'].stop() + + def test_turns_off_ublox(self): + for s in (0.1, 0.5, 1, 5): + managed_processes['pigeond'].start() + time.sleep(s) + managed_processes['pigeond'].stop() + + assert gpio_read(GPIO.UBLOX_RST_N) == 0 + assert gpio_read(GPIO.UBLOX_PWR_EN) == 0 + + +if __name__ == "__main__": + unittest.main() diff --git a/selfdrive/sensord/test/test_sensord.py b/selfdrive/sensord/tests/test_sensord.py similarity index 100% rename from selfdrive/sensord/test/test_sensord.py rename to selfdrive/sensord/tests/test_sensord.py diff --git a/selfdrive/sensord/test/ttff_test.py b/selfdrive/sensord/tests/ttff_test.py similarity index 100% rename from selfdrive/sensord/test/ttff_test.py rename to selfdrive/sensord/tests/ttff_test.py From 40d6f4b65c3776ffd78b3c3285dc5532a802c423 Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Thu, 1 Sep 2022 10:31:14 -0700 Subject: [PATCH 004/152] modeld: Move from SNPE to tinygrad (#25207) * compiling, won't work yet * running with inputs and outputs * there's some magic chance this works * no more dlc, include onnx * yolo tests plz * bump tinygrad * files_common + delete dlc * tinygrad_repo -> tinygrad * pre commit config * llops needed * extra in files_common * bump tinygrad * fix indent * tinygrad/nn/__init__ * tinygrad_repo * bump tinygrad repo * bump tinygrad * bump with native_exp, match maybe * native_explog is argument * pyopencl no cache * 5% chance this matches * work in float32? * bump tinygrad * fix build * no __init__ * fix recip * dumb hack * adding thneed PC support * fix pc segfault * pc thneed is working * to_image * prints stuff with debug=2 * it sort of works * copy host ptr is simpler * bug fix * build on c3 * this correct? * reenable float16 * fix private, fixup copy_inputs internal * bump tinygrad and update ref commit * fix OPTWG on PC * maybe fix non determinism * revert model replay ref commit * comments, init zeroed out buffers * upd ref commit * bump tinygrad to fix initial image * try this ref Co-authored-by: Comma Device --- .gitignore | 1 + .gitmodules | 3 + .pre-commit-config.yaml | 6 +- SConstruct | 5 ++ common/clutil.cc | 5 +- release/build_release.sh | 2 +- release/files_common | 15 +++- selfdrive/modeld/SConscript | 68 +++++++++++++++---- selfdrive/modeld/models/supercombo.dlc | 3 - selfdrive/modeld/thneed/serialize.cc | 7 +- selfdrive/modeld/thneed/thneed.h | 2 +- selfdrive/modeld/thneed/thneed_common.cc | 19 +++--- selfdrive/modeld/thneed/thneed_pc.cc | 40 +++++++++++ selfdrive/modeld/thneed/thneed_qcom2.cc | 2 +- .../process_replay/model_replay_ref_commit | 2 +- tinygrad | 1 + tinygrad_repo | 1 + 17 files changed, 143 insertions(+), 39 deletions(-) delete mode 100644 selfdrive/modeld/models/supercombo.dlc create mode 100644 selfdrive/modeld/thneed/thneed_pc.cc create mode 120000 tinygrad create mode 160000 tinygrad_repo diff --git a/.gitignore b/.gitignore index 6aee0ed8e0..062358ef24 100644 --- a/.gitignore +++ b/.gitignore @@ -36,6 +36,7 @@ a.out config.json clcache compile_commands.json +compare_runtime*.html persist board/obj/ diff --git a/.gitmodules b/.gitmodules index bc439b451c..26f93ef164 100644 --- a/.gitmodules +++ b/.gitmodules @@ -16,3 +16,6 @@ [submodule "body"] path = body url = ../../commaai/body.git +[submodule "tinygrad"] + path = tinygrad_repo + url = https://github.com/geohot/tinygrad.git diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 50554acceb..347216f2fb 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -28,7 +28,7 @@ repos: rev: v0.931 hooks: - id: mypy - exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)/' + exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)/|(tinygrad/)|(tinygrad_repo/)' additional_dependencies: ['types-PyYAML', 'lxml', 'numpy', 'types-atomicwrites', 'types-pycurl', 'types-requests', 'types-certifi'] args: - --warn-redundant-casts @@ -40,7 +40,7 @@ repos: rev: 4.0.1 hooks: - id: flake8 - exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)|(selfdrive/debug/)/' + exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)|(selfdrive/debug/)/' additional_dependencies: ['flake8-no-implicit-concat'] args: - --indent-size=2 @@ -55,7 +55,7 @@ repos: entry: pylint language: system types: [python] - exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(laika_repo/)|(rednose_repo/)' + exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(laika_repo/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)' args: - -rn - -sn diff --git a/SConstruct b/SConstruct index d4155f4f83..66a94f9b1b 100644 --- a/SConstruct +++ b/SConstruct @@ -49,6 +49,11 @@ AddOption('--no-thneed', dest='no_thneed', help='avoid using thneed') +AddOption('--pc-thneed', + action='store_true', + dest='pc_thneed', + help='use thneed on pc') + AddOption('--no-test', action='store_false', dest='test', diff --git a/common/clutil.cc b/common/clutil.cc index b8f9fde4cf..9d3447d807 100644 --- a/common/clutil.cc +++ b/common/clutil.cc @@ -78,7 +78,8 @@ cl_program cl_program_from_file(cl_context ctx, cl_device_id device_id, const ch } cl_program cl_program_from_source(cl_context ctx, cl_device_id device_id, const std::string& src, const char* args) { - cl_program prg = CL_CHECK_ERR(clCreateProgramWithSource(ctx, 1, (const char*[]){src.c_str()}, NULL, &err)); + const char *csrc = src.c_str(); + cl_program prg = CL_CHECK_ERR(clCreateProgramWithSource(ctx, 1, &csrc, NULL, &err)); if (int err = clBuildProgram(prg, 1, &device_id, args, NULL, NULL); err != 0) { cl_print_build_errors(prg, device_id); assert(0); @@ -87,7 +88,7 @@ cl_program cl_program_from_source(cl_context ctx, cl_device_id device_id, const } cl_program cl_program_from_binary(cl_context ctx, cl_device_id device_id, const uint8_t* binary, size_t length, const char* args) { - cl_program prg = CL_CHECK_ERR(clCreateProgramWithBinary(ctx, 1, &device_id, &length, (const uint8_t*[]){binary}, NULL, &err)); + cl_program prg = CL_CHECK_ERR(clCreateProgramWithBinary(ctx, 1, &device_id, &length, &binary, NULL, &err)); if (int err = clBuildProgram(prg, 1, &device_id, args, NULL, NULL); err != 0) { cl_print_build_errors(prg, device_id); assert(0); diff --git a/release/build_release.sh b/release/build_release.sh index 1000e607fa..80106eefb2 100755 --- a/release/build_release.sh +++ b/release/build_release.sh @@ -78,7 +78,7 @@ find . -name 'moc_*' -delete find . -name '__pycache__' -delete rm -rf panda/board panda/certs panda/crypto rm -rf .sconsign.dblite Jenkinsfile release/ -rm selfdrive/modeld/models/supercombo.dlc +rm selfdrive/modeld/models/supercombo.onnx # Move back signed panda fw mkdir -p panda/board/obj diff --git a/release/files_common b/release/files_common index ca6e91fb65..5be07b1c75 100644 --- a/release/files_common +++ b/release/files_common @@ -352,7 +352,7 @@ selfdrive/modeld/models/driving.cc selfdrive/modeld/models/driving.h selfdrive/modeld/models/dmonitoring.cc selfdrive/modeld/models/dmonitoring.h -selfdrive/modeld/models/supercombo.dlc +selfdrive/modeld/models/supercombo.onnx selfdrive/modeld/models/dmonitoring_model_q.dlc selfdrive/modeld/transforms/loadyuv.cc @@ -561,3 +561,16 @@ opendbc/vw_mqb_2010.dbc opendbc/tesla_can.dbc opendbc/tesla_radar.dbc opendbc/tesla_powertrain.dbc + +tinygrad_repo/openpilot/compile.py +tinygrad_repo/accel/opencl/* +tinygrad_repo/extra/onnx.py +tinygrad_repo/extra/utils.py +tinygrad_repo/tinygrad/llops/ops_gpu.py +tinygrad_repo/tinygrad/llops/ops_opencl.py +tinygrad_repo/tinygrad/helpers.py +tinygrad_repo/tinygrad/mlops.py +tinygrad_repo/tinygrad/ops.py +tinygrad_repo/tinygrad/shapetracker.py +tinygrad_repo/tinygrad/tensor.py +tinygrad_repo/tinygrad/nn/__init__.py diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index 4feb17f238..2544607aa4 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -62,25 +62,65 @@ else: common_model = lenv.Object(common_src) -# build thneed model -if use_thneed and arch == "larch64": - fn = File("models/supercombo").abspath - compiler = lenv.Program('thneed/compile', ["thneed/compile.cc"]+common_model, LIBS=libs) - cmd = f"cd {Dir('.').abspath} && {compiler[0].abspath} --in {fn}.dlc --out {fn}.thneed --binary --optimize" - - lib_paths = ':'.join(Dir(p).abspath for p in lenv["LIBPATH"]) - kernel_path = os.path.join(Dir('.').abspath, "thneed", "kernels") - cenv = Environment(ENV={'LD_LIBRARY_PATH': f"{lib_paths}:{lenv['ENV']['LD_LIBRARY_PATH']}", 'KERNEL_PATH': kernel_path}) - - kernels = [os.path.join(kernel_path, x) for x in os.listdir(kernel_path) if x.endswith(".cl")] - cenv.Command(fn + ".thneed", [fn + ".dlc", kernels, compiler], cmd) - lenv.Program('_dmonitoringmodeld', [ "dmonitoringmodeld.cc", "models/dmonitoring.cc", ]+common_model, LIBS=libs) -lenv.Program('_modeld', [ +# build thneed model +if use_thneed and arch == "larch64" or GetOption('pc_thneed'): + fn = File("models/supercombo").abspath + + if GetOption('pc_thneed'): + cmd = f"cd {Dir('#').abspath}/tinygrad_repo && NATIVE_EXPLOG=1 OPTWG=1 UNSAFE_FLOAT4=1 DEBUGCL=1 python3 openpilot/compile.py {fn}.onnx {fn}.thneed" + else: + cmd = f"cd {Dir('#').abspath}/tinygrad_repo && FLOAT16=1 PYOPENCL_NO_CACHE=1 MATMUL=1 NATIVE_EXPLOG=1 OPTWG=1 UNSAFE_FLOAT4=1 DEBUGCL=1 python3 openpilot/compile.py {fn}.onnx {fn}.thneed" + + # is there a better way then listing all of tinygrad? + lenv.Command(fn + ".thneed", [fn + ".onnx", + "#tinygrad_repo/openpilot/compile.py", + "#tinygrad_repo/accel/opencl/conv.cl", + "#tinygrad_repo/accel/opencl/matmul.cl", + "#tinygrad_repo/accel/opencl/ops_opencl.py", + "#tinygrad_repo/accel/opencl/preprocessing.py", + "#tinygrad_repo/extra/onnx.py", + "#tinygrad_repo/extra/utils.py", + "#tinygrad_repo/tinygrad/llops/ops_gpu.py", + "#tinygrad_repo/tinygrad/llops/ops_opencl.py", + "#tinygrad_repo/tinygrad/helpers.py", + "#tinygrad_repo/tinygrad/mlops.py", + "#tinygrad_repo/tinygrad/ops.py", + "#tinygrad_repo/tinygrad/shapetracker.py", + "#tinygrad_repo/tinygrad/tensor.py", + "#tinygrad_repo/tinygrad/nn/__init__.py" + ], cmd) + + # old thneed compiler. TODO: remove this once tinygrad stuff is stable + + #compiler = lenv.Program('thneed/compile', ["thneed/compile.cc"]+common_model, LIBS=libs) + #cmd = f"cd {Dir('.').abspath} && {compiler[0].abspath} --in {fn}.dlc --out {fn}.thneed --binary --optimize" + + #lib_paths = ':'.join(Dir(p).abspath for p in lenv["LIBPATH"]) + #kernel_path = os.path.join(Dir('.').abspath, "thneed", "kernels") + #cenv = Environment(ENV={'LD_LIBRARY_PATH': f"{lib_paths}:{lenv['ENV']['LD_LIBRARY_PATH']}", 'KERNEL_PATH': kernel_path}) + + #kernels = [os.path.join(kernel_path, x) for x in os.listdir(kernel_path) if x.endswith(".cl")] + #cenv.Command(fn + ".thneed", [fn + ".dlc", kernels, compiler], cmd) + +llenv = lenv.Clone() +if GetOption('pc_thneed'): + pc_thneed_src = [ + "thneed/thneed_common.cc", + "thneed/thneed_pc.cc", + "thneed/serialize.cc", + "runners/thneedmodel.cc", + ] + llenv['CFLAGS'].append("-DUSE_THNEED") + llenv['CXXFLAGS'].append("-DUSE_THNEED") + common_model += llenv.Object(pc_thneed_src) + libs += ['dl'] + +llenv.Program('_modeld', [ "modeld.cc", "models/driving.cc", ]+common_model, LIBS=libs + transformations) diff --git a/selfdrive/modeld/models/supercombo.dlc b/selfdrive/modeld/models/supercombo.dlc deleted file mode 100644 index fe133523fc..0000000000 --- a/selfdrive/modeld/models/supercombo.dlc +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:93d265fc88f05746ce47257e15fc2afe43b250b44715313049f829e8aa30a9d6 -size 94302331 diff --git a/selfdrive/modeld/thneed/serialize.cc b/selfdrive/modeld/thneed/serialize.cc index 0b8b02c6ac..afc84ee769 100644 --- a/selfdrive/modeld/thneed/serialize.cc +++ b/selfdrive/modeld/thneed/serialize.cc @@ -33,11 +33,14 @@ void Thneed::load(const char *filename) { assert(mobj["needs_load"].bool_value() == false); } else { if (mobj["needs_load"].bool_value()) { - //printf("loading %p %d @ 0x%X\n", clbuf, sz, ptr); clbuf = clCreateBuffer(context, CL_MEM_COPY_HOST_PTR | CL_MEM_READ_WRITE, sz, &buf[ptr], NULL); + if (debug >= 1) printf("loading %p %d @ 0x%X\n", clbuf, sz, ptr); ptr += sz; } else { - clbuf = clCreateBuffer(context, CL_MEM_READ_WRITE, sz, NULL, NULL); + // TODO: is there a faster way to init zeroed out buffers? + void *host_zeros = calloc(sz, 1); + clbuf = clCreateBuffer(context, CL_MEM_COPY_HOST_PTR | CL_MEM_READ_WRITE, sz, host_zeros, NULL); + free(host_zeros); } } assert(clbuf != NULL); diff --git a/selfdrive/modeld/thneed/thneed.h b/selfdrive/modeld/thneed/thneed.h index 19dc46e8f6..2a5800f302 100644 --- a/selfdrive/modeld/thneed/thneed.h +++ b/selfdrive/modeld/thneed/thneed.h @@ -122,7 +122,7 @@ class Thneed { // all CL kernels void find_inputs_outputs(); - void copy_inputs(float **finputs); + void copy_inputs(float **finputs, bool internal=false); void copy_output(float *foutput); cl_int clexec(); vector > kq; diff --git a/selfdrive/modeld/thneed/thneed_common.cc b/selfdrive/modeld/thneed/thneed_common.cc index b751cdf665..a3f5c908f9 100644 --- a/selfdrive/modeld/thneed/thneed_common.cc +++ b/selfdrive/modeld/thneed/thneed_common.cc @@ -30,17 +30,16 @@ cl_int Thneed::clexec() { return clFinish(command_queue); } -void Thneed::copy_inputs(float **finputs) { - //cl_int ret; +void Thneed::copy_inputs(float **finputs, bool internal) { for (int idx = 0; idx < inputs.size(); ++idx) { if (debug >= 1) printf("copying %lu -- %p -> %p (cl %p)\n", input_sizes[idx], finputs[idx], inputs[idx], input_clmem[idx]); - // TODO: fix thneed caching - if (finputs[idx] != NULL) memcpy(inputs[idx], finputs[idx], input_sizes[idx]); - //if (finputs[idx] != NULL) CL_CHECK(clEnqueueWriteBuffer(command_queue, input_clmem[idx], CL_TRUE, 0, input_sizes[idx], finputs[idx], 0, NULL, NULL)); - - // HACK - //if (input_sizes[idx] == 16) memset((char*)inputs[idx] + 8, 0, 8); + if (internal) { + // if it's internal, using memcpy is fine since the buffer sync is cached in the ioctl layer + if (finputs[idx] != NULL) memcpy(inputs[idx], finputs[idx], input_sizes[idx]); + } else { + if (finputs[idx] != NULL) CL_CHECK(clEnqueueWriteBuffer(command_queue, input_clmem[idx], CL_TRUE, 0, input_sizes[idx], finputs[idx], 0, NULL, NULL)); + } } } @@ -202,8 +201,8 @@ void CLQueuedKernel::debug_print(bool verbose) { assert(slice_pitch == 0); clGetImageInfo(val, CL_IMAGE_BUFFER, sizeof(buf), &buf, NULL); - size_t sz; - clGetMemObjectInfo(buf, CL_MEM_SIZE, sizeof(sz), &sz, NULL); + size_t sz = 0; + if (buf != NULL) clGetMemObjectInfo(buf, CL_MEM_SIZE, sizeof(sz), &sz, NULL); printf(" image %zu x %zu rp %zu @ %p buffer %zu", width, height, row_pitch, buf, sz); } else { size_t sz; diff --git a/selfdrive/modeld/thneed/thneed_pc.cc b/selfdrive/modeld/thneed/thneed_pc.cc new file mode 100644 index 0000000000..e32dd289ec --- /dev/null +++ b/selfdrive/modeld/thneed/thneed_pc.cc @@ -0,0 +1,40 @@ +#include "selfdrive/modeld/thneed/thneed.h" + +#include + +#include "common/clutil.h" +#include "common/timing.h" + +Thneed::Thneed(bool do_clinit, cl_context _context) { + context = _context; + if (do_clinit) clinit(); + char *thneed_debug_env = getenv("THNEED_DEBUG"); + debug = (thneed_debug_env != NULL) ? atoi(thneed_debug_env) : 0; +} + +void Thneed::execute(float **finputs, float *foutput, bool slow) { + uint64_t tb, te; + if (debug >= 1) tb = nanos_since_boot(); + + // ****** copy inputs + copy_inputs(finputs); + + // ****** run commands + clexec(); + + // ****** copy outputs + copy_output(foutput); + + if (debug >= 1) { + te = nanos_since_boot(); + printf("model exec in %lu us\n", (te-tb)/1000); + } +} + +void Thneed::stop() { +} + +void Thneed::find_inputs_outputs() { + // thneed on PC doesn't work on old style inputs/outputs +} + diff --git a/selfdrive/modeld/thneed/thneed_qcom2.cc b/selfdrive/modeld/thneed/thneed_qcom2.cc index e79bb77edf..f35317d2a7 100644 --- a/selfdrive/modeld/thneed/thneed_qcom2.cc +++ b/selfdrive/modeld/thneed/thneed_qcom2.cc @@ -269,7 +269,7 @@ void Thneed::execute(float **finputs, float *foutput, bool slow) { if (debug >= 1) tb = nanos_since_boot(); // ****** copy inputs - copy_inputs(finputs); + copy_inputs(finputs, true); // ****** set power constraint int ret; diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 80be9b464f..e2ee2e7bb6 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -ca90e11f8d59902af38d3785ddd91a27d0fbb411 +cffb4e720b0379bedd4ff802912d998ace775c37 diff --git a/tinygrad b/tinygrad new file mode 120000 index 0000000000..cb003823c6 --- /dev/null +++ b/tinygrad @@ -0,0 +1 @@ +tinygrad_repo/tinygrad \ No newline at end of file diff --git a/tinygrad_repo b/tinygrad_repo new file mode 160000 index 0000000000..2e9b7637b3 --- /dev/null +++ b/tinygrad_repo @@ -0,0 +1 @@ +Subproject commit 2e9b7637b3c3c8895fda9f964215db3a35fe3441 From cbe1c89698a20d7eb26897c1e202bcc7d48ee1cd Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 1 Sep 2022 13:39:00 -0700 Subject: [PATCH 005/152] Update total scons nodes --- selfdrive/manager/build.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/manager/build.py b/selfdrive/manager/build.py index 12f894061a..c8a7d41539 100755 --- a/selfdrive/manager/build.py +++ b/selfdrive/manager/build.py @@ -15,7 +15,7 @@ from system.version import is_dirty MAX_CACHE_SIZE = 4e9 if "CI" in os.environ else 2e9 CACHE_DIR = Path("/data/scons_cache" if AGNOS else "/tmp/scons_cache") -TOTAL_SCONS_NODES = 2035 +TOTAL_SCONS_NODES = 2395 MAX_BUILD_PROGRESS = 100 PREBUILT = os.path.exists(os.path.join(BASEDIR, 'prebuilt')) From e1b7a37a1f6a341bdc729c186ca5b4d3fb8af9ee Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Thu, 1 Sep 2022 15:40:25 -0700 Subject: [PATCH 006/152] Support e2e long in longitudinal planner (#25636) * refactor * Add planer modes to support offline, acc, and blended * add acceleration * Fix index * Update model ref * Read in model outputs * Add model msg * Add e2e logic * Add source --- .../lib/longitudinal_mpc_lib/long_mpc.py | 117 +++++++++++------- .../controls/lib/longitudinal_planner.py | 22 +++- selfdrive/modeld/models/driving.cc | 5 + .../test/longitudinal_maneuvers/plant.py | 4 +- .../process_replay/model_replay_ref_commit | 2 +- 5 files changed, 103 insertions(+), 47 deletions(-) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index 94efd7a875..eaecb63a6b 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -3,7 +3,7 @@ import os import numpy as np from common.realtime import sec_since_boot -from common.numpy_fast import clip, interp +from common.numpy_fast import clip from system.swaglog import cloudlog from selfdrive.modeld.constants import index_function from selfdrive.controls.lib.radar_helpers import _LEAD_ACCEL_TAU @@ -20,7 +20,7 @@ LONG_MPC_DIR = os.path.dirname(os.path.abspath(__file__)) EXPORT_DIR = os.path.join(LONG_MPC_DIR, "c_generated_code") JSON_FILE = os.path.join(LONG_MPC_DIR, "acados_ocp_long.json") -SOURCES = ['lead0', 'lead1', 'cruise'] +SOURCES = ['lead0', 'lead1', 'cruise', 'e2e'] X_DIM = 3 U_DIM = 1 @@ -50,6 +50,7 @@ T_IDXS_LST = [index_function(idx, max_val=MAX_T, max_idx=N) for idx in range(N+1 T_IDXS = np.array(T_IDXS_LST) T_DIFFS = np.diff(T_IDXS, prepend=[0.]) MIN_ACCEL = -3.5 +MAX_ACCEL = 2.0 T_FOLLOW = 1.45 COMFORT_BRAKE = 2.5 STOP_DISTANCE = 6.0 @@ -190,8 +191,8 @@ def gen_long_ocp(): class LongitudinalMpc: - def __init__(self, e2e=False): - self.e2e = e2e + def __init__(self, mode='acc'): + self.mode = mode self.solver = AcadosOcpSolverCython(MODEL_NAME, ACADOS_SOLVER_TYPE, N) self.reset() self.source = SOURCES[2] @@ -225,49 +226,42 @@ class LongitudinalMpc: self.x0 = np.zeros(X_DIM) self.set_weights() - def set_weights(self, prev_accel_constraint=True): - if self.e2e: - self.set_weights_for_xva_policy() - self.params[:,0] = -10. - self.params[:,1] = 10. - self.params[:,2] = 1e5 - else: - self.set_weights_for_lead_policy(prev_accel_constraint) - - def set_weights_for_lead_policy(self, prev_accel_constraint=True): - a_change_cost = A_CHANGE_COST if prev_accel_constraint else 0 - W = np.asfortranarray(np.diag([X_EGO_OBSTACLE_COST, X_EGO_COST, V_EGO_COST, A_EGO_COST, a_change_cost, J_EGO_COST])) + def set_cost_weights(self, cost_weights, constraint_cost_weights): + W = np.asfortranarray(np.diag(cost_weights)) for i in range(N): + # TODO don't hardcode A_CHANGE_COST idx # reduce the cost on (a-a_prev) later in the horizon. - W[4,4] = a_change_cost * np.interp(T_IDXS[i], [0.0, 1.0, 2.0], [1.0, 1.0, 0.0]) + W[4,4] = cost_weights[4] * np.interp(T_IDXS[i], [0.0, 1.0, 2.0], [1.0, 1.0, 0.0]) self.solver.cost_set(i, 'W', W) # Setting the slice without the copy make the array not contiguous, # causing issues with the C interface. self.solver.cost_set(N, 'W', np.copy(W[:COST_E_DIM, :COST_E_DIM])) # Set L2 slack cost on lower bound constraints - Zl = np.array([LIMIT_COST, LIMIT_COST, LIMIT_COST, DANGER_ZONE_COST]) + Zl = np.array(constraint_cost_weights) for i in range(N): self.solver.cost_set(i, 'Zl', Zl) - def set_weights_for_xva_policy(self): - W = np.asfortranarray(np.diag([0., 0.2, 0.25, 1., 0.0, .1])) - for i in range(N): - self.solver.cost_set(i, 'W', W) - # Setting the slice without the copy make the array not contiguous, - # causing issues with the C interface. - self.solver.cost_set(N, 'W', np.copy(W[:COST_E_DIM, :COST_E_DIM])) - - # Set L2 slack cost on lower bound constraints - Zl = np.array([LIMIT_COST, LIMIT_COST, LIMIT_COST, 0.0]) - for i in range(N): - self.solver.cost_set(i, 'Zl', Zl) + def set_weights(self, prev_accel_constraint=True): + if self.mode == 'acc': + 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] + constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, DANGER_ZONE_COST] + elif self.mode == 'blended': + cost_weights = [0., 1.0, 0.0, 0.0, 0.0, 1.0] + constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 0.0] + elif self.mode == 'e2e': + cost_weights = [0., 0.2, 0.25, 1., 0.0, .1] + constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 0.0] + else: + raise NotImplementedError(f'Planner mode {self.mode} not recognized') + self.set_cost_weights(cost_weights, constraint_cost_weights) def set_cur_state(self, v, a): v_prev = self.x0[1] self.x0[1] = v self.x0[2] = a - if abs(v_prev - v) > 2.: # probably only helps if v < v_prev + if abs(v_prev - v) > 2.: # probably only helps if v < v_prev for i in range(0, N+1): self.solver.set(i, 'x', self.x0) @@ -306,31 +300,62 @@ class LongitudinalMpc: self.cruise_min_a = min_a self.cruise_max_a = max_a - def update(self, carstate, radarstate, v_cruise): + def update(self, carstate, radarstate, v_cruise, x, v, a, j): v_ego = self.x0[1] self.status = radarstate.leadOne.status or radarstate.leadTwo.status lead_xv_0 = self.process_lead(radarstate.leadOne) lead_xv_1 = self.process_lead(radarstate.leadTwo) - # set accel limits in params - self.params[:,0] = interp(float(self.status), [0.0, 1.0], [self.cruise_min_a, MIN_ACCEL]) - self.params[:,1] = self.cruise_max_a - # To estimate a safe distance from a moving lead, we calculate how much stopping # distance that lead needs as a minimum. We can add that to the current distance # and then treat that as a stopped car/obstacle at this new distance. lead_0_obstacle = lead_xv_0[:,0] + get_stopped_equivalence_factor(lead_xv_0[:,1]) lead_1_obstacle = lead_xv_1[:,0] + get_stopped_equivalence_factor(lead_xv_1[:,1]) - # Fake an obstacle for cruise, this ensures smooth acceleration to set speed - # when the leads are no factor. - v_lower = v_ego + (T_IDXS * self.cruise_min_a * 1.05) - v_upper = v_ego + (T_IDXS * self.cruise_max_a * 1.05) - v_cruise_clipped = np.clip(v_cruise * np.ones(N+1), - v_lower, - v_upper) - cruise_obstacle = np.cumsum(T_DIFFS * v_cruise_clipped) + get_safe_obstacle_distance(v_cruise_clipped) + # Update in ACC mode or ACC/e2e blend + if self.mode == 'acc': + self.params[:,0] = MIN_ACCEL if self.status else self.cruise_min_a + self.params[:,1] = self.cruise_max_a + + # Fake an obstacle for cruise, this ensures smooth acceleration to set speed + # when the leads are no factor. + v_lower = v_ego + (T_IDXS * self.cruise_min_a * 1.05) + v_upper = v_ego + (T_IDXS * self.cruise_max_a * 1.05) + v_cruise_clipped = np.clip(v_cruise * np.ones(N+1), + v_lower, + v_upper) + cruise_obstacle = np.cumsum(T_DIFFS * v_cruise_clipped) + get_safe_obstacle_distance(v_cruise_clipped) + x_obstacles = np.column_stack([lead_0_obstacle, lead_1_obstacle, cruise_obstacle]) + self.source = SOURCES[np.argmin(x_obstacles[0])] + + # These are not used in ACC mode + x[:], v[:], a[:], j[:] = 0.0, 0.0, 0.0, 0.0 + + elif self.mode == 'blended': + self.params[:,0] = MIN_ACCEL + self.params[:,1] = MAX_ACCEL + + x_obstacles = np.column_stack([lead_0_obstacle, + lead_1_obstacle]) + cruise_target = T_IDXS * v_cruise + x[0] + xforward = ((v[1:] + v[:-1]) / 2) * (T_IDXS[1:] - T_IDXS[:-1]) + x = np.cumsum(np.insert(xforward, 0, x[0])) + + x_and_cruise = np.column_stack([x, cruise_target]) + x = np.min(x_and_cruise, axis=1) + self.source = 'e2e' + + else: + raise NotImplementedError(f'Planner mode {self.mode} not recognized') + + self.yref[:,1] = x + self.yref[:,2] = v + self.yref[:,3] = a + self.yref[:,5] = j + for i in range(N): + self.solver.set(i, "yref", self.yref[i]) + self.solver.set(N, "yref", self.yref[N][:COST_E_DIM]) x_obstacles = np.column_stack([lead_0_obstacle, lead_1_obstacle, cruise_obstacle]) self.source = SOURCES[np.argmin(x_obstacles[0])] @@ -345,6 +370,10 @@ class LongitudinalMpc: self.crash_cnt = 0 def update_with_xva(self, x, v, a): + self.params[:,0] = -10. + self.params[:,1] = 10. + self.params[:,2] = 1e5 + # v, and a are in local frame, but x is wrt the x[0] position # In >90degree turns, x goes to 0 (and may even be -ve) # So, we use integral(v) + x[0] to obtain the forward-distance diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index cf51136770..42ce2bd0ec 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -53,12 +53,31 @@ class Planner: self.a_desired = init_a self.v_desired_filter = FirstOrderFilter(init_v, 2.0, DT_MDL) + self.t_uniform = np.arange(0.0, T_IDXS_MPC[-1] + 0.5, 0.5) self.v_desired_trajectory = np.zeros(CONTROL_N) self.a_desired_trajectory = np.zeros(CONTROL_N) self.j_desired_trajectory = np.zeros(CONTROL_N) self.solverExecutionTime = 0.0 + def parse_model(self, model_msg): + if (len(model_msg.position.x) == 33 and + len(model_msg.velocity.x) == 33 and + len(model_msg.acceleration.x) == 33): + x = np.interp(T_IDXS_MPC, T_IDXS, model_msg.position.x) + v = np.interp(T_IDXS_MPC, T_IDXS, model_msg.velocity.x) + a = np.interp(T_IDXS_MPC, T_IDXS, model_msg.acceleration.x) + # Uniform interp so gradient is less noisy + a_sparse = np.interp(self.t_uniform, T_IDXS, model_msg.acceleration.x) + j_sparse = np.gradient(a_sparse, self.t_uniform) + j = np.interp(T_IDXS_MPC, self.t_uniform, j_sparse) + else: + x = np.zeros(len(T_IDXS_MPC)) + v = np.zeros(len(T_IDXS_MPC)) + a = np.zeros(len(T_IDXS_MPC)) + j = np.zeros(len(T_IDXS_MPC)) + return x, v, a, j + def update(self, sm): v_ego = sm['carState'].vEgo @@ -95,7 +114,8 @@ class Planner: self.mpc.set_weights(prev_accel_constraint) 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.update(sm['carState'], sm['radarState'], v_cruise) + x, v, a, j = self.parse_model(sm['modelV2']) + self.mpc.update(sm['carState'], sm['radarState'], v_cruise, x, v, a, j) self.v_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC, self.mpc.v_solution) self.a_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC, self.mpc.a_solution) diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index 7a7a6ff6e3..8d02eb6b2f 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -203,6 +203,7 @@ void fill_plan(cereal::ModelDataV2::Builder &framed, const ModelOutputPlanPredic std::array pos_x_std, pos_y_std, pos_z_std; std::array vel_x, vel_y, vel_z; std::array rot_x, rot_y, rot_z; + std::array acc_x, acc_y, acc_z; std::array rot_rate_x, rot_rate_y, rot_rate_z; for(int i=0; i Date: Thu, 1 Sep 2022 16:19:21 -0700 Subject: [PATCH 007/152] Optima 2019: set LKAS icon correctly (#25637) * are we sure? * add params * should work should work * fix * fix * clean up * comment * comment * Update selfdrive/car/hyundai/hyundaican.py --- selfdrive/car/hyundai/carcontroller.py | 1 + selfdrive/car/hyundai/hyundaican.py | 18 ++++++++++++++++-- 2 files changed, 17 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 971330a335..586d215ffe 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -15,6 +15,7 @@ def process_hud_alert(enabled, fingerprint, hud_control): sys_warning = (hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw)) # initialize to no line visible + # TODO: this is not accurate for all cars sys_state = 1 if hud_control.leftLaneVisible and hud_control.rightLaneVisible or sys_warning: # HUD alert only display when LKAS status is active sys_state = 3 if enabled or sys_warning else 4 diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py index 8a5e33f111..f94cc508a7 100644 --- a/selfdrive/car/hyundai/hyundaican.py +++ b/selfdrive/car/hyundai/hyundaican.py @@ -37,12 +37,26 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req, # Note: the warning is hidden while the blinkers are on values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 + # Likely cars lacking the ability to show individual lane lines in the dash + elif car_fingerprint in (CAR.KIA_OPTIMA,): + # SysWarning 4 = keep hands on wheel + beep + values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 + + # SysState 0 = no icons + # SysState 1-2 = white car + lanes + # SysState 3 = green car + lanes, green steering wheel + # SysState 4 = green car + lanes + values["CF_Lkas_LdwsSysState"] = 3 if enabled else 1 + values["CF_Lkas_LdwsOpt_USM"] = 2 # non-2 changes above SysState definition + + # these have no effect + values["CF_Lkas_LdwsActivemode"] = 0 + values["CF_Lkas_FcwOpt_USM"] = 0 + elif car_fingerprint == CAR.HYUNDAI_GENESIS: # This field is actually LdwsActivemode # Genesis and Optima fault when forwarding while engaged values["CF_Lkas_LdwsActivemode"] = 2 - elif car_fingerprint == CAR.KIA_OPTIMA: - values["CF_Lkas_LdwsActivemode"] = 0 dat = packer.make_can_msg("LKAS11", 0, values)[2] From 6c39382d71978d20f00286678b2f13e00134bb0a Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Thu, 1 Sep 2022 18:28:20 -0700 Subject: [PATCH 008/152] modeld: delete unused SNPE stuff after move to tinygrad (#25635) * delete unused stuff * remove CL interceptor from thneed since we don't use SNPE anymore * remove dead files from release * that's removed * oops, didn't save --- release/files_common | 3 - selfdrive/modeld/SConscript | 13 - selfdrive/modeld/runners/snpemodel.cc | 77 +---- selfdrive/modeld/runners/thneedmodel.cc | 1 - selfdrive/modeld/thneed/compile.cc | 81 ------ .../modeld/thneed/kernels/convolution_.cl | 272 ------------------ .../convolution_horizontal_reduced_reads.cl | 3 - ...onvolution_horizontal_reduced_reads_1x1.cl | 4 - ...tion_horizontal_reduced_reads_5_outputs.cl | 3 - ...tion_horizontal_reduced_reads_depthwise.cl | 4 - ...zontal_reduced_reads_depthwise_stride_1.cl | 3 - selfdrive/modeld/thneed/optimizer.cc | 261 ----------------- selfdrive/modeld/thneed/serialize.cc | 152 ---------- selfdrive/modeld/thneed/thneed.h | 8 +- selfdrive/modeld/thneed/thneed_common.cc | 29 +- selfdrive/modeld/thneed/thneed_pc.cc | 8 - selfdrive/modeld/thneed/thneed_qcom2.cc | 104 ------- selfdrive/modeld/thneed/weights_fixup.py | 146 ---------- 18 files changed, 14 insertions(+), 1158 deletions(-) delete mode 100644 selfdrive/modeld/thneed/compile.cc delete mode 100644 selfdrive/modeld/thneed/kernels/convolution_.cl delete mode 100644 selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads.cl delete mode 100644 selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_1x1.cl delete mode 100644 selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_5_outputs.cl delete mode 100644 selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise.cl delete mode 100644 selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise_stride_1.cl delete mode 100644 selfdrive/modeld/thneed/optimizer.cc delete mode 100755 selfdrive/modeld/thneed/weights_fixup.py diff --git a/release/files_common b/release/files_common index 5be07b1c75..10c66a8960 100644 --- a/release/files_common +++ b/release/files_common @@ -367,10 +367,7 @@ selfdrive/modeld/thneed/thneed.h selfdrive/modeld/thneed/thneed_common.cc selfdrive/modeld/thneed/thneed_qcom2.cc selfdrive/modeld/thneed/serialize.cc -selfdrive/modeld/thneed/compile.cc -selfdrive/modeld/thneed/optimizer.cc selfdrive/modeld/thneed/include/* -selfdrive/modeld/thneed/kernels/*.cl selfdrive/modeld/runners/snpemodel.cc selfdrive/modeld/runners/snpemodel.h diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index 2544607aa4..246f8c2941 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -26,7 +26,6 @@ thneed_src = [ "thneed/thneed_common.cc", "thneed/thneed_qcom2.cc", "thneed/serialize.cc", - "thneed/optimizer.cc", "runners/thneedmodel.cc", ] @@ -95,18 +94,6 @@ if use_thneed and arch == "larch64" or GetOption('pc_thneed'): "#tinygrad_repo/tinygrad/nn/__init__.py" ], cmd) - # old thneed compiler. TODO: remove this once tinygrad stuff is stable - - #compiler = lenv.Program('thneed/compile', ["thneed/compile.cc"]+common_model, LIBS=libs) - #cmd = f"cd {Dir('.').abspath} && {compiler[0].abspath} --in {fn}.dlc --out {fn}.thneed --binary --optimize" - - #lib_paths = ':'.join(Dir(p).abspath for p in lenv["LIBPATH"]) - #kernel_path = os.path.join(Dir('.').abspath, "thneed", "kernels") - #cenv = Environment(ENV={'LD_LIBRARY_PATH': f"{lib_paths}:{lenv['ENV']['LD_LIBRARY_PATH']}", 'KERNEL_PATH': kernel_path}) - - #kernels = [os.path.join(kernel_path, x) for x in os.listdir(kernel_path) if x.endswith(".cl")] - #cenv.Command(fn + ".thneed", [fn + ".dlc", kernels, compiler], cmd) - llenv = lenv.Clone() if GetOption('pc_thneed'): pc_thneed_src = [ diff --git a/selfdrive/modeld/runners/snpemodel.cc b/selfdrive/modeld/runners/snpemodel.cc index 95ee5fe822..ff4adcd8d3 100644 --- a/selfdrive/modeld/runners/snpemodel.cc +++ b/selfdrive/modeld/runners/snpemodel.cc @@ -186,75 +186,14 @@ std::unique_ptr SNPEModel::addExtra(float *state, in } void SNPEModel::execute() { -#ifdef USE_THNEED - if (Runtime == zdl::DlSystem::Runtime_t::GPU) { - if (!thneed_recorded) { - bool ret = inputBuffer->setBufferAddress(input); - assert(ret == true); - if (use_extra) { - assert(extra != NULL); - bool extra_ret = extraBuffer->setBufferAddress(extra); - assert(extra_ret == true); - } - if (!snpe->execute(inputMap, outputMap)) { - PrintErrorStringAndExit(); - } - memset(recurrent, 0, recurrent_size*sizeof(float)); - thneed->record = true; - if (!snpe->execute(inputMap, outputMap)) { - PrintErrorStringAndExit(); - } - thneed->stop(); - printf("thneed cached\n"); - - // doing self test - float *outputs_golden = (float *)malloc(output_size*sizeof(float)); - memcpy(outputs_golden, output, output_size*sizeof(float)); - memset(output, 0, output_size*sizeof(float)); - memset(recurrent, 0, recurrent_size*sizeof(float)); - uint64_t start_time = nanos_since_boot(); - if (extra != NULL) { - float *inputs[5] = {recurrent, trafficConvention, desire, extra, input}; - thneed->execute(inputs, output); - } else { - float *inputs[4] = {recurrent, trafficConvention, desire, input}; - thneed->execute(inputs, output); - } - uint64_t elapsed_time = nanos_since_boot() - start_time; - printf("ran model in %.2f ms\n", float(elapsed_time)/1e6); - - if (memcmp(output, outputs_golden, output_size*sizeof(float)) == 0) { - printf("thneed selftest passed\n"); - } else { - for (int i = 0; i < output_size; i++) { - printf("mismatch %3d: %f %f\n", i, output[i], outputs_golden[i]); - } - assert(false); - } - free(outputs_golden); - thneed_recorded = true; - } else { - if (use_extra) { - float *inputs[5] = {recurrent, trafficConvention, desire, extra, input}; - thneed->execute(inputs, output); - } else { - float *inputs[4] = {recurrent, trafficConvention, desire, input}; - thneed->execute(inputs, output); - } - } - } else { -#endif - bool ret = inputBuffer->setBufferAddress(input); - assert(ret == true); - if (use_extra) { - bool extra_ret = extraBuffer->setBufferAddress(extra); - assert(extra_ret == true); - } - if (!snpe->execute(inputMap, outputMap)) { - PrintErrorStringAndExit(); - } -#ifdef USE_THNEED + bool ret = inputBuffer->setBufferAddress(input); + assert(ret == true); + if (use_extra) { + bool extra_ret = extraBuffer->setBufferAddress(extra); + assert(extra_ret == true); + } + if (!snpe->execute(inputMap, outputMap)) { + PrintErrorStringAndExit(); } -#endif } diff --git a/selfdrive/modeld/runners/thneedmodel.cc b/selfdrive/modeld/runners/thneedmodel.cc index d55a8104ee..67db01bb95 100644 --- a/selfdrive/modeld/runners/thneedmodel.cc +++ b/selfdrive/modeld/runners/thneedmodel.cc @@ -6,7 +6,6 @@ ThneedModel::ThneedModel(const char *path, float *loutput, size_t loutput_size, thneed = new Thneed(true, context); thneed->load(path); thneed->clexec(); - thneed->find_inputs_outputs(); recorded = false; output = loutput; diff --git a/selfdrive/modeld/thneed/compile.cc b/selfdrive/modeld/thneed/compile.cc deleted file mode 100644 index f76c63b2b9..0000000000 --- a/selfdrive/modeld/thneed/compile.cc +++ /dev/null @@ -1,81 +0,0 @@ -#include -#include - -#include "selfdrive/modeld/runners/snpemodel.h" -#include "selfdrive/modeld/thneed/thneed.h" -#include "system/hardware/hw.h" - -#define TEMPORAL_SIZE 512 -#define DESIRE_LEN 8 -#define TRAFFIC_CONVENTION_LEN 2 - -// TODO: This should probably use SNPE directly. -int main(int argc, char* argv[]) { - bool run_optimizer = false, save_binaries = false; - const char *input_file = NULL, *output_file = NULL; - static struct option long_options[] = { - {"in", required_argument, 0, 'i' }, - {"out", required_argument, 0, 'o' }, - {"binary", no_argument, 0, 'b' }, - {"optimize", no_argument, 0, 'f' }, - {0, 0, 0, 0 } - }; - int long_index = 0, opt = 0; - while ((opt = getopt_long_only(argc, argv,"", long_options, &long_index)) != -1) { - switch (opt) { - case 'i': input_file = optarg; break; - case 'o': output_file = optarg; break; - case 'b': save_binaries = true; break; - case 'f': run_optimizer = true; break; - } - } - - // no input? - if (!input_file) { - printf("usage: -i -o --binary --optimize\n"); - return -1; - } - - #define OUTPUT_SIZE 0x10000 - - float *output = (float*)calloc(OUTPUT_SIZE, sizeof(float)); - SNPEModel mdl(input_file, output, 0, USE_GPU_RUNTIME, true); - mdl.thneed->run_optimizer = run_optimizer; - - float state[TEMPORAL_SIZE] = {0}; - float desire[DESIRE_LEN] = {0}; - float traffic_convention[TRAFFIC_CONVENTION_LEN] = {0}; - float *input = (float*)calloc(0x1000000, sizeof(float)); - float *extra = (float*)calloc(0x1000000, sizeof(float)); - - mdl.addRecurrent(state, TEMPORAL_SIZE); - mdl.addDesire(desire, DESIRE_LEN); - mdl.addTrafficConvention(traffic_convention, TRAFFIC_CONVENTION_LEN); - mdl.addImage(input, 0); - mdl.addExtra(extra, 0); - - // first run - printf("************** execute 1 **************\n"); - memset(output, 0, OUTPUT_SIZE * sizeof(float)); - mdl.execute(); - - // don't save? - if (!output_file) { - printf("no output file, exiting\n"); - return 0; - } - - // save model - printf("saving %s with binary %d\n", output_file, save_binaries); - mdl.thneed->save(output_file, save_binaries); - - // test model - auto thneed = new Thneed(true); - thneed->record = false; - thneed->load(output_file); - thneed->clexec(); - thneed->find_inputs_outputs(); - - return 0; -} - diff --git a/selfdrive/modeld/thneed/kernels/convolution_.cl b/selfdrive/modeld/thneed/kernels/convolution_.cl deleted file mode 100644 index 1b9d74b83f..0000000000 --- a/selfdrive/modeld/thneed/kernels/convolution_.cl +++ /dev/null @@ -1,272 +0,0 @@ - read_only image2d_t input, -#ifndef DEPTHWISE - short startPackedInputChannel, - short numPackedInputChannelsForGroup, short totalNumPackedInputChannels, - // typo required for API compatibility - short packedOuputChannelOffset, short totalNumPackedOutputChannels, -#else - short totalNumPackedChannels, -#endif - read_only image2d_t weights, __constant float *biases, - short filterSizeX, short filterSizeY, - write_only image2d_t output, - short paddingX, short paddingY, short strideX, short strideY, -#ifdef SUPPORT_DILATION - short dilationX, short dilationY, -#endif - short neuron, float a, float b, float min_clamp, float max_clamp, -#ifndef DEPTHWISE - // note: these are not supported - __constant float *parameters, __constant float *batchNormBiases, -#endif - short numOutputColumns -#ifdef SUPPORT_ACCUMULATION - , short doAccumulate, read_only image2d_t accumulator -#endif - ) { - -#ifndef NUM_OUTPUTS - #define NUM_OUTPUTS 4 -#endif - - // init - const sampler_t smp = CLK_NORMALIZED_COORDS_FALSE | CLK_ADDRESS_CLAMP | CLK_FILTER_NEAREST; - short packedOutputChannel = get_global_id(0); - short startOutputColumn = mul24((short)get_global_id(1), NUM_OUTPUTS); - short outputRow = get_global_id(2); - -#ifdef DEPTHWISE - short totalNumPackedInputChannels = totalNumPackedChannels; - short totalNumPackedOutputChannels = totalNumPackedChannels; - short startPackedInputChannel = packedOutputChannel; -#endif - - short startX = mad24(mad24(startOutputColumn, strideX, -paddingX), totalNumPackedInputChannels, startPackedInputChannel); - short strideWithChannels = mul24(strideX, totalNumPackedInputChannels); - - float4 outputValues[NUM_OUTPUTS]; - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputValues[i] = (float4)(0, 0, 0, 0); - } - - int2 inputLocation; - inputLocation.y = mad24(outputRow, strideY, -paddingY); - - int2 weightLocation; - weightLocation.x = 0; - weightLocation.y = packedOutputChannel; - -#ifdef DEPTHWISE - -#ifdef SUPPORT_DILATION - - // depthwise convolution - for (short rfRow = 0; rfRow < filterSizeY; ++rfRow) { - for (short rfColumn = 0; rfColumn < filterSizeX; ++rfColumn) { - short dilatedStepX = mul24(totalNumPackedChannels, dilationX); - inputLocation.x = mad24(rfColumn, dilatedStepX, startX); - float4 inputValues[4]; - for (short i = 0; i < 4; ++i) { - inputValues[i] = read_imagef(input, smp, inputLocation); - inputLocation.x += strideWithChannels; - } - float4 weightValues = read_imagef(weights, smp, weightLocation); - ++weightLocation.x; - outputValues[0] += inputValues[0] * weightValues; - outputValues[1] += inputValues[1] * weightValues; - outputValues[2] += inputValues[2] * weightValues; - outputValues[3] += inputValues[3] * weightValues; - } - inputLocation.y += dilationY; - } - -#else - - // depthwise unstrided convolution - for (short rfRow = 0; rfRow < filterSizeY; ++rfRow) { - float4 inputValues[4]; - inputLocation.x = startX; - for (short i = 1; i < 4; ++i) { - inputValues[i] = read_imagef(input, smp, inputLocation); - inputLocation.x += totalNumPackedOutputChannels; - } - for (short rfColumn = 0; rfColumn < filterSizeX; ++rfColumn) { - inputValues[0] = inputValues[1]; - inputValues[1] = inputValues[2]; - inputValues[2] = inputValues[3]; - inputValues[3] = read_imagef(input, smp, inputLocation); - inputLocation.x += totalNumPackedChannels; - float4 weightValues = read_imagef(weights, smp, weightLocation); - ++weightLocation.x; - outputValues[0] += inputValues[0] * weightValues; - outputValues[1] += inputValues[1] * weightValues; - outputValues[2] += inputValues[2] * weightValues; - outputValues[3] += inputValues[3] * weightValues; - } - ++inputLocation.y; - } - -#endif - -#elif defined(ONLY_1X1_CONV) - - // 1x1 convolution - short endPackedInputChannel = startPackedInputChannel + numPackedInputChannelsForGroup; - for (short packedInputChannel = startPackedInputChannel; packedInputChannel < endPackedInputChannel; ++packedInputChannel) { - float4 weightValues[4]; - for (short outChIdx = 0; outChIdx < 4; ++outChIdx) { - weightValues[outChIdx] = read_imagef(weights, smp, weightLocation); - ++weightLocation.x; - } - - inputLocation.x = startX + packedInputChannel; - float4 inputValues[NUM_OUTPUTS]; - for (short i = 0; i < NUM_OUTPUTS; ++i) { - inputValues[i] = read_imagef(input, smp, inputLocation); - inputLocation.x += strideWithChannels; - } - - for (short i = 0; i < NUM_OUTPUTS; ++i) { - float4 curOutputValues = outputValues[i]; - curOutputValues.x += inputValues[i].x * weightValues[0].x; - curOutputValues.x += inputValues[i].y * weightValues[0].y; - curOutputValues.x += inputValues[i].z * weightValues[0].z; - curOutputValues.x += inputValues[i].w * weightValues[0].w; - curOutputValues.y += inputValues[i].x * weightValues[1].x; - curOutputValues.y += inputValues[i].y * weightValues[1].y; - curOutputValues.y += inputValues[i].z * weightValues[1].z; - curOutputValues.y += inputValues[i].w * weightValues[1].w; - curOutputValues.z += inputValues[i].x * weightValues[2].x; - curOutputValues.z += inputValues[i].y * weightValues[2].y; - curOutputValues.z += inputValues[i].z * weightValues[2].z; - curOutputValues.z += inputValues[i].w * weightValues[2].w; - curOutputValues.w += inputValues[i].x * weightValues[3].x; - curOutputValues.w += inputValues[i].y * weightValues[3].y; - curOutputValues.w += inputValues[i].z * weightValues[3].z; - curOutputValues.w += inputValues[i].w * weightValues[3].w; - outputValues[i] = curOutputValues; - } - } - packedOutputChannel += packedOuputChannelOffset; - -#else - - // normal convolution - for (short rfRow = 0; rfRow < filterSizeY; ++rfRow) { - for (short packedInputChannel = 0; packedInputChannel < numPackedInputChannelsForGroup; ++packedInputChannel) { - short startXForChannel = startX + packedInputChannel; - for (short rfColumn = 0; rfColumn < filterSizeX; ++rfColumn) { - - float4 weightValues[4]; - for (short outChIdx = 0; outChIdx < 4; ++outChIdx) { - weightValues[outChIdx] = read_imagef(weights, smp, weightLocation); - ++weightLocation.x; - } - -#ifdef SUPPORT_DILATION - short dilatedStepX = mul24(totalNumPackedInputChannels, dilationX); - inputLocation.x = mad24(rfColumn, dilatedStepX, startXForChannel); -#else - inputLocation.x = mad24(rfColumn, totalNumPackedInputChannels, startXForChannel); -#endif - float4 inputValues[NUM_OUTPUTS]; - for (short i = 0; i < NUM_OUTPUTS; ++i) { - inputValues[i] = read_imagef(input, smp, inputLocation); - inputLocation.x += strideWithChannels; - } - for (short i = 0; i < NUM_OUTPUTS; ++i) { - float4 curOutputValues = outputValues[i]; - curOutputValues.x += inputValues[i].x * weightValues[0].x; - curOutputValues.x += inputValues[i].y * weightValues[0].y; - curOutputValues.x += inputValues[i].z * weightValues[0].z; - curOutputValues.x += inputValues[i].w * weightValues[0].w; - curOutputValues.y += inputValues[i].x * weightValues[1].x; - curOutputValues.y += inputValues[i].y * weightValues[1].y; - curOutputValues.y += inputValues[i].z * weightValues[1].z; - curOutputValues.y += inputValues[i].w * weightValues[1].w; - curOutputValues.z += inputValues[i].x * weightValues[2].x; - curOutputValues.z += inputValues[i].y * weightValues[2].y; - curOutputValues.z += inputValues[i].z * weightValues[2].z; - curOutputValues.z += inputValues[i].w * weightValues[2].w; - curOutputValues.w += inputValues[i].x * weightValues[3].x; - curOutputValues.w += inputValues[i].y * weightValues[3].y; - curOutputValues.w += inputValues[i].z * weightValues[3].z; - curOutputValues.w += inputValues[i].w * weightValues[3].w; - outputValues[i] = curOutputValues; - } - } - } -#ifdef SUPPORT_DILATION - inputLocation.y += dilationY; -#else - ++inputLocation.y; -#endif - } - packedOutputChannel += packedOuputChannelOffset; -#endif - - // bias - short outputChannel = mul24(packedOutputChannel, 4); - float4 biasValues = vload4(0, biases + outputChannel); - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputValues[i] += biasValues; - } - -#ifdef SUPPORT_ACCUMULATION - // accumulate - if (doAccumulate) { - int2 outputLocation; - short outputColumn = startOutputColumn; - outputLocation.y = outputRow; - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputLocation.x = mad24(outputColumn, totalNumPackedOutputChannels, packedOutputChannel); - if (outputColumn < numOutputColumns) { - outputValues[i] += read_imagef(accumulator, smp, outputLocation); - } - ++outputColumn; - } - } -#endif - - // activation - switch (neuron) { - case 1: - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputValues[i] = max(outputValues[i], 0.0f); - } - break; - case 2: - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputValues[i] = a * tanh(b * outputValues[i]); - } - break; - case 3: - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputValues[i] = native_recip(1.0f + native_exp(-a * outputValues[i] + b)); - } - break; - case 4: - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputValues[i] = max(outputValues[i], min_clamp); - outputValues[i] = min(outputValues[i], max_clamp); - } - break; - case 5: - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputValues[i] = max(outputValues[i], 0.0f) + a * (native_exp(min(outputValues[i], 0.0f)) - 1.0f); - } - break; - } - - // output - int2 outputLocation; - short outputColumn = startOutputColumn; - outputLocation.y = outputRow; - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputLocation.x = mad24(outputColumn, totalNumPackedOutputChannels, packedOutputChannel); - if (outputColumn < numOutputColumns) { - write_imagef(output, outputLocation, outputValues[i]); - } - ++outputColumn; - } -} diff --git a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads.cl b/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads.cl deleted file mode 100644 index fcea88ce90..0000000000 --- a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads.cl +++ /dev/null @@ -1,3 +0,0 @@ -#define SUPPORT_DILATION - -__kernel void convolution_horizontal_reduced_reads( diff --git a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_1x1.cl b/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_1x1.cl deleted file mode 100644 index 0d15d80581..0000000000 --- a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_1x1.cl +++ /dev/null @@ -1,4 +0,0 @@ -#define ONLY_1X1_CONV -#define SUPPORT_ACCUMULATION - -__kernel void convolution_horizontal_reduced_reads_1x1( diff --git a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_5_outputs.cl b/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_5_outputs.cl deleted file mode 100644 index 69421fc2a9..0000000000 --- a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_5_outputs.cl +++ /dev/null @@ -1,3 +0,0 @@ -#define NUM_OUTPUTS 5 - -__kernel void convolution_horizontal_reduced_reads_5_outputs( diff --git a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise.cl b/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise.cl deleted file mode 100644 index 50e39941d4..0000000000 --- a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise.cl +++ /dev/null @@ -1,4 +0,0 @@ -#define DEPTHWISE -#define SUPPORT_DILATION - -__kernel void convolution_horizontal_reduced_reads_depthwise( diff --git a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise_stride_1.cl b/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise_stride_1.cl deleted file mode 100644 index b347cb6c71..0000000000 --- a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise_stride_1.cl +++ /dev/null @@ -1,3 +0,0 @@ -#define DEPTHWISE - -__kernel void convolution_horizontal_reduced_reads_depthwise_stride_1( diff --git a/selfdrive/modeld/thneed/optimizer.cc b/selfdrive/modeld/thneed/optimizer.cc deleted file mode 100644 index 39737d3d76..0000000000 --- a/selfdrive/modeld/thneed/optimizer.cc +++ /dev/null @@ -1,261 +0,0 @@ -#include -#include -#include -#include -#include "thneed.h" - -#include "common/util.h" -#include "common/clutil.h" - -extern map g_program_source; - -/*static int is_same_size_image(cl_mem a, cl_mem b) { - size_t a_width, a_height, a_depth, a_array_size, a_row_pitch, a_slice_pitch; - clGetImageInfo(a, CL_IMAGE_WIDTH, sizeof(a_width), &a_width, NULL); - clGetImageInfo(a, CL_IMAGE_HEIGHT, sizeof(a_height), &a_height, NULL); - clGetImageInfo(a, CL_IMAGE_DEPTH, sizeof(a_depth), &a_depth, NULL); - clGetImageInfo(a, CL_IMAGE_ARRAY_SIZE, sizeof(a_array_size), &a_array_size, NULL); - clGetImageInfo(a, CL_IMAGE_ROW_PITCH, sizeof(a_row_pitch), &a_row_pitch, NULL); - clGetImageInfo(a, CL_IMAGE_SLICE_PITCH, sizeof(a_slice_pitch), &a_slice_pitch, NULL); - - size_t b_width, b_height, b_depth, b_array_size, b_row_pitch, b_slice_pitch; - clGetImageInfo(b, CL_IMAGE_WIDTH, sizeof(b_width), &b_width, NULL); - clGetImageInfo(b, CL_IMAGE_HEIGHT, sizeof(b_height), &b_height, NULL); - clGetImageInfo(b, CL_IMAGE_DEPTH, sizeof(b_depth), &b_depth, NULL); - clGetImageInfo(b, CL_IMAGE_ARRAY_SIZE, sizeof(b_array_size), &b_array_size, NULL); - clGetImageInfo(b, CL_IMAGE_ROW_PITCH, sizeof(b_row_pitch), &b_row_pitch, NULL); - clGetImageInfo(b, CL_IMAGE_SLICE_PITCH, sizeof(b_slice_pitch), &b_slice_pitch, NULL); - - return (a_width == b_width) && (a_height == b_height) && - (a_depth == b_depth) && (a_array_size == b_array_size) && - (a_row_pitch == b_row_pitch) && (a_slice_pitch == b_slice_pitch); -}*/ - -static cl_mem make_image_like(cl_context context, cl_mem val) { - cl_image_format format; - size_t width, height, row_pitch; - clGetImageInfo(val, CL_IMAGE_FORMAT, sizeof(format), &format, NULL); - assert(format.image_channel_order == CL_RGBA); - assert(format.image_channel_data_type == CL_HALF_FLOAT); - clGetImageInfo(val, CL_IMAGE_WIDTH, sizeof(width), &width, NULL); - clGetImageInfo(val, CL_IMAGE_HEIGHT, sizeof(height), &height, NULL); - clGetImageInfo(val, CL_IMAGE_ROW_PITCH, sizeof(row_pitch), &row_pitch, NULL); - - cl_image_desc desc = {0}; - desc.image_type = CL_MEM_OBJECT_IMAGE2D; - desc.image_width = width; - desc.image_height = height; - desc.image_row_pitch = row_pitch; - - cl_mem buf = clCreateBuffer(context, CL_MEM_READ_WRITE, row_pitch*height, NULL, NULL); - assert(buf != NULL); - desc.buffer = buf; - - cl_int err; - cl_mem tmp = clCreateImage(context, CL_MEM_READ_WRITE, &format, &desc, NULL, &err); - //printf("got %d for image %zux%zu %zu\n", err, width, height, row_pitch); - assert(tmp != NULL); - - return tmp; -} - -// convolution_horizontal_reduced_reads_1x1 is 66% of the model runtime -// make that faster and the model gets faster - -// this cuts ~2 ms off the model runtime right now -int Thneed::optimize() { - const char *kernel_path = getenv("KERNEL_PATH"); - if (!kernel_path) { kernel_path = "/data/openpilot/selfdrive/modeld/thneed/kernels"; printf("no KERNEL_PATH set, defaulting to %s\n", kernel_path); } - - string convolution_; - { - char fn[0x100]; - snprintf(fn, sizeof(fn), "%s/%s.cl", kernel_path, "convolution_"); - convolution_ = util::read_file(fn); - } - - // load custom kernels - map g_programs; - for (auto &k : kq) { - // replace program? - if (g_programs.find(k->name) == g_programs.end()) { - char fn[0x100]; - snprintf(fn, sizeof(fn), "%s/%s.cl", kernel_path, k->name.c_str()); - if (util::file_exists(fn)) { - string kernel_src = util::read_file(fn); - if (k->name.rfind("convolution_", 0) == 0) { - kernel_src += convolution_; - } - printf("building kernel %s with len %lu\n", k->name.c_str(), kernel_src.length()); - k->program = cl_program_from_source(context, device_id, kernel_src); - - // save in cache - g_programs[k->name] = k->program; - g_program_source[k->program] = kernel_src; - } else { - g_programs[k->name] = NULL; - } - } else { - // cached replacement - if (g_programs[k->name] != NULL) { - k->program = g_programs[k->name]; - } - } - - // hack in accumulator to convolution_horizontal_reduced_reads_1x1 - if (k->name == "convolution_horizontal_reduced_reads_1x1") { - k->arg_names.push_back("doAccumulate"); - short doAccumulate = 0; - k->args.push_back(string((char *)&doAccumulate, sizeof(doAccumulate))); - k->args_size.push_back(2); - k->arg_names.push_back("accumulator"); - k->args.push_back(k->args[k->get_arg_num("output")]); - k->args_size.push_back(8); - k->num_args += 2; - } - - // assert that parameters + batchNormBiases are not used - // since they aren't supported in custom replacement kernels - if (k->name == "convolution_horizontal_reduced_reads_1x1" || - k->name == "convolution_horizontal_reduced_reads" || - k->name == "convolution_horizontal_reduced_reads_5_outputs") { - string p1 = k->args[k->get_arg_num("parameters")]; - string p2 = k->args[k->get_arg_num("batchNormBiases")]; - assert(p1.length() == 8 && *((uint64_t*)p1.data()) == 0); - assert(p2.length() == 8 && *((uint64_t*)p2.data()) == 0); - } - } - - // optimizer - size_t start_size; - do { - start_size = kq.size(); - - // get optimizations - map replacements; - for (int i = 0; i < kq.size(); i++) { - // fusing elementwise_sum + activate_image will save 3 enqueues - - // delete useless copy layers - // saves ~0.7 ms - /*if (kq[i]->name == "concatenation" || kq[i]->name == "flatten") { - string in = kq[i]->args[kq[i]->get_arg_num("input")]; - string out = kq[i]->args[kq[i]->get_arg_num("output")]; - if (is_same_size_image(*(cl_mem*)in.data(), *(cl_mem*)out.data())) { - cl_mem tmp = make_image_like(context, *(cl_mem *)in.data()); - replacements[in] = string((char *)&tmp, sizeof(tmp)); - replacements[out] = string((char *)&tmp, sizeof(tmp)); - - kq.erase(kq.begin()+i); --i; - } - }*/ - - // NOTE: if activations/accumulation are done in the wrong order, this will be wrong - - // fuse activations into convs and fc_Wtx - // saves ~1.5 ms - // NOTE: this changes the outputs because of rounding, should be better now! - if (i != 0 && kq[i]->name == "activate_image") { - if (kq[i-1]->name == "convolution_horizontal_reduced_reads_1x1" || - kq[i-1]->name == "convolution_horizontal_reduced_reads_5_outputs" || - kq[i-1]->name == "convolution_horizontal_reduced_reads" || - kq[i-1]->name == "convolution_horizontal_reduced_reads_depthwise" || - kq[i-1]->name == "convolution_horizontal_reduced_reads_depthwise_stride_1" || - kq[i-1]->name == "fc_Wtx") { - string lastout = kq[i-1]->args[kq[i-1]->get_arg_num("output")]; - string in = kq[i]->args[kq[i]->get_arg_num("input")]; - string out = kq[i]->args[kq[i]->get_arg_num("output")]; - - if (lastout == in) { - short neuron = *(int*)kq[i]->args[kq[i]->get_arg_num("neuron")].data(); - assert(neuron <= 5); - - // ELU isn't supported in fc_Wtx - assert(!(kq[i-1]->name == "fc_Wtx" && neuron == 5)); - - kq[i-1]->args[kq[i-1]->get_arg_num("neuron")] = string((char *)&neuron, sizeof(neuron)); - - cl_mem tmp = make_image_like(context, *(cl_mem *)lastout.data()); - replacements[in] = string((char *)&tmp, sizeof(tmp)); - replacements[out] = string((char *)&tmp, sizeof(tmp)); - - kq.erase(kq.begin()+i); --i; - } - } - } - - // fuse accumulation into convs and fc_Wtx - if (i != 0 && kq[i]->name == "elementwise_sum") { - if (kq[i-1]->name == "convolution_horizontal_reduced_reads_1x1" || - kq[i-1]->name == "fc_Wtx") { - string lastout = kq[i-1]->args[kq[i-1]->get_arg_num("output")]; - string a = kq[i]->args[kq[i]->get_arg_num("a")]; - string b = kq[i]->args[kq[i]->get_arg_num("b")]; - string out = kq[i]->args[kq[i]->get_arg_num("output")]; - - if (lastout == a) { - kq[i-1]->args[kq[i-1]->get_arg_num("accumulator")] = b; - } else if (lastout == b) { - kq[i-1]->args[kq[i-1]->get_arg_num("accumulator")] = a; - } else { - continue; - } - - cl_mem tmp = make_image_like(context, *(cl_mem *)lastout.data()); - replacements[lastout] = string((char *)&tmp, sizeof(tmp)); - replacements[out] = string((char *)&tmp, sizeof(tmp)); - - short doAccumulate = 1; - kq[i-1]->args[kq[i-1]->get_arg_num("doAccumulate")] = string((char *)&doAccumulate, sizeof(doAccumulate)); - - kq.erase(kq.begin()+i); --i; - } - } - } - - // remap inputs and outputs, and clear the kernels - for (int i = 0; i < kq.size(); i++) { - kq[i]->kernel = NULL; - for (int j = 0; j < kq[i]->num_args; j++) { - if (replacements.find(kq[i]->args[j]) != replacements.end()) { - kq[i]->args[j] = replacements[kq[i]->args[j]]; - } - } - } - - printf("optimize %lu -> %lu\n", start_size, kq.size()); - } while (kq.size() != start_size); - - size_t work_group_size = 0; - clGetDeviceInfo(device_id, CL_DEVICE_MAX_WORK_GROUP_SIZE, sizeof(work_group_size), &work_group_size, NULL); - printf("max work group size %lu\n", work_group_size); - - // local work group optimizer - for (auto &k : kq) { - // only do it for convs, since others might share memory - if (k->name.rfind("convolution_", 0) == 0) { - int best = -1; - if (k->local_work_size[0] * k->local_work_size[1] * k->local_work_size[2] < work_group_size/2) { - uint64_t base_time = k->benchmark(); - uint64_t best_time = base_time; - for (int i = 0; i < 3; i++) { - k->local_work_size[i] *= 2; - uint64_t this_time = k->benchmark(); - if (this_time < best_time) { - best = i; - best_time = this_time; - } - k->local_work_size[i] /= 2; - } - if (best != -1) { - k->local_work_size[best] *= 2; - //printf("%s %.2f ms doubled %d to %.2f ms\n", k->name.c_str(), base_time/1e6, best, best_time/1e6); - } - } - - } - } - - return 0; -} - diff --git a/selfdrive/modeld/thneed/serialize.cc b/selfdrive/modeld/thneed/serialize.cc index afc84ee769..f789e5bf57 100644 --- a/selfdrive/modeld/thneed/serialize.cc +++ b/selfdrive/modeld/thneed/serialize.cc @@ -152,155 +152,3 @@ void Thneed::load(const char *filename) { clFinish(command_queue); } - -void Thneed::save(const char *filename, bool save_binaries) { - printf("Thneed::save: saving to %s\n", filename); - - // get kernels - std::vector kernels; - std::set saved_objects; - std::vector objects; - std::map programs; - std::map binaries; - - for (auto &k : kq) { - kernels.push_back(k->to_json()); - - // check args for objects - int i = 0; - for (auto &a : k->args) { - if (a.size() == 8) { - if (saved_objects.find(a) == saved_objects.end()) { - saved_objects.insert(a); - cl_mem val = *(cl_mem*)(a.data()); - if (val != NULL) { - bool needs_load = k->arg_names[i] == "weights" || k->arg_names[i] == "biases"; - - auto jj = Json::object({ - {"id", a}, - {"arg_type", k->arg_types[i]}, - }); - - if (k->arg_types[i] == "image2d_t" || k->arg_types[i] == "image1d_t") { - cl_mem buf = NULL; - clGetImageInfo(val, CL_IMAGE_BUFFER, sizeof(buf), &buf, NULL); - string aa = string((char *)&buf, sizeof(buf)); - jj["buffer_id"] = aa; - - size_t width, height, row_pitch; - clGetImageInfo(val, CL_IMAGE_WIDTH, sizeof(width), &width, NULL); - clGetImageInfo(val, CL_IMAGE_HEIGHT, sizeof(height), &height, NULL); - clGetImageInfo(val, CL_IMAGE_ROW_PITCH, sizeof(row_pitch), &row_pitch, NULL); - jj["width"] = (int)width; - jj["height"] = (int)height; - jj["row_pitch"] = (int)row_pitch; - jj["size"] = (int)(height * row_pitch); - jj["needs_load"] = false; - jj["float32"] = false; - - if (saved_objects.find(aa) == saved_objects.end()) { - saved_objects.insert(aa); - size_t sz; - clGetMemObjectInfo(buf, CL_MEM_SIZE, sizeof(sz), &sz, NULL); - // save the buffer - objects.push_back(Json::object({ - {"id", aa}, - {"arg_type", ""}, - {"needs_load", needs_load}, - {"size", (int)sz} - })); - if (needs_load) assert(sz == height * row_pitch); - } - } else { - size_t sz = 0; - clGetMemObjectInfo(val, CL_MEM_SIZE, sizeof(sz), &sz, NULL); - jj["size"] = (int)sz; - jj["needs_load"] = needs_load; - } - - objects.push_back(jj); - } - } - } - i++; - } - - if (save_binaries) { - int err; - size_t binary_size = 0; - err = clGetProgramInfo(k->program, CL_PROGRAM_BINARY_SIZES, sizeof(binary_size), &binary_size, NULL); - assert(err == 0); - assert(binary_size > 0); - string sv(binary_size, '\x00'); - - uint8_t* bufs[1] = { (uint8_t*)sv.data(), }; - err = clGetProgramInfo(k->program, CL_PROGRAM_BINARIES, sizeof(bufs), &bufs, NULL); - assert(err == 0); - - binaries[k->name] = sv; - } else { - programs[k->name] = g_program_source[k->program]; - } - } - - vector saved_buffers; - for (auto &obj : objects) { - auto mobj = obj.object_items(); - cl_mem val = *(cl_mem*)(mobj["id"].string_value().data()); - int sz = mobj["size"].int_value(); - if (mobj["needs_load"].bool_value()) { - char *buf = (char *)malloc(sz); - if (mobj["arg_type"] == "image2d_t" || mobj["arg_type"] == "image1d_t") { - assert(false); - } else { - // buffers allocated with CL_MEM_HOST_WRITE_ONLY, hence this hack - //hexdump((uint32_t*)val, 0x100); - - // the worst hack in thneed, the flags are at 0x14 - ((uint32_t*)val)[0x14] &= ~CL_MEM_HOST_WRITE_ONLY; - cl_int ret = clEnqueueReadBuffer(command_queue, val, CL_TRUE, 0, sz, buf, 0, NULL, NULL); - assert(ret == CL_SUCCESS); - } - //printf("saving buffer: %d %p %s\n", sz, buf, mobj["arg_type"].string_value().c_str()); - saved_buffers.push_back(string(buf, sz)); - free(buf); - } - } - - std::vector jbinaries; - for (auto &obj : binaries) { - jbinaries.push_back(Json::object({{"name", obj.first}, {"length", (int)obj.second.size()}})); - saved_buffers.push_back(obj.second); - } - - Json jdat = Json::object({ - {"kernels", kernels}, - {"objects", objects}, - {"programs", programs}, - {"binaries", jbinaries}, - }); - - string str = jdat.dump(); - int jsz = str.length(); - - FILE *f = fopen(filename, "wb"); - fwrite(&jsz, 1, sizeof(jsz), f); - fwrite(str.data(), 1, jsz, f); - for (auto &s : saved_buffers) { - fwrite(s.data(), 1, s.length(), f); - } - fclose(f); -} - -Json CLQueuedKernel::to_json() const { - return Json::object { - { "name", name }, - { "work_dim", (int)work_dim }, - { "global_work_size", Json::array { (int)global_work_size[0], (int)global_work_size[1], (int)global_work_size[2] } }, - { "local_work_size", Json::array { (int)local_work_size[0], (int)local_work_size[1], (int)local_work_size[2] } }, - { "num_args", (int)num_args }, - { "args", args }, - { "args_size", args_size }, - }; -} - diff --git a/selfdrive/modeld/thneed/thneed.h b/selfdrive/modeld/thneed/thneed.h index 2a5800f302..65475ccf7f 100644 --- a/selfdrive/modeld/thneed/thneed.h +++ b/selfdrive/modeld/thneed/thneed.h @@ -17,7 +17,6 @@ using namespace std; cl_int thneed_clSetKernelArg(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value); -cl_program thneed_clCreateProgramWithSource(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret); namespace json11 { class Json; @@ -43,7 +42,6 @@ class CLQueuedKernel { const size_t *_global_work_size, const size_t *_local_work_size); cl_int exec(); - uint64_t benchmark(); void debug_print(bool verbose); int get_arg_num(const char *search_arg_name); cl_program program; @@ -96,8 +94,6 @@ class Thneed { void stop(); void execute(float **finputs, float *foutput, bool slow=false); void wait(); - int optimize(); - bool run_optimizer = false; vector input_clmem; vector inputs; @@ -121,7 +117,6 @@ class Thneed { #endif // all CL kernels - void find_inputs_outputs(); void copy_inputs(float **finputs, bool internal=false); void copy_output(float *foutput); cl_int clexec(); @@ -130,9 +125,8 @@ class Thneed { // pending CL kernels vector > ckq; - // loading and saving + // loading void load(const char *filename); - void save(const char *filename, bool save_binaries=false); private: void clinit(); }; diff --git a/selfdrive/modeld/thneed/thneed_common.cc b/selfdrive/modeld/thneed/thneed_common.cc index a3f5c908f9..21170b13a6 100644 --- a/selfdrive/modeld/thneed/thneed_common.cc +++ b/selfdrive/modeld/thneed/thneed_common.cc @@ -11,6 +11,11 @@ map, string> g_args; map, int> g_args_size; map g_program_source; +void Thneed::stop() { + printf("Thneed::stop: recorded %lu commands\n", cmds.size()); + record = false; +} + void Thneed::clinit() { device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); if (context == NULL) context = CL_CHECK_ERR(clCreateContext(NULL, 1, &device_id, NULL, NULL, &err)); @@ -131,23 +136,6 @@ cl_int CLQueuedKernel::exec() { kernel, work_dim, NULL, global_work_size, local_work_size, 0, NULL, NULL); } -uint64_t CLQueuedKernel::benchmark() { - uint64_t ret = 0; - int old_record = thneed->record; - thneed->record = 0; - clFinish(thneed->command_queue); - // TODO: benchmarking at a lower level will make this more accurate - for (int i = 0; i < 10; i++) { - uint64_t sb = nanos_since_boot(); - exec(); - clFinish(thneed->command_queue); - uint64_t et = nanos_since_boot() - sb; - if (ret == 0 || et < ret) ret = et; - } - thneed->record = old_record; - return ret; -} - void CLQueuedKernel::debug_print(bool verbose) { printf("%p %56s -- ", kernel, name.c_str()); for (int i = 0; i < work_dim; i++) { @@ -226,10 +214,3 @@ cl_int thneed_clSetKernelArg(cl_kernel kernel, cl_uint arg_index, size_t arg_siz cl_int ret = clSetKernelArg(kernel, arg_index, arg_size, arg_value); return ret; } - -cl_program thneed_clCreateProgramWithSource(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret) { - assert(count == 1); - cl_program ret = clCreateProgramWithSource(context, count, strings, lengths, errcode_ret); - g_program_source[ret] = strings[0]; - return ret; -} \ No newline at end of file diff --git a/selfdrive/modeld/thneed/thneed_pc.cc b/selfdrive/modeld/thneed/thneed_pc.cc index e32dd289ec..8d0037628e 100644 --- a/selfdrive/modeld/thneed/thneed_pc.cc +++ b/selfdrive/modeld/thneed/thneed_pc.cc @@ -30,11 +30,3 @@ void Thneed::execute(float **finputs, float *foutput, bool slow) { printf("model exec in %lu us\n", (te-tb)/1000); } } - -void Thneed::stop() { -} - -void Thneed::find_inputs_outputs() { - // thneed on PC doesn't work on old style inputs/outputs -} - diff --git a/selfdrive/modeld/thneed/thneed_qcom2.cc b/selfdrive/modeld/thneed/thneed_qcom2.cc index f35317d2a7..a29a82c8c8 100644 --- a/selfdrive/modeld/thneed/thneed_qcom2.cc +++ b/selfdrive/modeld/thneed/thneed_qcom2.cc @@ -218,39 +218,6 @@ Thneed::Thneed(bool do_clinit, cl_context _context) { debug = (thneed_debug_env != NULL) ? atoi(thneed_debug_env) : 0; } -void Thneed::stop() { - find_inputs_outputs(); - printf("Thneed::stop: recorded %lu commands\n", cmds.size()); - record = false; -} - -void Thneed::find_inputs_outputs() { - cl_int err; - if (inputs.size() > 0) return; - - // save the global inputs/outputs - for (auto &k : kq) { - for (int i = 0; i < k->num_args; i++) { - if (k->name == "zero_pad_image_float" && k->arg_names[i] == "input") { - cl_mem aa = *(cl_mem*)(k->args[i].data()); - input_clmem.push_back(aa); - - size_t sz; - clGetMemObjectInfo(aa, CL_MEM_SIZE, sizeof(sz), &sz, NULL); - input_sizes.push_back(sz); - - void *ret = clEnqueueMapBuffer(command_queue, aa, CL_TRUE, CL_MAP_WRITE, 0, sz, 0, NULL, NULL, &err); - assert(err == CL_SUCCESS); - inputs.push_back(ret); - } - - if (k->name == "image2d_to_buffer_float" && k->arg_names[i] == "output") { - output = *(cl_mem*)(k->args[i].data()); - } - } - } -} - void Thneed::wait() { struct kgsl_device_waittimestamp_ctxtid wait; wait.context_id = context_id; @@ -314,74 +281,3 @@ void Thneed::execute(float **finputs, float *foutput, bool slow) { printf("model exec in %lu us\n", (te-tb)/1000); } } - -// *********** OpenCL interceptor *********** - -cl_int thneed_clEnqueueNDRangeKernel(cl_command_queue command_queue, - cl_kernel kernel, - cl_uint work_dim, - const size_t *global_work_offset, - const size_t *global_work_size, - const size_t *local_work_size, - cl_uint num_events_in_wait_list, - const cl_event *event_wait_list, - cl_event *event) { - - Thneed *thneed = g_thneed; - - // SNPE doesn't use these - assert(num_events_in_wait_list == 0); - assert(global_work_offset == NULL); - assert(event_wait_list == NULL); - - cl_int ret = 0; - if (thneed != NULL && thneed->record) { - if (thneed->context == NULL) { - thneed->command_queue = command_queue; - clGetKernelInfo(kernel, CL_KERNEL_CONTEXT, sizeof(thneed->context), &thneed->context, NULL); - clGetContextInfo(thneed->context, CL_CONTEXT_DEVICES, sizeof(thneed->device_id), &thneed->device_id, NULL); - } - - // if we are recording, we don't actually enqueue the kernel - thneed->kq.push_back(unique_ptr(new CLQueuedKernel(thneed, kernel, work_dim, global_work_size, local_work_size))); - *event = NULL; - } else { - ret = clEnqueueNDRangeKernel(command_queue, kernel, work_dim, - global_work_offset, global_work_size, local_work_size, - num_events_in_wait_list, event_wait_list, event); - } - - return ret; -} - -cl_int thneed_clFinish(cl_command_queue command_queue) { - Thneed *thneed = g_thneed; - - if (thneed != NULL && thneed->record) { - if (thneed->run_optimizer) thneed->optimize(); - return thneed->clexec(); - } else { - return clFinish(command_queue); - } -} - -void *dlsym(void *handle, const char *symbol) { -#ifdef QCOM2 - void *(*my_dlsym)(void *handle, const char *symbol) = (void *(*)(void *handle, const char *symbol))((uintptr_t)dlopen + DLSYM_OFFSET); -#else - #error "Unsupported platform for thneed" -#endif - if (memcmp("REAL_", symbol, 5) == 0) { - return my_dlsym(handle, symbol+5); - } else if (strcmp("clFinish", symbol) == 0) { - return (void*)thneed_clFinish; - } else if (strcmp("clEnqueueNDRangeKernel", symbol) == 0) { - return (void*)thneed_clEnqueueNDRangeKernel; - } else if (strcmp("clSetKernelArg", symbol) == 0) { - return (void*)thneed_clSetKernelArg; - } else if (strcmp("clCreateProgramWithSource", symbol) == 0) { - return (void*)thneed_clCreateProgramWithSource; - } else { - return my_dlsym(handle, symbol); - } -} diff --git a/selfdrive/modeld/thneed/weights_fixup.py b/selfdrive/modeld/thneed/weights_fixup.py deleted file mode 100755 index 539b1b5d32..0000000000 --- a/selfdrive/modeld/thneed/weights_fixup.py +++ /dev/null @@ -1,146 +0,0 @@ -#!/usr/bin/env python3 -import os -import struct -import zipfile -import numpy as np -from tqdm import tqdm - -from common.basedir import BASEDIR -from selfdrive.modeld.thneed.lib import load_thneed, save_thneed - -# this is junk code, but it doesn't have deps -def load_dlc_weights(fn): - archive = zipfile.ZipFile(fn, 'r') - dlc_params = archive.read("model.params") - - def extract(rdat): - idx = rdat.find(b"\x00\x00\x00\x09\x04\x00\x00\x00") - rdat = rdat[idx+8:] - ll = struct.unpack("I", rdat[0:4])[0] - buf = np.frombuffer(rdat[4:4+ll*4], dtype=np.float32) - rdat = rdat[4+ll*4:] - dims = struct.unpack("I", rdat[0:4])[0] - buf = buf.reshape(struct.unpack("I"*dims, rdat[4:4+dims*4])) - if len(buf.shape) == 4: - buf = np.transpose(buf, (3,2,0,1)) - return buf - - def parse(tdat): - ll = struct.unpack("I", tdat[0:4])[0] + 4 - return (None, [extract(tdat[0:]), extract(tdat[ll:])]) - - ptr = 0x20 - def r4(): - nonlocal ptr - ret = struct.unpack("I", dlc_params[ptr:ptr+4])[0] - ptr += 4 - return ret - ranges = [] - cnt = r4() - for _ in range(cnt): - o = r4() + ptr - # the header is 0xC - plen, is_4, is_2 = struct.unpack("III", dlc_params[o:o+0xC]) - assert is_4 == 4 and is_2 == 2 - ranges.append((o+0xC, o+plen+0xC)) - ranges = sorted(ranges, reverse=True) - - return [parse(dlc_params[s:e]) for s,e in ranges] - -# this won't run on device without onnx -def load_onnx_weights(fn): - import onnx - from onnx import numpy_helper - - model = onnx.load(fn) - graph = model.graph # pylint: disable=maybe-no-member - init = {x.name:x for x in graph.initializer} - - onnx_layers = [] - for node in graph.node: - #print(node.name, node.op_type, node.input, node.output) - vals = [] - for inp in node.input: - if inp in init: - vals.append(numpy_helper.to_array(init[inp])) - if len(vals) > 0: - onnx_layers.append((node.name, vals)) - return onnx_layers - -def weights_fixup(target, source_thneed, dlc): - #onnx_layers = load_onnx_weights(os.path.join(BASEDIR, "models/supercombo.onnx")) - onnx_layers = load_dlc_weights(dlc) - jdat = load_thneed(source_thneed) - - bufs = {} - for o in jdat['objects']: - bufs[o['id']] = o - - thneed_layers = [] - for k in jdat['kernels']: - #print(k['name']) - vals = [] - for a in k['args']: - if a in bufs: - o = bufs[a] - if o['needs_load'] or ('buffer_id' in o and bufs[o['buffer_id']]['needs_load']): - #print(" ", o['arg_type']) - vals.append(o) - if len(vals) > 0: - thneed_layers.append((k['name'], vals)) - - assert len(thneed_layers) == len(onnx_layers) - - # fix up weights - for tl, ol in tqdm(zip(thneed_layers, onnx_layers), total=len(thneed_layers)): - #print(tl[0], ol[0]) - assert len(tl[1]) == len(ol[1]) - for o, onnx_weight in zip(tl[1], ol[1]): - if o['arg_type'] == "image2d_t": - obuf = bufs[o['buffer_id']] - saved_weights = np.frombuffer(obuf['data'], dtype=np.float16).reshape(o['height'], o['row_pitch']//2) - - if len(onnx_weight.shape) == 4: - # convolution - oc,ic,ch,cw = onnx_weight.shape - - if 'depthwise' in tl[0]: - assert ic == 1 - weights = np.transpose(onnx_weight.reshape(oc//4,4,ch,cw), (0,2,3,1)).reshape(o['height'], o['width']*4) - else: - weights = np.transpose(onnx_weight.reshape(oc//4,4,ic//4,4,ch,cw), (0,4,2,5,1,3)).reshape(o['height'], o['width']*4) - else: - # fc_Wtx - weights = onnx_weight - - new_weights = np.zeros((o['height'], o['row_pitch']//2), dtype=np.float32) - new_weights[:, :weights.shape[1]] = weights - - # weights shouldn't be too far off - err = np.mean((saved_weights.astype(np.float32) - new_weights)**2) - assert err < 1e-3 - rerr = np.mean(np.abs((saved_weights.astype(np.float32) - new_weights)/(new_weights+1e-12))) - assert rerr < 0.5 - - # fix should improve things - fixed_err = np.mean((new_weights.astype(np.float16).astype(np.float32) - new_weights)**2) - assert (err/fixed_err) >= 1 - - #print(" ", o['size'], onnx_weight.shape, o['row_pitch'], o['width'], o['height'], "err %.2fx better" % (err/fixed_err)) - - obuf['data'] = new_weights.astype(np.float16).tobytes() - - elif o['arg_type'] == "float*": - # unconverted floats are correct - new_weights = np.zeros(o['size']//4, dtype=np.float32) - new_weights[:onnx_weight.shape[0]] = onnx_weight - assert new_weights.tobytes() == o['data'] - #print(" ", o['size'], onnx_weight.shape) - - save_thneed(jdat, target) - -if __name__ == "__main__": - model_dir = os.path.join(BASEDIR, "selfdrive/modeld/models/") - weights_fixup(os.path.join(model_dir, "supercombo_fixed.thneed"), - os.path.join(model_dir, "supercombo.thneed"), - os.path.join(model_dir, "supercombo.dlc")) From 502a39219932172d52ee0f280c5200ba11bca0c9 Mon Sep 17 00:00:00 2001 From: Jeroen Date: Fri, 2 Sep 2022 04:05:15 +0200 Subject: [PATCH 009/152] bootlog: only do nvme checks on tici (#25634) --- selfdrive/loggerd/bootlog.cc | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/loggerd/bootlog.cc b/selfdrive/loggerd/bootlog.cc index 90ba487ff0..6ff052655a 100644 --- a/selfdrive/loggerd/bootlog.cc +++ b/selfdrive/loggerd/bootlog.cc @@ -26,10 +26,13 @@ static kj::Array build_boot_log() { // Gather output of commands std::vector bootlog_commands = { - "[ -e /dev/nvme0 ] && sudo nvme smart-log --output-format=json /dev/nvme0", "[ -x \"$(command -v journalctl)\" ] && journalctl", }; + if (Hardware::TICI()) { + bootlog_commands.push_back("[ -e /dev/nvme0 ] && sudo nvme smart-log --output-format=json /dev/nvme0"); + } + auto commands = boot.initCommands().initEntries(bootlog_commands.size()); for (int j = 0; j < bootlog_commands.size(); j++) { auto lentry = commands[j]; From 6b236b4edd2028521e0a36fe59547ee0115751f0 Mon Sep 17 00:00:00 2001 From: Alex Ye <49353607+FeistyFinn@users.noreply.github.com> Date: Thu, 1 Sep 2022 22:23:49 -0400 Subject: [PATCH 010/152] Toyota: Add missing engine FW 2020 Corolla (#25626) * Toyota: Add missing engine FW 2020 Corolla 2020 Corolla LE (2ZR-FAE) Dongle/route: 73fed27d198f6a7d|2022-08-31--17-41-34 * Made entry alphabetical --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 5649e7d65a..42a67ec969 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -718,6 +718,7 @@ FW_VERSIONS = { b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', b'\x02312K4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02312U5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', ], From fd7525d806eb6fb6bd397db0dd95325d4175b979 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 1 Sep 2022 21:51:48 -0700 Subject: [PATCH 011/152] Chrysler: support convenience blinkers (#25644) Co-authored-by: Comma Device --- selfdrive/car/chrysler/carstate.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index fefd351a23..0f0d30782a 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -58,8 +58,8 @@ class CarState(CarStateBase): ) # button presses - ret.leftBlinker = cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 1 - ret.rightBlinker = cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 2 + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk(200, cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 1, + cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 2) ret.genericToggle = cp.vl["STEERING_LEVERS"]["HIGH_BEAM_PRESSED"] == 1 # steering wheel From 7ecc0409bd767392074a37cdd0b7e44ed9953296 Mon Sep 17 00:00:00 2001 From: Robbe Derks Date: Fri, 2 Sep 2022 07:18:44 +0200 Subject: [PATCH 012/152] camerad: read param to see if we want manual gain (#25642) * also read params to determine if we want manual gains * check for larger than 0 Co-authored-by: Comma Device --- system/camerad/cameras/camera_qcom2.cc | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index c06aeb4360..a86218c06e 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -1101,14 +1101,18 @@ void CameraState::set_camera_exposure(float grey_frac) { } else if (enable_dc_gain && target_grey > 0.3) { enable_dc_gain = false; } + + std::string gain_bytes, time_bytes; if (env_ctrl_exp_from_params) { + gain_bytes = Params().get("CameraDebugExpGain"); + time_bytes = Params().get("CameraDebugExpTime"); + } + + if (gain_bytes.size() > 0 && time_bytes.size() > 0) { // Override gain and exposure time - if (buf.cur_frame_data.frame_id % 5 == 0) { - std::string gain_bytes = Params().get("CameraDebugExpGain"); - std::string time_bytes = Params().get("CameraDebugExpTime"); - gain_idx = std::stoi(gain_bytes); - exposure_time = std::stoi(time_bytes); - } + gain_idx = std::stoi(gain_bytes); + exposure_time = std::stoi(time_bytes); + new_g = gain_idx; new_t = exposure_time; enable_dc_gain = false; From faff2b8950c3ae0b0dff69c871381416ce2be416 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Fri, 2 Sep 2022 00:24:53 -0700 Subject: [PATCH 013/152] Add e2e long toggle (#25638) * Add toggle * Misc fixes * Update translations * pre alpha not great --- common/params.cc | 1 + .../lib/longitudinal_mpc_lib/long_mpc.py | 10 +- .../controls/lib/longitudinal_planner.py | 9 +- selfdrive/ui/qt/offroad/settings.cc | 6 + selfdrive/ui/translations/main_ja.ts | 136 ++++++++++-------- selfdrive/ui/translations/main_ko.ts | 136 ++++++++++-------- selfdrive/ui/translations/main_pt-BR.ts | 136 ++++++++++-------- selfdrive/ui/translations/main_zh-CHS.ts | 136 ++++++++++-------- selfdrive/ui/translations/main_zh-CHT.ts | 136 ++++++++++-------- 9 files changed, 383 insertions(+), 323 deletions(-) diff --git a/common/params.cc b/common/params.cc index e5071268b7..5c8002dfb7 100644 --- a/common/params.cc +++ b/common/params.cc @@ -100,6 +100,7 @@ std::unordered_map keys = { {"DashcamOverride", PERSISTENT}, {"DisableLogging", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"DisablePowerDown", PERSISTENT}, + {"EndToEndLong", PERSISTENT}, {"DisableRadar_Allow", PERSISTENT}, {"DisableRadar", PERSISTENT}, // WARNING: THIS DISABLES AEB {"DisableUpdates", PERSISTENT}, diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index eaecb63a6b..405ef81916 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -248,13 +248,13 @@ class LongitudinalMpc: cost_weights = [X_EGO_OBSTACLE_COST, X_EGO_COST, V_EGO_COST, A_EGO_COST, a_change_cost, J_EGO_COST] constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, DANGER_ZONE_COST] elif self.mode == 'blended': - cost_weights = [0., 1.0, 0.0, 0.0, 0.0, 1.0] - constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 0.0] + cost_weights = [0., 0.2, 0.25, 1.0, 0.0, 1.0] + constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 5.0] elif self.mode == 'e2e': cost_weights = [0., 0.2, 0.25, 1., 0.0, .1] constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 0.0] else: - raise NotImplementedError(f'Planner mode {self.mode} not recognized') + raise NotImplementedError(f'Planner mode {self.mode} not recognized in planner cost set') self.set_cost_weights(cost_weights, constraint_cost_weights) def set_cur_state(self, v, a): @@ -347,7 +347,7 @@ class LongitudinalMpc: self.source = 'e2e' else: - raise NotImplementedError(f'Planner mode {self.mode} not recognized') + raise NotImplementedError(f'Planner mode {self.mode} not recognized in planner update') self.yref[:,1] = x self.yref[:,2] = v @@ -357,8 +357,6 @@ class LongitudinalMpc: self.solver.set(i, "yref", self.yref[i]) self.solver.set(N, "yref", self.yref[N][:COST_E_DIM]) - x_obstacles = np.column_stack([lead_0_obstacle, lead_1_obstacle, cruise_obstacle]) - self.source = SOURCES[np.argmin(x_obstacles[0])] self.params[:,2] = np.min(x_obstacles, axis=1) self.params[:,3] = np.copy(self.prev_a) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 42ce2bd0ec..b6120d2451 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -6,6 +6,7 @@ from common.numpy_fast import interp import cereal.messaging as messaging from common.conversions import Conversions as CV from common.filter_simple import FirstOrderFilter +from common.params import Params from common.realtime import DT_MDL from selfdrive.modeld.constants import T_IDXS from selfdrive.controls.lib.longcontrol import LongCtrlState @@ -47,7 +48,10 @@ def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): class Planner: def __init__(self, CP, init_v=0.0, init_a=0.0): self.CP = CP - self.mpc = LongitudinalMpc() + params = Params() + # TODO read param in the loop for live toggling + mode = 'blended' if params.get_bool('EndToEndLong') else 'acc' + self.mpc = LongitudinalMpc(mode=mode) self.fcw = False @@ -122,7 +126,8 @@ class Planner: self.j_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC[:-1], self.mpc.j_solution) # TODO counter is only needed because radar is glitchy, remove once radar is gone - self.fcw = self.mpc.crash_cnt > 5 + # TODO write fcw in e2e_long mode + self.fcw = self.mpc.mode == 'acc' and self.mpc.crash_cnt > 5 if self.fcw: cloudlog.info("FCW triggered") diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 5e0e87e64d..09ff0eed94 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -53,6 +53,12 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { tr("Upload data from the driver facing camera and help improve the driver monitoring algorithm."), "../assets/offroad/icon_monitoring.png", }, + { + "EndToEndLong", + tr("🌮 End-to-end longitudinal (extremely alpha) 🌮"), + tr("Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental."), + "../assets/offroad/icon_road.png", + }, { "DisengageOnAccelerator", tr("Disengage On Accelerator Pedal"), diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index dd9f933dcf..d56f4e8466 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID ドングル番号 (Dongle ID) - + N/A N/A - + Serial シリアル番号 - + Driver Camera 車内カメラ - + PREVIEW 見る - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 車内カメラをプレビューして、ドライバー監視システムの視界を確認ができます。(車両の電源を切る必要があります) - + Reset Calibration キャリブレーションをリセット - + RESET リセット - + Are you sure you want to reset calibration? キャリブレーションをリセットしてもよろしいですか? - + Review Training Guide 入門書を見る - + REVIEW 見る - + Review the rules, features, and limitations of openpilot openpilot の特徴を見る - + Are you sure you want to review the training guide? 入門書を見てもよろしいですか? - + Regulatory 認証情報 - + VIEW 見る - + Change Language 言語を変更 - + CHANGE 変更 - + Select a language 言語を選択 - + Reboot 再起動 - + Power Off 電源を切る - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot は、左または右の4°以内、上の5°または下の8°以内にデバイスを取付ける必要があります。キャリブレーションを引き続きます、リセットはほとんど必要ありません。 - + Your device is pointed %1° %2 and %3° %4. このデバイスは%2の%1°、%4の%3°に向けます。 - + down - + up - + left - + right - + Are you sure you want to reboot? 再起動してもよろしいですか? - + Disengage to Reboot openpilot をキャンセルして再起動ができます - + Are you sure you want to power off? シャットダウンしてもよろしいですか? - + Disengage to Power Off openpilot をキャンセルしてシャットダウンができます @@ -718,33 +718,33 @@ location set SettingsWindow - + × × - + Device デバイス - - + + Network ネットワーク - + Toggles 切り替え - + Software ソフトウェア - + Navigation ナビゲーション @@ -983,89 +983,89 @@ location set SoftwarePanel - + Git Branch Git ブランチ - + Git Commit Git コミット - + OS Version OS バージョン - + Version バージョン - + Last Update Check 最終更新確認 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. openpilotが最後にアップデートの確認に成功してからの時間です。アップデート処理は、車の電源が切れているときのみ実行されます。 - + Check for Update 更新プログラムをチェック - + CHECKING 確認中 - + Switch Branch ブランチの切り替え - + ENTER 切替 - - + + The new branch will be pulled the next time the updater runs. updater を実行する時にブランチを切り替えます。 - + Enter branch name ブランチ名を入力 - + UNINSTALL アンインストール - + Uninstall %1 %1をアンインストール - + Are you sure you want to uninstall? アンインストールしてもよろしいですか? - + failed to fetch update 更新のダウンロードにエラーが発生しました - - + + CHECK 確認 @@ -1194,41 +1194,51 @@ location set + 🌮 End-to-end longitudinal (extremely alpha) 🌮 + + + + + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. + + + + Disengage On Accelerator Pedal アクセル踏むと openpilot をキャンセル - + When enabled, pressing the accelerator pedal will disengage openpilot. 有効な場合は、アクセルを踏むと openpilot をキャンセルします。 - + Show ETA in 24h Format 24時間表示 - + Use 24h format instead of am/pm AM/PM の代わりに24時間形式を使用します - + Show Map on Left Side of UI ディスプレイの左側にマップを表示 - + Show map on left side when in split screen view. 分割画面表示の場合、ディスプレイの左側にマップを表示します。 - + openpilot Longitudinal Control openpilot 縦方向制御 - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot は、車のレーダーを無効化し、アクセルとブレーキの制御を引き継ぎます。注意:AEB を無効化にします! diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index d4abe86196..bb4f884aa9 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID Dongle ID - + N/A N/A - + Serial Serial - + Driver Camera 운전자 카메라 - + PREVIEW 미리보기 - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 운전자 모니터링이 좋은 가시성을 갖도록 운전자를 향한 카메라를 미리 봅니다. (차량연결은 해제되어있어야 합니다) - + Reset Calibration 캘리브레이션 재설정 - + RESET 재설정 - + Are you sure you want to reset calibration? 캘리브레이션을 재설정하시겠습니까? - + Review Training Guide 트레이닝 가이드 다시보기 - + REVIEW 다시보기 - + Review the rules, features, and limitations of openpilot openpilot의 규칙, 기능 및 제한 다시보기 - + Are you sure you want to review the training guide? 트레이닝 가이드를 다시보시겠습니까? - + Regulatory 규제 - + VIEW 보기 - + Change Language 언어 변경 - + CHANGE 변경 - + Select a language 언어를 선택하세요 - + Reboot 재부팅 - + Power Off 전원 종료 - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot은 장치를 좌측 또는 우측은 4° 이내, 위쪽 5° 또는 아래쪽은 8° 이내로 설치해야 합니다. openpilot은 지속적으로 보정되므로 리셋이 거의 필요하지 않습니다. - + Your device is pointed %1° %2 and %3° %4. 사용자의 장치가 %1° %2 및 %3° %4를 가리키고 있습니다. - + down 아래로 - + up 위로 - + left 좌측으로 - + right 우측으로 - + Are you sure you want to reboot? 재부팅 하시겠습니까? - + Disengage to Reboot 재부팅 하려면 해제하세요 - + Are you sure you want to power off? 전원을 종료하시겠습니까? - + Disengage to Power Off 전원을 종료하려면 해제하세요 @@ -718,33 +718,33 @@ location set SettingsWindow - + × × - + Device 장치 - - + + Network 네트워크 - + Toggles 토글 - + Software 소프트웨어 - + Navigation 네비게이션 @@ -983,89 +983,89 @@ location set SoftwarePanel - + Git Branch Git 브렌치 - + Git Commit Git 커밋 - + OS Version OS 버전 - + Version 버전 - + Last Update Check 최신 업데이트 검사 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. 최근에 openpilot이 업데이트를 성공적으로 확인했습니다. 업데이트 프로그램은 차량 연결이 해제되었을때만 작동합니다. - + Check for Update 업데이트 확인 - + CHECKING 확인중 - + Switch Branch 브랜치 변경 - + ENTER 입력하세요 - - + + The new branch will be pulled the next time the updater runs. 다음 업데이트 프로그램이 실행될 때 새 브랜치가 적용됩니다. - + Enter branch name 브랜치명 입력 - + UNINSTALL 제거 - + Uninstall %1 %1 제거 - + Are you sure you want to uninstall? 제거하시겠습니까? - + failed to fetch update 업데이트를 가져올수없습니다 - - + + CHECK 확인 @@ -1194,41 +1194,51 @@ location set + 🌮 End-to-end longitudinal (extremely alpha) 🌮 + + + + + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. + + + + Disengage On Accelerator Pedal 가속페달 조작시 해제 - + When enabled, pressing the accelerator pedal will disengage openpilot. 활성화된 경우 가속 페달을 누르면 openpilot이 해제됩니다. - + Show ETA in 24h Format 24시간 형식으로 도착예정시간 표시 - + Use 24h format instead of am/pm 오전/오후 대신 24시간 형식 사용 - + Show Map on Left Side of UI UI 왼쪽에 지도 표시 - + Show map on left side when in split screen view. 분할 화면 보기에서 지도를 왼쪽에 표시합니다. - + openpilot Longitudinal Control openpilot Longitudinal Control - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot은 차량'의 레이더를 무력화시키고 가속페달과 브레이크의 제어를 인계받을 것이다. 경고: AEB를 비활성화합니다! diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index e0d6a3c049..c0ef5c88fe 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID Dongle ID - + N/A N/A - + Serial Serial - + Driver Camera Câmera voltada para o Motorista - + PREVIEW PREVISUAL - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) Pré-visualizar a câmera voltada para o motorista para garantir que monitor tem uma boa visibilidade (veículo precisa estar desligado) - + Reset Calibration Resetar Calibragem - + RESET RESET - + Are you sure you want to reset calibration? Tem certeza que quer resetar a calibragem? - + Review Training Guide Revisar o Treinamento - + REVIEW REVISAR - + Review the rules, features, and limitations of openpilot Revisar regras, aprimoramentos e limitações do openpilot - + Are you sure you want to review the training guide? Tem certeza que quer rever o treinamento? - + Regulatory Regulatório - + VIEW VER - + Change Language Mudar Linguagem - + CHANGE MUDAR - + Select a language Selecione uma linguagem - + Reboot Reiniciar - + Power Off Desligar - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. o openpilot requer que o dispositivo seja montado dentro de 4° esquerda ou direita e dentro de 5° para cima ou 8° para baixo. o openpilot está continuamente calibrando, resetar raramente é necessário. - + Your device is pointed %1° %2 and %3° %4. Seu dispositivo está montado %1° %2 e %3° %4. - + down baixo - + up cima - + left esquerda - + right direita - + Are you sure you want to reboot? Tem certeza que quer reiniciar? - + Disengage to Reboot Desacione para Reiniciar - + Are you sure you want to power off? Tem certeza que quer desligar? - + Disengage to Power Off Desacione para Desligar @@ -722,33 +722,33 @@ trabalho definido SettingsWindow - + × × - + Device Dispositivo - - + + Network Rede - + Toggles Ajustes - + Software Software - + Navigation Navegação @@ -987,89 +987,89 @@ trabalho definido SoftwarePanel - + Git Branch Ramo Git - + Git Commit Commit Git - + OS Version Versão do Sistema - + Version Versão - + Last Update Check Verificação da última atualização - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. A última vez que o openpilot verificou com sucesso uma atualização. O atualizador só funciona com o carro desligado. - + Check for Update Verifique atualizações - + CHECKING VERIFICANDO - + Switch Branch Trocar Branch - + ENTER INSERIR - - + + The new branch will be pulled the next time the updater runs. A nova branch será aplicada ao verificar atualizações. - + Enter branch name Inserir o nome da branch - + UNINSTALL DESINSTALAR - + Uninstall %1 Desintalar o %1 - + Are you sure you want to uninstall? Tem certeza que quer desinstalar? - + failed to fetch update falha ao buscar atualização - - + + CHECK VERIFICAR @@ -1198,41 +1198,51 @@ trabalho definido + 🌮 End-to-end longitudinal (extremely alpha) 🌮 + + + + + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. + + + + Disengage On Accelerator Pedal Desacionar Com Pedal Do Acelerador - + When enabled, pressing the accelerator pedal will disengage openpilot. Quando ativado, pressionar o pedal do acelerador desacionará o openpilot. - + Show ETA in 24h Format Mostrar ETA em formato 24h - + Use 24h format instead of am/pm Use o formato 24h em vez de am/pm - + Show Map on Left Side of UI Exibir Mapa no Lado Esquerdo - + Show map on left side when in split screen view. Exibir mapa do lado esquerdo quando a tela for dividida. - + openpilot Longitudinal Control openpilot Controle Longitudinal - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot desativará o radar do carro e assumirá o controle do acelerador e freios. Atenção: isso desativa AEB! diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index a26cddc0c3..e8c9b8ec52 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID 设备ID(Dongle ID) - + N/A N/A - + Serial 序列号 - + Driver Camera 驾驶员摄像头 - + PREVIEW 预览 - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 打开并预览驾驶员摄像头,以确保驾驶员监控具有良好视野。仅熄火时可用。 - + Reset Calibration 重置设备校准 - + RESET 重置 - + Are you sure you want to reset calibration? 您确定要重置设备校准吗? - + Review Training Guide 新手指南 - + REVIEW 查看 - + Review the rules, features, and limitations of openpilot 查看openpilot的使用规则,以及其功能和限制。 - + Are you sure you want to review the training guide? 您确定要查看新手指南吗? - + Regulatory 监管信息 - + VIEW 查看 - + Change Language 切换语言 - + CHANGE 切换 - + Select a language 选择语言 - + Reboot 重启 - + Power Off 关机 - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot要求设备安装的偏航角在左4°和右4°之间,俯仰角在上5°和下8°之间。一般来说,openpilot会持续更新校准,很少需要重置。 - + Your device is pointed %1° %2 and %3° %4. 您的设备校准为%1° %2、%3° %4。 - + down 朝下 - + up 朝上 - + left 朝左 - + right 朝右 - + Are you sure you want to reboot? 您确定要重新启动吗? - + Disengage to Reboot 取消openpilot以重新启动 - + Are you sure you want to power off? 您确定要关机吗? - + Disengage to Power Off 取消openpilot以关机 @@ -716,33 +716,33 @@ location set SettingsWindow - + × × - + Device 设备 - - + + Network 网络 - + Toggles 设定 - + Software 软件 - + Navigation 导航 @@ -981,89 +981,89 @@ location set SoftwarePanel - + Git Branch Git Branch - + Git Commit Git Commit - + OS Version 系统版本 - + Version 软件版本 - + Last Update Check 上次检查更新 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. 上一次成功检查更新的时间。更新程序仅在汽车熄火时运行。 - + Check for Update 检查更新 - + CHECKING 正在检查更新 - + Switch Branch 切换分支 - + ENTER 输入 - - + + The new branch will be pulled the next time the updater runs. 分支将在更新服务下次启动时自动切换。 - + Enter branch name 输入分支名称 - + UNINSTALL 卸载 - + Uninstall %1 卸载 %1 - + Are you sure you want to uninstall? 您确定要卸载吗? - + failed to fetch update 获取更新失败 - - + + CHECK 查看 @@ -1192,41 +1192,51 @@ location set + 🌮 End-to-end longitudinal (extremely alpha) 🌮 + + + + + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. + + + + Disengage On Accelerator Pedal 踩油门时取消控制 - + When enabled, pressing the accelerator pedal will disengage openpilot. 启用后,踩下油门踏板将取消openpilot。 - + Show ETA in 24h Format 以24小时格式显示预计到达时间 - + Use 24h format instead of am/pm 使用24小时制代替am/pm - + Show Map on Left Side of UI 在介面左侧显示地图 - + Show map on left side when in split screen view. 在分屏模式中,将地图置于屏幕左侧。 - + openpilot Longitudinal Control openpilot纵向控制 - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot将禁用车辆的雷达并接管油门和刹车的控制。警告:AEB将被禁用! diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index f4681f85d9..9b792e6df0 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID Dongle ID - + N/A 無法使用 - + Serial 序號 - + Driver Camera 駕駛員攝像頭 - + PREVIEW 預覽 - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 預覽駕駛員監控鏡頭畫面,以確保其具有良好視野。(僅在熄火時可用) - + Reset Calibration 重置校準 - + RESET 重置 - + Are you sure you want to reset calibration? 您確定要重置校準嗎? - + Review Training Guide 觀看使用教學 - + REVIEW 觀看 - + Review the rules, features, and limitations of openpilot 觀看 openpilot 的使用規則、功能和限制 - + Are you sure you want to review the training guide? 您確定要觀看使用教學嗎? - + Regulatory 法規/監管 - + VIEW 觀看 - + Change Language 更改語言 - + CHANGE 更改 - + Select a language 選擇語言 - + Reboot 重新啟動 - + Power Off 關機 - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot 需要將裝置固定在左右偏差 4° 以內,朝上偏差 5° 以内或朝下偏差 8° 以内。鏡頭在後台會持續自動校準,很少有需要重置的情况。 - + Your device is pointed %1° %2 and %3° %4. 你的設備目前朝%2 %1° 以及朝%4 %3° 。 - + down - + up - + left - + right - + Are you sure you want to reboot? 您確定要重新啟動嗎? - + Disengage to Reboot 請先取消控車才能重新啟動 - + Are you sure you want to power off? 您確定您要關機嗎? - + Disengage to Power Off 請先取消控車才能關機 @@ -718,33 +718,33 @@ location set SettingsWindow - + × × - + Device 設備 - - + + Network 網路 - + Toggles 設定 - + Software 軟體 - + Navigation 導航 @@ -983,89 +983,89 @@ location set SoftwarePanel - + Git Branch Git 分支 - + Git Commit Git 提交 - + OS Version 系統版本 - + Version 版本 - + Last Update Check 上次檢查時間 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. 上次成功檢查更新的時間。更新系統只會在車子熄火時執行。 - + Check for Update 檢查更新 - + CHECKING 檢查中 - + Switch Branch 切換分支 - + ENTER 切換 - - + + The new branch will be pulled the next time the updater runs. 新的分支將會在下次檢查更新時切換過去。 - + Enter branch name 輸入分支名稱 - + UNINSTALL 卸載 - + Uninstall %1 卸載 %1 - + Are you sure you want to uninstall? 您確定您要卸載嗎? - + failed to fetch update 下載更新失敗 - - + + CHECK 檢查 @@ -1194,41 +1194,51 @@ location set + 🌮 End-to-end longitudinal (extremely alpha) 🌮 + + + + + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. + + + + Disengage On Accelerator Pedal 油門取消控車 - + When enabled, pressing the accelerator pedal will disengage openpilot. 啟用後,踩踏油門將會取消 openpilot 控制。 - + Show ETA in 24h Format 預計到達時間單位改用 24 小時制 - + Use 24h format instead of am/pm 使用 24 小時制。(預設值為 12 小時制) - + Show Map on Left Side of UI 將地圖顯示在畫面的左側 - + Show map on left side when in split screen view. 進入分割畫面後,地圖將會顯示在畫面的左側。 - + openpilot Longitudinal Control openpilot 縱向控制 - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot 將會關閉雷達訊號並接管油門和剎車的控制。注意:這也會關閉自動緊急煞車 (AEB) 系統! From b805b138453e175e560df60cba9d83e330f1db8d Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Fri, 2 Sep 2022 14:57:09 -0500 Subject: [PATCH 014/152] VW MQB: Add FW for 2023 Volkswagen Atlas (#25648) --- docs/CARS.md | 2 +- selfdrive/car/volkswagen/values.py | 6 +++++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index aa7b5ecc5b..1bea3f868e 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -185,7 +185,7 @@ A supported vehicle is one that just works when you install a comma three. All s |Volkswagen|Arteon 2018-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| |Volkswagen|Arteon eHybrid 2020-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| |Volkswagen|Arteon R 2020-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Atlas 2018-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Atlas 2018-23[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| |Volkswagen|Atlas Cross Sport 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| |Volkswagen|California 2021[7](#footnotes)|Driver Assistance|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| |Volkswagen|Caravelle 2020[7](#footnotes)|Driver Assistance|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 7b1b0c8762..278f4bc665 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -174,7 +174,7 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = { VWCarInfo("Volkswagen CC 2018-22", footnotes=[Footnote.VW_HARNESS, Footnote.VW_VARIANT], harness=Harness.j533, video_link="https://youtu.be/FAomFKPFlDA"), ], CAR.ATLAS_MK1: [ - VWCarInfo("Volkswagen Atlas 2018-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), + VWCarInfo("Volkswagen Atlas 2018-23", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), VWCarInfo("Volkswagen Atlas Cross Sport 2021-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), VWCarInfo("Volkswagen Teramont 2018-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), VWCarInfo("Volkswagen Teramont Cross Sport 2021-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), @@ -275,6 +275,7 @@ FW_VERSIONS = { b'\xf1\x8703H906026AA\xf1\x899970', b'\xf1\x8703H906026AJ\xf1\x890638', b'\xf1\x8703H906026AT\xf1\x891922', + b'\xf1\x8703H906026BC\xf1\x892664', b'\xf1\x8703H906026F \xf1\x896696', b'\xf1\x8703H906026F \xf1\x899970', b'\xf1\x8703H906026J \xf1\x896026', @@ -287,12 +288,14 @@ FW_VERSIONS = { b'\xf1\x8709G927158DR\xf1\x893536', b'\xf1\x8709G927158DR\xf1\x893742', b'\xf1\x8709G927158FT\xf1\x893835', + b'\xf1\x8709G927158GL\xf1\x893939', ], (Ecu.srs, 0x715, None): [ b'\xf1\x873Q0959655BC\xf1\x890503\xf1\x82\0161914151912001103111122031200', b'\xf1\x873Q0959655BN\xf1\x890713\xf1\x82\0162214152212001105141122052900', b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\0162214152212001105141122052900', b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1114151112001105161122052J00', + b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1115151112001105171122052J00', ], (Ecu.eps, 0x712, None): [ b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\00571B60924A1', @@ -300,6 +303,7 @@ FW_VERSIONS = { b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6090105', ], (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', b'\xf1\x872Q0907572R \xf1\x890372', b'\xf1\x872Q0907572T \xf1\x890383', b'\xf1\x875Q0907572H \xf1\x890620', From 3b602e28443263c043daec4bfa2ca6bc7a13eb56 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 2 Sep 2022 13:41:58 -0700 Subject: [PATCH 015/152] GM: update minimum steer speed (#25618) * EUV is 10 kph * Update ref_commit * temp * Revert "temp" This reverts commit 90ce28b06ba623e7bd1252798af3c285b465e0ec. --- docs/CARS.md | 12 ++++++------ selfdrive/car/gm/interface.py | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 1bea3f868e..097a5c5775 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -17,10 +17,10 @@ A supported vehicle is one that just works when you install a comma three. All s |Audi|Q3 2020-21|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| |Audi|RS3 2018|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| |Audi|S3 2015-17|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Cadillac|Escalade ESV 2016[1](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| -|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| -|Chevrolet|Silverado 1500 2020-21|Safety Package II|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| -|Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| +|Cadillac|Escalade ESV 2016[1](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| +|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|Stock|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| +|Chevrolet|Silverado 1500 2020-21|Safety Package II|Stock|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| +|Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| |Chrysler|Pacifica 2017-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Chrysler|Pacifica 2019-20|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Chrysler|Pacifica 2021|All|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| @@ -31,8 +31,8 @@ A supported vehicle is one that just works when you install a comma three. All s |Genesis|G70 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| |Genesis|G80 2017-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Genesis|G90 2017-18|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| -|GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| -|GMC|Sierra 1500 2020-21|Driver Alert Package II|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| +|GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| +|GMC|Sierra 1500 2020-21|Driver Alert Package II|Stock|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| |Honda|Accord 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| |Honda|Accord Hybrid 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| |Honda|Civic 2016-18|Honda Sensing|openpilot|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 118e54aa0e..ac8bc45809 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -74,7 +74,7 @@ class CarInterface(CarInterfaceBase): ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL} # Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below. - ret.minSteerSpeed = 7 * CV.MPH_TO_MS + ret.minSteerSpeed = 10 * CV.KPH_TO_MS ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.00]] ret.lateralTuning.pid.kf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594 diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 591acc2f1b..2f93b75872 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -af74c25e869d1128c0277f789e8f88bb95c5be1b +cad0c6a23a9baea9853fe2117ff9127a83f9e884 From 593dfd0aed6f3bbb37b05ef7c331df08781327d9 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Fri, 2 Sep 2022 16:19:06 -0700 Subject: [PATCH 016/152] Faster a_ego filter (#25646) * Faster a_ego filter * :x Update ref * typo * update ref --- selfdrive/car/interfaces.py | 6 +++--- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 401b243ba9..1e14aca8cf 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -271,12 +271,12 @@ class CarStateBase(ABC): self.left_blinker_prev = False self.right_blinker_prev = False - # Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) - # R = 1e3 + # Q = np.matrix([[0.0, 0.0], [0.0, 100.0]]) + # R = 0.3 self.v_ego_kf = KF1D(x0=[[0.0], [0.0]], A=[[1.0, DT_CTRL], [0.0, 1.0]], C=[1.0, 0.0], - K=[[0.12287673], [0.29666309]]) + K=[[0.17406039], [1.65925647]]) def update_speed_kf(self, v_ego_raw): if abs(v_ego_raw - self.v_ego_kf.x[0][0]) > 2.0: # Prevent large accelerations when car starts at non zero speed diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 2f93b75872..672763461a 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -cad0c6a23a9baea9853fe2117ff9127a83f9e884 +5cb8e7ea92f333bdb49682b0593ab2ae5a5f3824 From 3183b00ff265602da9f852e23a4230c7e12a475b Mon Sep 17 00:00:00 2001 From: AlexandreSato <66435071+AlexandreSato@users.noreply.github.com> Date: Fri, 2 Sep 2022 20:34:28 -0300 Subject: [PATCH 017/152] Portuguese: add e2e long translations (#25650) * fix and improve pt-BR translation * Shorter phrase for Finish Setup * Concluir are better than Encerrar bacause means sucessfuly * improve pt-BR, DEVbrazilians use english as default * fix "atualizador" text cutoff * miss mark as finish on qt linguist * translate to pt-BR the e2e_long toggle --- selfdrive/ui/translations/main_pt-BR.ts | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index c0ef5c88fe..e4df8f36b0 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -1199,12 +1199,12 @@ trabalho definido 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + 🌮 End-to-end longitudinal (experimental) 🌮 Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Deixe o modelo de direção controlar o acelerador e o freio, o openpilot dirigirá da maneira como ele entende que um humano o faria. Super experimental. From 1d86c431ee7a63616e5f0b927280bf82f34c7969 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 2 Sep 2022 17:02:54 -0700 Subject: [PATCH 018/152] Kia: update Forte supported package (#25652) * Not standard * https://cdn.dealereprocess.org/cdn/brochures/hyundai/2020-ioniqhybrid.pdf * revert --- docs/CARS.md | 2 +- selfdrive/car/hyundai/values.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 097a5c5775..1f0e24865d 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -85,7 +85,7 @@ A supported vehicle is one that just works when you install a comma three. All s |Kia|Ceed 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Kia|EV6 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P| |Kia|Forte 2018|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| -|Kia|Forte 2019-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| +|Kia|Forte 2019-21|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| |Kia|K5 2021-22|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| |Kia|Niro Electric 2019|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Kia|Niro Electric 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index aa18235223..79e3ea4190 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -140,7 +140,7 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { # Kia CAR.KIA_FORTE: [ HyundaiCarInfo("Kia Forte 2018", harness=Harness.hyundai_b), - HyundaiCarInfo("Kia Forte 2019-21", "All", harness=Harness.hyundai_g), + HyundaiCarInfo("Kia Forte 2019-21", harness=Harness.hyundai_g), ], CAR.KIA_K5_2021: HyundaiCarInfo("Kia K5 2021-22", "Smart Cruise Control (SCC)", harness=Harness.hyundai_a), CAR.KIA_NIRO_EV: [ From 01a73b14d8b23c17bc6c7b314a266d594e88eb55 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Sun, 4 Sep 2022 12:04:28 -0700 Subject: [PATCH 019/152] Toggles must be alphabetical (#25654) toggles must be alphabetical --- selfdrive/ui/qt/offroad/settings.cc | 12 ++++++------ selfdrive/ui/translations/main_ja.ts | 8 ++++---- selfdrive/ui/translations/main_ko.ts | 8 ++++---- selfdrive/ui/translations/main_pt-BR.ts | 8 ++++---- selfdrive/ui/translations/main_zh-CHS.ts | 8 ++++---- selfdrive/ui/translations/main_zh-CHT.ts | 8 ++++---- 6 files changed, 26 insertions(+), 26 deletions(-) diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 09ff0eed94..d44f4c75f6 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -53,18 +53,18 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { tr("Upload data from the driver facing camera and help improve the driver monitoring algorithm."), "../assets/offroad/icon_monitoring.png", }, - { - "EndToEndLong", - tr("🌮 End-to-end longitudinal (extremely alpha) 🌮"), - tr("Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental."), - "../assets/offroad/icon_road.png", - }, { "DisengageOnAccelerator", tr("Disengage On Accelerator Pedal"), tr("When enabled, pressing the accelerator pedal will disengage openpilot."), "../assets/offroad/icon_disengage_on_accelerator.svg", }, + { + "EndToEndLong", + tr("🌮 End-to-end longitudinal (extremely alpha) 🌮"), + tr("Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental."), + "../assets/offroad/icon_road.png", + }, #ifdef ENABLE_MAPS { "NavSettingTime24h", diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index d56f4e8466..13697ce523 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -1193,22 +1193,22 @@ location set 車内カメラの映像をアップロードし、ドライバー監視システムのアルゴリズムの向上に役立てます。 - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal アクセル踏むと openpilot をキャンセル - + When enabled, pressing the accelerator pedal will disengage openpilot. 有効な場合は、アクセルを踏むと openpilot をキャンセルします。 diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index bb4f884aa9..918cd29e27 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -1193,22 +1193,22 @@ location set 운전자 카메라에서 데이터를 업로드하고 운전자 모니터링 알고리즘을 개선합니다. - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal 가속페달 조작시 해제 - + When enabled, pressing the accelerator pedal will disengage openpilot. 활성화된 경우 가속 페달을 누르면 openpilot이 해제됩니다. diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index e4df8f36b0..f5aa386e5d 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -1197,22 +1197,22 @@ trabalho definido Upload dados da câmera voltada para o motorista e ajude a melhorar o algoritmo de monitoramentor. - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 🌮 End-to-end longitudinal (experimental) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. Deixe o modelo de direção controlar o acelerador e o freio, o openpilot dirigirá da maneira como ele entende que um humano o faria. Super experimental. - + Disengage On Accelerator Pedal Desacionar Com Pedal Do Acelerador - + When enabled, pressing the accelerator pedal will disengage openpilot. Quando ativado, pressionar o pedal do acelerador desacionará o openpilot. diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index e8c9b8ec52..e405dc9026 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -1191,22 +1191,22 @@ location set 上传驾驶员摄像头的数据,帮助改进驾驶员监控算法。 - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal 踩油门时取消控制 - + When enabled, pressing the accelerator pedal will disengage openpilot. 启用后,踩下油门踏板将取消openpilot。 diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 9b792e6df0..71893218ff 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -1193,22 +1193,22 @@ location set 上傳駕駛監控的錄像來協助我們提升駕駛監控的準確率。 - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal 油門取消控車 - + When enabled, pressing the accelerator pedal will disengage openpilot. 啟用後,踩踏油門將會取消 openpilot 控制。 From 2eff6d0ebd20b95b10726f979b04df028f50d303 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Sun, 4 Sep 2022 13:07:51 -0700 Subject: [PATCH 020/152] Remove lane planning code (#25651) * Remove all lane planning logic * Revert "Update ref" This reverts commit 8dcb08ebccbb5641443459ac40601a95cf605682. * bump cereal * Update ref --- cereal | 2 +- release/files_common | 1 - selfdrive/controls/controlsd.py | 2 +- selfdrive/controls/lib/lane_planner.py | 97 ----------------------- selfdrive/controls/lib/lateral_planner.py | 38 +++------ selfdrive/controls/plannerd.py | 7 +- selfdrive/test/process_replay/ref_commit | 2 +- 7 files changed, 17 insertions(+), 132 deletions(-) delete mode 100644 selfdrive/controls/lib/lane_planner.py diff --git a/cereal b/cereal index d3a943ef66..6323950101 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit d3a943ef660dd29f73700806ee0baf1d5aff6834 +Subproject commit 632395010102aabdd0ed87aba50d25042cdcb70e diff --git a/release/files_common b/release/files_common index 10c66a8960..ad99af752f 100644 --- a/release/files_common +++ b/release/files_common @@ -173,7 +173,6 @@ selfdrive/controls/lib/alerts_offroad.json selfdrive/controls/lib/desire_helper.py selfdrive/controls/lib/drive_helpers.py selfdrive/controls/lib/events.py -selfdrive/controls/lib/lane_planner.py selfdrive/controls/lib/latcontrol_angle.py selfdrive/controls/lib/latcontrol_indi.py selfdrive/controls/lib/latcontrol_torque.py diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index b8b66a5677..f2b2ddc98e 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -15,7 +15,7 @@ from system.swaglog import cloudlog from system.version import get_short_branch from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.car.car_helpers import get_car, get_startup_event, get_one_can -from selfdrive.controls.lib.lane_planner import CAMERA_OFFSET +from selfdrive.controls.lib.lateral_planner import CAMERA_OFFSET from selfdrive.controls.lib.drive_helpers import V_CRUISE_INITIAL, update_v_cruise, initialize_v_cruise from selfdrive.controls.lib.drive_helpers import get_lag_adjusted_curvature from selfdrive.controls.lib.latcontrol import LatControl diff --git a/selfdrive/controls/lib/lane_planner.py b/selfdrive/controls/lib/lane_planner.py deleted file mode 100644 index 1facb66d63..0000000000 --- a/selfdrive/controls/lib/lane_planner.py +++ /dev/null @@ -1,97 +0,0 @@ -import numpy as np -from cereal import log -from common.filter_simple import FirstOrderFilter -from common.numpy_fast import interp -from common.realtime import DT_MDL -from system.swaglog import cloudlog - - -TRAJECTORY_SIZE = 33 -# camera offset is meters from center car to camera -# model path is in the frame of the camera -PATH_OFFSET = 0.00 -CAMERA_OFFSET = 0.04 - - -class LanePlanner: - def __init__(self, wide_camera=False): - self.ll_t = np.zeros((TRAJECTORY_SIZE,)) - self.ll_x = np.zeros((TRAJECTORY_SIZE,)) - self.lll_y = np.zeros((TRAJECTORY_SIZE,)) - self.rll_y = np.zeros((TRAJECTORY_SIZE,)) - self.lane_width_estimate = FirstOrderFilter(3.7, 9.95, DT_MDL) - self.lane_width_certainty = FirstOrderFilter(1.0, 0.95, DT_MDL) - self.lane_width = 3.7 - - self.lll_prob = 0. - self.rll_prob = 0. - self.d_prob = 0. - - self.lll_std = 0. - self.rll_std = 0. - - self.l_lane_change_prob = 0. - self.r_lane_change_prob = 0. - - self.camera_offset = -CAMERA_OFFSET if wide_camera else CAMERA_OFFSET - self.path_offset = -PATH_OFFSET if wide_camera else PATH_OFFSET - - def parse_model(self, md): - lane_lines = md.laneLines - if len(lane_lines) == 4 and len(lane_lines[0].t) == TRAJECTORY_SIZE: - self.ll_t = (np.array(lane_lines[1].t) + np.array(lane_lines[2].t))/2 - # left and right ll x is the same - self.ll_x = lane_lines[1].x - self.lll_y = np.array(lane_lines[1].y) + self.camera_offset - self.rll_y = np.array(lane_lines[2].y) + self.camera_offset - self.lll_prob = md.laneLineProbs[1] - self.rll_prob = md.laneLineProbs[2] - self.lll_std = md.laneLineStds[1] - self.rll_std = md.laneLineStds[2] - - desire_state = md.meta.desireState - if len(desire_state): - self.l_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeLeft] - self.r_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeRight] - - def get_d_path(self, v_ego, path_t, path_xyz): - # Reduce reliance on lanelines that are too far apart or - # will be in a few seconds - path_xyz[:, 1] += self.path_offset - l_prob, r_prob = self.lll_prob, self.rll_prob - width_pts = self.rll_y - self.lll_y - prob_mods = [] - for t_check in (0.0, 1.5, 3.0): - width_at_t = interp(t_check * (v_ego + 7), self.ll_x, width_pts) - prob_mods.append(interp(width_at_t, [4.0, 5.0], [1.0, 0.0])) - mod = min(prob_mods) - l_prob *= mod - r_prob *= mod - - # Reduce reliance on uncertain lanelines - l_std_mod = interp(self.lll_std, [.15, .3], [1.0, 0.0]) - r_std_mod = interp(self.rll_std, [.15, .3], [1.0, 0.0]) - l_prob *= l_std_mod - r_prob *= r_std_mod - - # Find current lanewidth - self.lane_width_certainty.update(l_prob * r_prob) - current_lane_width = abs(self.rll_y[0] - self.lll_y[0]) - self.lane_width_estimate.update(current_lane_width) - speed_lane_width = interp(v_ego, [0., 31.], [2.8, 3.5]) - self.lane_width = self.lane_width_certainty.x * self.lane_width_estimate.x + \ - (1 - self.lane_width_certainty.x) * speed_lane_width - - clipped_lane_width = min(4.0, self.lane_width) - path_from_left_lane = self.lll_y + clipped_lane_width / 2.0 - path_from_right_lane = self.rll_y - clipped_lane_width / 2.0 - - self.d_prob = l_prob + r_prob - l_prob * r_prob - lane_path_y = (l_prob * path_from_left_lane + r_prob * path_from_right_lane) / (l_prob + r_prob + 0.0001) - safe_idxs = np.isfinite(self.ll_t) - if safe_idxs[0]: - lane_path_y_interp = np.interp(path_t, self.ll_t[safe_idxs], lane_path_y[safe_idxs]) - path_xyz[:,1] = self.d_prob * lane_path_y_interp + (1.0 - self.d_prob) * path_xyz[:,1] - else: - cloudlog.warning("Lateral mpc - NaNs in laneline times, ignoring") - return path_xyz diff --git a/selfdrive/controls/lib/lateral_planner.py b/selfdrive/controls/lib/lateral_planner.py index 29dfc77111..3470754bc6 100644 --- a/selfdrive/controls/lib/lateral_planner.py +++ b/selfdrive/controls/lib/lateral_planner.py @@ -4,16 +4,15 @@ from common.numpy_fast import interp from system.swaglog import cloudlog from selfdrive.controls.lib.lateral_mpc_lib.lat_mpc import LateralMpc from selfdrive.controls.lib.drive_helpers import CONTROL_N, MPC_COST_LAT, LAT_MPC_N -from selfdrive.controls.lib.lane_planner import LanePlanner, TRAJECTORY_SIZE from selfdrive.controls.lib.desire_helper import DesireHelper import cereal.messaging as messaging from cereal import log +TRAJECTORY_SIZE = 33 +CAMERA_OFFSET = 0.04 class LateralPlanner: - def __init__(self, CP, use_lanelines=True, wide_camera=False): - self.use_lanelines = use_lanelines - self.LP = LanePlanner(wide_camera) + def __init__(self, CP): self.DH = DesireHelper() # Vehicle model parameters used to calculate lateral movement of car @@ -42,7 +41,6 @@ class LateralPlanner: # Parse model predictions md = sm['modelV2'] - self.LP.parse_model(md) if len(md.position.x) == TRAJECTORY_SIZE and len(md.orientation.x) == TRAJECTORY_SIZE: self.path_xyz = np.column_stack([md.position.x, md.position.y, md.position.z]) self.t_idxs = np.array(md.position.t) @@ -51,23 +49,17 @@ class LateralPlanner: self.path_xyz_stds = np.column_stack([md.position.xStd, md.position.yStd, md.position.zStd]) # Lane change logic - lane_change_prob = self.LP.l_lane_change_prob + self.LP.r_lane_change_prob + desire_state = md.meta.desireState + if len(desire_state): + self.l_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeLeft] + self.r_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeRight] + lane_change_prob = self.l_lane_change_prob + self.r_lane_change_prob self.DH.update(sm['carState'], sm['carControl'].latActive, lane_change_prob) - # Turn off lanes during lane change - if self.DH.desire == log.LateralPlan.Desire.laneChangeRight or self.DH.desire == log.LateralPlan.Desire.laneChangeLeft: - self.LP.lll_prob *= self.DH.lane_change_ll_prob - self.LP.rll_prob *= self.DH.lane_change_ll_prob - - # Calculate final driving path and set MPC costs - if self.use_lanelines: - d_path_xyz = self.LP.get_d_path(v_ego, self.t_idxs, self.path_xyz) - self.lat_mpc.set_weights(MPC_COST_LAT.PATH, MPC_COST_LAT.HEADING, MPC_COST_LAT.STEER_RATE) - else: - d_path_xyz = self.path_xyz - # Heading cost is useful at low speed, otherwise end of plan can be off-heading - heading_cost = interp(v_ego, [5.0, 10.0], [MPC_COST_LAT.HEADING, 0.15]) - self.lat_mpc.set_weights(MPC_COST_LAT.PATH, heading_cost, MPC_COST_LAT.STEER_RATE) + d_path_xyz = self.path_xyz + # Heading cost is useful at low speed, otherwise end of plan can be off-heading + heading_cost = interp(v_ego, [5.0, 10.0], [MPC_COST_LAT.HEADING, 0.15]) + self.lat_mpc.set_weights(MPC_COST_LAT.PATH, heading_cost, MPC_COST_LAT.STEER_RATE) y_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(d_path_xyz, axis=1), d_path_xyz[:, 1]) heading_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw) @@ -112,20 +104,16 @@ class LateralPlanner: lateralPlan = plan_send.lateralPlan lateralPlan.modelMonoTime = sm.logMonoTime['modelV2'] - lateralPlan.laneWidth = float(self.LP.lane_width) lateralPlan.dPathPoints = self.y_pts.tolist() lateralPlan.psis = self.lat_mpc.x_sol[0:CONTROL_N, 2].tolist() lateralPlan.curvatures = self.lat_mpc.x_sol[0:CONTROL_N, 3].tolist() lateralPlan.curvatureRates = [float(x) for x in self.lat_mpc.u_sol[0:CONTROL_N - 1]] + [0.0] - lateralPlan.lProb = float(self.LP.lll_prob) - lateralPlan.rProb = float(self.LP.rll_prob) - lateralPlan.dProb = float(self.LP.d_prob) lateralPlan.mpcSolutionValid = bool(plan_solution_valid) lateralPlan.solverExecutionTime = self.lat_mpc.solve_time lateralPlan.desire = self.DH.desire - lateralPlan.useLaneLines = self.use_lanelines + lateralPlan.useLaneLines = False lateralPlan.laneChangeState = self.DH.lane_change_state lateralPlan.laneChangeDirection = self.DH.lane_change_direction diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py index ca7523f2ee..513131a33b 100755 --- a/selfdrive/controls/plannerd.py +++ b/selfdrive/controls/plannerd.py @@ -16,13 +16,8 @@ def plannerd_thread(sm=None, pm=None): CP = car.CarParams.from_bytes(params.get("CarParams", block=True)) cloudlog.info("plannerd got CarParams: %s", CP.carName) - use_lanelines = False - wide_camera = params.get_bool('WideCameraOnly') - - cloudlog.event("e2e mode", on=use_lanelines) - longitudinal_planner = Planner(CP) - lateral_planner = LateralPlanner(CP, use_lanelines=use_lanelines, wide_camera=wide_camera) + lateral_planner = LateralPlanner(CP) if sm is None: sm = messaging.SubMaster(['carControl', 'carState', 'controlsState', 'radarState', 'modelV2'], diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 672763461a..cf3eb89f94 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -5cb8e7ea92f333bdb49682b0593ab2ae5a5f3824 +e1c189b002a179763fa34f24e5d96f2b2d0c4c49 From 4c05c88c10f24d771c76bd8b078426a06a82b4f8 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Sun, 4 Sep 2022 13:29:13 -0700 Subject: [PATCH 021/152] Radard: ignore leads without model confirmation wider than 1.0m (#25664) Dont stop for cars next to you without model confirmation --- selfdrive/controls/lib/radar_helpers.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/radar_helpers.py b/selfdrive/controls/lib/radar_helpers.py index 85699866b0..0e2b96668f 100644 --- a/selfdrive/controls/lib/radar_helpers.py +++ b/selfdrive/controls/lib/radar_helpers.py @@ -152,7 +152,7 @@ class Cluster(): def potential_low_speed_lead(self, v_ego): # stop for stuff in front of you and low speed, even without model confirmation - return abs(self.yRel) < 1.5 and (v_ego < v_ego_stationary) and self.dRel < 25 + return abs(self.yRel) < 1.0 and (v_ego < v_ego_stationary) and self.dRel < 25 def is_potential_fcw(self, model_prob): return model_prob > .9 From f44ebb9f1ed37b2c3add981bf493e4d7cc7d0ee0 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 6 Sep 2022 04:20:05 +0800 Subject: [PATCH 022/152] ui/sidebar: remove unused variable params (#25667) * remove params * update translations Co-authored-by: Adeeb Shihadeh --- selfdrive/ui/qt/sidebar.h | 2 -- selfdrive/ui/translations/main_ja.ts | 14 +++++++------- selfdrive/ui/translations/main_ko.ts | 14 +++++++------- selfdrive/ui/translations/main_pt-BR.ts | 14 +++++++------- selfdrive/ui/translations/main_zh-CHS.ts | 14 +++++++------- selfdrive/ui/translations/main_zh-CHT.ts | 14 +++++++------- 6 files changed, 35 insertions(+), 37 deletions(-) diff --git a/selfdrive/ui/qt/sidebar.h b/selfdrive/ui/qt/sidebar.h index 0140673aac..621a21444d 100644 --- a/selfdrive/ui/qt/sidebar.h +++ b/selfdrive/ui/qt/sidebar.h @@ -3,7 +3,6 @@ #include #include -#include "common/params.h" #include "selfdrive/ui/ui.h" typedef QPair, QColor> ItemStatus; @@ -49,7 +48,6 @@ protected: const QColor warning_color = QColor(218, 202, 37); const QColor danger_color = QColor(201, 34, 49); - Params params; ItemStatus connect_status, panda_status, temp_status; QString net_type; int net_strength = 0; diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 13697ce523..43327f8ef7 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -945,37 +945,37 @@ location set 検索 - + -- -- - + Wi-Fi Wi-Fi - + ETH ETH - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 918cd29e27..1d7ddbe6e8 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -945,37 +945,37 @@ location set 검색중 - + -- -- - + Wi-Fi Wi-Fi - + ETH 이더넷 - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index f5aa386e5d..f50cf65e15 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -949,37 +949,37 @@ trabalho definido PROCURA - + -- -- - + Wi-Fi Wi-Fi - + ETH ETH - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index e405dc9026..1a384482da 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -943,37 +943,37 @@ location set 搜索中 - + -- -- - + Wi-Fi Wi-Fi - + ETH 以太网 - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 71893218ff..d7dd5cb563 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -945,37 +945,37 @@ location set 車輛通訊 - + -- -- - + Wi-Fi - + ETH - + 2G - + 3G - + LTE - + 5G From 23254b454e927a5813f8beb00a4579150a5a7fab Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Mon, 5 Sep 2022 15:20:56 -0500 Subject: [PATCH 023/152] Add missing HIGHLANDER_TSS2 engine f/w (#25657) --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 42a67ec969..9635fe2e73 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -948,6 +948,7 @@ FW_VERSIONS = { b'\x01896630EC4000\x00\x00\x00\x00', b'\x01896630ED9000\x00\x00\x00\x00', b'\x01896630EE1000\x00\x00\x00\x00', + b'\x01896630EE1100\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301400\x00\x00\x00\x00', From 98484697cb66aa7863f509ef36bef0e51dd96b32 Mon Sep 17 00:00:00 2001 From: Justin Newberry Date: Mon, 5 Sep 2022 16:24:17 -0400 Subject: [PATCH 024/152] Subaru Legacy 22 fingerprint (#25665) --- selfdrive/car/subaru/values.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 7d8365a11f..d04e5f2cc6 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -106,18 +106,23 @@ FW_VERSIONS = { CAR.LEGACY: { (Ecu.esp, 0x7b0, None): [ b'\xa1\\ x04\x01', + b'\xa1 \x03\x03' ], (Ecu.eps, 0x746, None): [ b'\x9b\xc0\x11\x00', + b'\x9b\xc0\x11\x02' ], (Ecu.fwdCamera, 0x787, None): [ b'\x00\x00e\x80\x00\x1f@ \x19\x00', + b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00' ], (Ecu.engine, 0x7e0, None): [ b'\xde\"a0\x07', + b'\xe2"aq\x07' ], (Ecu.transmission, 0x7e1, None): [ b'\xa5\xf6\x05@\x00', + b'\xa7\xf6\x04@\x00' ], }, CAR.IMPREZA: { From d804b945e2a161a2a53923d70c2ee45c0a3493ce Mon Sep 17 00:00:00 2001 From: vanillagorillaa <31773928+vanillagorillaa@users.noreply.github.com> Date: Mon, 5 Sep 2022 13:25:24 -0700 Subject: [PATCH 025/152] small nissan cleanup (#25663) --- selfdrive/car/nissan/interface.py | 4 +--- selfdrive/car/nissan/nissancan.py | 5 +---- 2 files changed, 2 insertions(+), 7 deletions(-) diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index fe567468bb..494573f498 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -18,24 +18,22 @@ class CarInterface(CarInterfaceBase): ret.steerLimitTimer = 1.0 ret.steerActuatorDelay = 0.1 + ret.steerRatio = 17 if candidate in (CAR.ROGUE, CAR.XTRAIL): ret.mass = 1610 + STD_CARGO_KG ret.wheelbase = 2.705 ret.centerToFront = ret.wheelbase * 0.44 - ret.steerRatio = 17 elif candidate in (CAR.LEAF, CAR.LEAF_IC): ret.mass = 1610 + STD_CARGO_KG ret.wheelbase = 2.705 ret.centerToFront = ret.wheelbase * 0.44 - ret.steerRatio = 17 elif candidate == CAR.ALTIMA: # Altima has EPS on C-CAN unlike the others that have it on V-CAN ret.safetyConfigs[0].safetyParam = 1 # EPS is on alternate bus ret.mass = 1492 + STD_CARGO_KG ret.wheelbase = 2.824 ret.centerToFront = ret.wheelbase * 0.44 - ret.steerRatio = 17 ret.steerControlType = car.CarParams.SteerControlType.angle ret.radarOffCan = True diff --git a/selfdrive/car/nissan/nissancan.py b/selfdrive/car/nissan/nissancan.py index f59714b8d4..01fb3463a9 100644 --- a/selfdrive/car/nissan/nissancan.py +++ b/selfdrive/car/nissan/nissancan.py @@ -24,10 +24,7 @@ def create_steering_control(packer, apply_steer, frame, steer_on, lkas_max_torqu def create_acc_cancel_cmd(packer, car_fingerprint, cruise_throttle_msg): values = copy.copy(cruise_throttle_msg) - can_bus = 2 - - if car_fingerprint == CAR.ALTIMA: - can_bus = 1 + can_bus = 1 if car_fingerprint == CAR.ALTIMA else 2 values["CANCEL_BUTTON"] = 1 values["NO_BUTTON_PRESSED"] = 0 From 71d152bf518f4e2866d6f2cd8c84e1916310d6f2 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 6 Sep 2022 04:25:46 +0800 Subject: [PATCH 026/152] manager.py: set default lang to main_en (#25666) * default main_en * update transaltions * set default language in manager.py * after h --- selfdrive/manager/manager.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index a065242bbf..772dd9488f 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -40,6 +40,7 @@ def manager_init() -> None: ("CompletedTrainingVersion", "0"), ("DisengageOnAccelerator", "1"), ("HasAcceptedTerms", "0"), + ("LanguageSetting", "main_en"), ("OpenpilotEnabledToggle", "1"), ] if not PC: From 80533d6c0368b6b2fd797ec0388ed75d74dee80f Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 5 Sep 2022 13:57:07 -0700 Subject: [PATCH 027/152] Toyota: match dash set speed (#25649) * toyota: match set speed from dash * Use unit bit * Use RSA2 * flip this * Universal unit signal, set vEgoCluster * remove this and bump opendbc * detect if car interface sets cluster fields * revert * needs to be cp * UI_SPEED is actually always in kph? * forgot to actually convert it * same in onroad * try conv factor only for imperial * Seems like UI_SPEED is not the UI speed at all * the dash might floor it * same openpilot behavior * bump * ego speed factor is dynamic across speeds, handle Lexus exceptions with diff msg * remove test, bump opendbc * secret formula * secret formula v2 * 1.03 is sufficient * try short press * bump opendbc * surely this can be cleaned up surely this can be cleaned up * use filter * redo factors * try UI_SPEED again with a factor try UI_SPEED again with a factor * dash applies hysteresis to speed. this matches pretty well, but not exactly * match only set speed * clean up * clean up clean up * Update ref_commit * update refs Co-authored-by: Willem Melching Co-authored-by: Adeeb Shihadeh --- opendbc | 2 +- selfdrive/car/toyota/carstate.py | 14 ++++++++++++++ selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 16 insertions(+), 2 deletions(-) diff --git a/opendbc b/opendbc index 8c634615c5..83d4cb9fd8 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 8c634615c5b6eb05ebdecc097bdc72f5403a3afa +Subproject commit 83d4cb9fd871a563f4a0af0102992c0b52c94310 diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index 70ba690aa1..0cfba2b09f 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -90,9 +90,17 @@ class CarState(CarStateBase): if self.CP.carFingerprint in (CAR.LEXUS_IS, CAR.LEXUS_RC): ret.cruiseState.available = cp.vl["DSU_CRUISE"]["MAIN_ON"] != 0 ret.cruiseState.speed = cp.vl["DSU_CRUISE"]["SET_SPEED"] * CV.KPH_TO_MS + cluster_set_speed = cp.vl["PCM_CRUISE_ALT"]["UI_SET_SPEED"] else: ret.cruiseState.available = cp.vl["PCM_CRUISE_2"]["MAIN_ON"] != 0 ret.cruiseState.speed = cp.vl["PCM_CRUISE_2"]["SET_SPEED"] * CV.KPH_TO_MS + cluster_set_speed = cp.vl["PCM_CRUISE_SM"]["UI_SET_SPEED"] + + # UI_SET_SPEED is always non-zero when main is on, hide until first enable + if ret.cruiseState.speed != 0: + is_metric = cp.vl["BODY_CONTROL_STATE_2"]["UNITS"] in (1, 2) + conversion_factor = CV.KPH_TO_MS if is_metric else CV.MPH_TO_MS + ret.cruiseState.speedCluster = cluster_set_speed * conversion_factor cp_acc = cp_cam if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) else cp @@ -147,6 +155,7 @@ class CarState(CarStateBase): ("DOOR_OPEN_RR", "BODY_CONTROL_STATE"), ("SEATBELT_DRIVER_UNLATCHED", "BODY_CONTROL_STATE"), ("PARKING_BRAKE", "BODY_CONTROL_STATE"), + ("UNITS", "BODY_CONTROL_STATE_2"), ("TC_DISABLED", "ESP_CONTROL"), ("BRAKE_HOLD_ACTIVE", "ESP_CONTROL"), ("STEER_FRACTION", "STEER_ANGLE_SENSOR"), @@ -154,6 +163,7 @@ class CarState(CarStateBase): ("CRUISE_ACTIVE", "PCM_CRUISE"), ("CRUISE_STATE", "PCM_CRUISE"), ("GAS_RELEASED", "PCM_CRUISE"), + ("UI_SET_SPEED", "PCM_CRUISE_SM"), ("STEER_TORQUE_DRIVER", "STEER_TORQUE_SENSOR"), ("STEER_TORQUE_EPS", "STEER_TORQUE_SENSOR"), ("STEER_ANGLE", "STEER_TORQUE_SENSOR"), @@ -168,12 +178,14 @@ class CarState(CarStateBase): ("LIGHT_STALK", 1), ("BLINKERS_STATE", 0.15), ("BODY_CONTROL_STATE", 3), + ("BODY_CONTROL_STATE_2", 2), ("ESP_CONTROL", 3), ("EPS_STATUS", 25), ("BRAKE_MODULE", 40), ("WHEEL_SPEEDS", 80), ("STEER_ANGLE_SENSOR", 80), ("PCM_CRUISE", 33), + ("PCM_CRUISE_SM", 1), ("STEER_TORQUE_SENSOR", 50), ] @@ -187,7 +199,9 @@ class CarState(CarStateBase): if CP.carFingerprint in (CAR.LEXUS_IS, CAR.LEXUS_RC): signals.append(("MAIN_ON", "DSU_CRUISE")) signals.append(("SET_SPEED", "DSU_CRUISE")) + signals.append(("UI_SET_SPEED", "PCM_CRUISE_ALT")) checks.append(("DSU_CRUISE", 5)) + checks.append(("PCM_CRUISE_ALT", 1)) else: signals.append(("MAIN_ON", "PCM_CRUISE_2")) signals.append(("SET_SPEED", "PCM_CRUISE_2")) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index cf3eb89f94..20bb4c82f3 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -e1c189b002a179763fa34f24e5d96f2b2d0c4c49 +915309019fef256512ee30cf92cfae2e479dd04e \ No newline at end of file From a3bc906b113bbe6a5726c2fef4f64f3304cdaf1a Mon Sep 17 00:00:00 2001 From: cydia2020 <12470297+cydia2020@users.noreply.github.com> Date: Tue, 6 Sep 2022 07:07:47 +1000 Subject: [PATCH 028/152] Toyota: add missing HIGHLANDER_TSS2 engine f/w (#25659) --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 9635fe2e73..18b6db0db7 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -947,6 +947,7 @@ FW_VERSIONS = { b'\x01896630EB2200\x00\x00\x00\x00', b'\x01896630EC4000\x00\x00\x00\x00', b'\x01896630ED9000\x00\x00\x00\x00', + b'\x01896630ED9100\x00\x00\x00\x00', b'\x01896630EE1000\x00\x00\x00\x00', b'\x01896630EE1100\x00\x00\x00\x00', ], From 75c434bde708b15f392cea68f897a1450d4d8b78 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 6 Sep 2022 05:11:32 +0800 Subject: [PATCH 029/152] replay: add shortcuts for seeking to the next info, warning, and critical alerts (#25576) --- tools/replay/consoleui.cc | 11 ++++++++++- tools/replay/replay.cc | 7 +++++-- tools/replay/replay.h | 3 +++ 3 files changed, 18 insertions(+), 3 deletions(-) diff --git a/tools/replay/consoleui.cc b/tools/replay/consoleui.cc index 6b419ca9d8..5f165ac312 100644 --- a/tools/replay/consoleui.cc +++ b/tools/replay/consoleui.cc @@ -18,7 +18,10 @@ const std::initializer_list> keyboard_shortc {"space", "Pause/Resume"}, {"e", "Next Engagement"}, {"d", "Next Disengagement"}, - {"t", "Next User Tag"} + {"t", "Next User Tag"}, + {"i", "Next Info"}, + {"w", "Next Warning"}, + {"c", "Next Critical"}, }, { {"enter", "Enter seek request"}, @@ -344,6 +347,12 @@ void ConsoleUI::handleKey(char c) { replay->seekToFlag(FindFlag::nextDisEngagement); } else if (c == 't') { replay->seekToFlag(FindFlag::nextUserFlag); + } else if (c == 'i') { + replay->seekToFlag(FindFlag::nextInfo); + } else if (c == 'w') { + replay->seekToFlag(FindFlag::nextWarning); + } else if (c == 'c') { + replay->seekToFlag(FindFlag::nextCritical); } else if (c == 'm') { replay->seekTo(+60, true); } else if (c == 'M') { diff --git a/tools/replay/replay.cc b/tools/replay/replay.cc index ed8dea6121..3e482b5474 100644 --- a/tools/replay/replay.cc +++ b/tools/replay/replay.cc @@ -166,8 +166,11 @@ std::optional Replay::find(FindFlag flag) { } else if (flag == FindFlag::nextDisEngagement && end_ts > cur_ts) { return end_ts; } - } else if (type == TimelineType::UserFlag) { - if (flag == FindFlag::nextUserFlag && start_ts > cur_ts) { + } else if (start_ts > cur_ts) { + if ((flag == FindFlag::nextUserFlag && type == TimelineType::UserFlag) || + (flag == FindFlag::nextInfo && type == TimelineType::AlertInfo) || + (flag == FindFlag::nextWarning && type == TimelineType::AlertWarning) || + (flag == FindFlag::nextCritical && type == TimelineType::AlertCritical)) { return start_ts; } } diff --git a/tools/replay/replay.h b/tools/replay/replay.h index e4217736d5..e86c453f7e 100644 --- a/tools/replay/replay.h +++ b/tools/replay/replay.h @@ -26,6 +26,9 @@ enum class FindFlag { nextEngagement, nextDisEngagement, nextUserFlag, + nextInfo, + nextWarning, + nextCritical }; enum class TimelineType { None, Engaged, AlertInfo, AlertWarning, AlertCritical, UserFlag }; From 19a33a4845da5c99c8ccd9b5f860f7eaf98d611c Mon Sep 17 00:00:00 2001 From: ogiechogie <48487836+ogiechogie@users.noreply.github.com> Date: Mon, 5 Sep 2022 14:33:43 -0700 Subject: [PATCH 030/152] VW: Add fingerprint for 2015 Audi A3 MK3 (US) (#25639) --- selfdrive/car/volkswagen/values.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 278f4bc665..62d6dcddaf 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -744,6 +744,7 @@ FW_VERSIONS = { b'\xf1\x8704E906023BL\xf1\x895190', b'\xf1\x8704E906027CJ\xf1\x897798', b'\xf1\x8704L997022N \xf1\x899459', + b'\xf1\x875G0906259A \xf1\x890004', b'\xf1\x875G0906259L \xf1\x890002', b'\xf1\x875G0906259Q \xf1\x890002', b'\xf1\x878V0906259F \xf1\x890002', @@ -756,6 +757,7 @@ FW_VERSIONS = { b'\xf1\x870CW300044T \xf1\x895245', b'\xf1\x870CW300048 \xf1\x895201', b'\xf1\x870D9300012 \xf1\x894912', + b'\xf1\x870D9300012K \xf1\x894513', b'\xf1\x870D9300013B \xf1\x894931', b'\xf1\x870D9300041N \xf1\x894512', b'\xf1\x870D9300043T \xf1\x899699', @@ -772,6 +774,7 @@ FW_VERSIONS = { b'\xf1\x875Q0959655AM\xf1\x890315\xf1\x82\x1311111111111111311411011231129321212100', b'\xf1\x875Q0959655AM\xf1\x890318\xf1\x82\x1311111111111112311411011531159321212100', b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1311110011131100311111011731179321342100', + b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--241115141112221291163221', 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\x13121111111111--341117141212231291163221', @@ -785,6 +788,7 @@ FW_VERSIONS = { b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521G0G809A1', b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\00503G00303A0', b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\00503G00803A0', + b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G0G803A0', b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\00516G00804A1', b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\00521G00807A1', ], From 1632c2aa62a2501783b7c4b3aa5b0b7dae7d00f3 Mon Sep 17 00:00:00 2001 From: Lee Jong Mun <43285072+crwusiz@users.noreply.github.com> Date: Tue, 6 Sep 2022 08:11:22 +0900 Subject: [PATCH 031/152] Korean: add missing translations (#25647) * kor translate update * more translation fix * better * this pr e2e long only Co-authored-by: sshane --- selfdrive/ui/translations/main_ko.ts | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 1d7ddbe6e8..73a5da5ad7 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -1195,12 +1195,12 @@ location set 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + 🌮 e2e long 사용 (매우 실험적) 🌮 Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + 주행모델이 가속과 감속을 제어하도록 하면 openpilot은 운전자가 생각하는것처럼 운전합니다. (매우 실험적) From 7cdb538043c40f4c30c83863fa52a1fba8c6f621 Mon Sep 17 00:00:00 2001 From: Inoichan <37664066+Ino-Ichan@users.noreply.github.com> Date: Tue, 6 Sep 2022 09:52:12 +0900 Subject: [PATCH 032/152] modeld: bug fix in single camera mode of modeld (#25658) --- selfdrive/modeld/modeld.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 653661a3a8..d08075ff25 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -109,7 +109,7 @@ void run_model(ModelState &model, VisionIpcClient &vipc_client_main, VisionIpcCl } } else { // Use single camera - buf_extra = buf_main; + buf_extra = nullptr; meta_extra = meta_main; } From 2e013c9d46119412571b8fa5f2d255663b4b22be Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 5 Sep 2022 18:07:45 -0700 Subject: [PATCH 033/152] fix intel mac build, from #25500 --- SConstruct | 11 +++++++++-- third_party/acados/build.sh | 9 +++++++-- 2 files changed, 16 insertions(+), 4 deletions(-) diff --git a/SConstruct b/SConstruct index 66a94f9b1b..8b32eba4ae 100644 --- a/SConstruct +++ b/SConstruct @@ -75,7 +75,7 @@ lenv = { "ACADOS_SOURCE_DIR": Dir("#third_party/acados/include/acados").abspath, "ACADOS_PYTHON_INTERFACE_PATH": Dir("#pyextra/acados_template").abspath, - "TERA_PATH": Dir("#").abspath + f"/third_party/acados/{arch}/t_renderer", + "TERA_PATH": Dir("#").abspath + f"/third_party/acados/{arch}/t_renderer" } rpath = lenv["LD_LIBRARY_PATH"].copy() @@ -112,6 +112,9 @@ else: # MacOS if arch == "Darwin": + if real_arch == "x86_64": + lenv["TERA_PATH"] = Dir("#").abspath + f"/third_party/acados/Darwin_x86_64/t_renderer" + brew_prefix = subprocess.check_output(['brew', '--prefix'], encoding='utf8').strip() yuv_dir = "mac" if real_arch != "arm64" else "mac_arm64" libpath = [ @@ -120,9 +123,13 @@ else: f"{brew_prefix}/Library", f"{brew_prefix}/opt/openssl/lib", f"{brew_prefix}/Cellar", - f"#third_party/acados/{arch}/lib", "/System/Library/Frameworks/OpenGL.framework/Libraries", ] + if real_arch == "x86_64": + libpath.append(f"#third_party/acados/Darwin_x86_64/lib") + else: + libpath.append(f"#third_party/acados/{arch}/lib") + cflags += ["-DGL_SILENCE_DEPRECATION"] cxxflags += ["-DGL_SILENCE_DEPRECATION"] cpppath += [ diff --git a/third_party/acados/build.sh b/third_party/acados/build.sh index a4246fbda6..0481e8159b 100755 --- a/third_party/acados/build.sh +++ b/third_party/acados/build.sh @@ -13,8 +13,13 @@ fi ACADOS_FLAGS="-DACADOS_WITH_QPOASES=ON -UBLASFEO_TARGET -DBLASFEO_TARGET=$BLAS_TARGET" if [[ "$OSTYPE" == "darwin"* ]]; then - ACADOS_FLAGS="$ACADOS_FLAGS -DCMAKE_OSX_ARCHITECTURES=arm64;x86_64" - ARCHNAME="Darwin" + if [[ $(uname -m) == "x86_64" ]]; then + ACADOS_FLAGS="$ACADOS_FLAGS -DCMAKE_OSX_ARCHITECTURES=x86_64" + ARCHNAME="Darwin_x86_64" + else + ACADOS_FLAGS="$ACADOS_FLAGS -DCMAKE_OSX_ARCHITECTURES=arm64;x86_64" + ARCHNAME="Darwin" + fi fi if [ ! -d acados_repo/ ]; then From bc9b862d271e20540cb996c7ad3bbfded37508fc Mon Sep 17 00:00:00 2001 From: Rewat S <76684800+taperec@users.noreply.github.com> Date: Wed, 7 Sep 2022 01:47:11 +0700 Subject: [PATCH 034/152] Thai: update translations (#25682) * Add Thai translations * update to add plurals remove * Update translations * Update Thai translation to match English source. * Add to badges * use shorter km/h * Add test for correct format specifier for plural translations * pass new test * Update some sentences to make it clear. Change short form of some words. * Hide from the UI * Thai: Update translations Update Low voltage alert for better understanding. Co-authored-by: Shane Smiskol --- selfdrive/ui/translations/main_th.ts | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts index 3277f53740..7e7fcf2788 100644 --- a/selfdrive/ui/translations/main_th.ts +++ b/selfdrive/ui/translations/main_th.ts @@ -754,7 +754,7 @@ location set WARNING: Low Voltage - คำเตือน: แรงดันไฟฟ้าต่ำ + คำเตือน: แรงดันแบตเตอรี่ต่ำ From 48efd8374bf7e484ab0580f344407ab57dcff6c8 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 6 Sep 2022 13:00:49 -0700 Subject: [PATCH 035/152] Revert "modeld: bug fix in single camera mode of modeld (#25658)" This reverts commit 7cdb538043c40f4c30c83863fa52a1fba8c6f621. --- selfdrive/modeld/modeld.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index d08075ff25..653661a3a8 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -109,7 +109,7 @@ void run_model(ModelState &model, VisionIpcClient &vipc_client_main, VisionIpcCl } } else { // Use single camera - buf_extra = nullptr; + buf_extra = buf_main; meta_extra = meta_main; } From d222461a3e630690d05fbd07ed0d80feadfae944 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 6 Sep 2022 13:05:47 -0700 Subject: [PATCH 036/152] LDW: fix deprecated ll prob reference (#25681) * fix crash when ldw is turned on * in lane change * Revert "in lane change" This reverts commit 98e7224f81d2036689339779e582e2085c9c4d3e. --- selfdrive/controls/controlsd.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index f2b2ddc98e..3704389304 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -709,8 +709,8 @@ class Controls: model_v2 = self.sm['modelV2'] desire_prediction = model_v2.meta.desirePrediction if len(desire_prediction) and ldw_allowed: - right_lane_visible = self.sm['lateralPlan'].rProb > 0.5 - left_lane_visible = self.sm['lateralPlan'].lProb > 0.5 + right_lane_visible = model_v2.laneLineProbs[2] > 0.5 + left_lane_visible = model_v2.laneLineProbs[1] > 0.5 l_lane_change_prob = desire_prediction[Desire.laneChangeLeft - 1] r_lane_change_prob = desire_prediction[Desire.laneChangeRight - 1] From 719d5f78560c393732df240f1b6e053113aef2f8 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 6 Sep 2022 13:23:41 -0700 Subject: [PATCH 037/152] translations tests: ignore line numbers (#25675) * no line numbers * remove locations * test * ignore line numbers * revert revert * fix that * use relative * non bytes, global * clean up --- selfdrive/ui/tests/test_translations.py | 13 +- selfdrive/ui/translations/main_en.ts | 4 + selfdrive/ui/translations/main_ja.ts | 506 +++++++++++------------ selfdrive/ui/translations/main_ko.ts | 506 +++++++++++------------ selfdrive/ui/translations/main_pt-BR.ts | 506 +++++++++++------------ selfdrive/ui/translations/main_zh-CHS.ts | 506 +++++++++++------------ selfdrive/ui/translations/main_zh-CHT.ts | 506 +++++++++++------------ selfdrive/ui/update_translations.py | 2 +- 8 files changed, 1278 insertions(+), 1271 deletions(-) diff --git a/selfdrive/ui/tests/test_translations.py b/selfdrive/ui/tests/test_translations.py index fead288dfc..d8609f110b 100755 --- a/selfdrive/ui/tests/test_translations.py +++ b/selfdrive/ui/tests/test_translations.py @@ -9,6 +9,7 @@ import xml.etree.ElementTree as ET from selfdrive.ui.update_translations import TRANSLATIONS_DIR, LANGUAGES_FILE, update_translations TMP_TRANSLATIONS_DIR = os.path.join(TRANSLATIONS_DIR, "tmp") +LOCATION_TAG = "" not in cur_translations, + self.assertTrue("" not in cur_translations, f"{file} ({name}) translation file has unfinished translations. Finish translations or mark them as completed in Qt Linguist") def test_vanished_translations(self): for name, file in self.translation_files.items(): with self.subTest(name=name, file=file): cur_translations = self._read_translation_file(TRANSLATIONS_DIR, file) - self.assertTrue(b"" not in cur_translations, + self.assertTrue("" not in cur_translations, f"{file} ({name}) translation file has obsolete translations. Run selfdrive/ui/update_translations.py --vanish to remove them") def test_plural_translations(self): diff --git a/selfdrive/ui/translations/main_en.ts b/selfdrive/ui/translations/main_en.ts index 3f9692e5fa..42e30a59af 100644 --- a/selfdrive/ui/translations/main_en.ts +++ b/selfdrive/ui/translations/main_en.ts @@ -4,6 +4,7 @@ InputDialog + Need at least %n character(s)! Need at least %n character! @@ -14,6 +15,7 @@ QObject + %n minute(s) ago %n minute ago @@ -21,6 +23,7 @@ + %n hour(s) ago %n hour ago @@ -28,6 +31,7 @@ + %n day(s) ago %n day ago diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 43327f8ef7..7d0203daed 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -4,17 +4,17 @@ AbstractAlert - + Close 閉じる - + Snooze Update 更新の一時停止 - + Reboot and Update 再起動してアップデート @@ -22,53 +22,53 @@ AdvancedNetworking - + Back 戻る - + Enable Tethering テザリングを有効化 - + Tethering Password テザリングパスワード - - + + EDIT 編集 - + Enter new tethering password 新しいテザリングパスワードを入力 - + IP Address IP アドレス - + Enable Roaming ローミングを有効化 - + APN Setting APN 設定 - + Enter APN APN を入力 - + leave blank for automatic configuration 空白のままにして、自動設定にします @@ -76,13 +76,13 @@ ConfirmationDialog - - + + Ok OK - + Cancel キャンセル @@ -90,17 +90,17 @@ DeclinePage - + You must accept the Terms and Conditions in order to use openpilot. openpilot をご利用される前に、利用規約に同意する必要があります。 - + Back 戻る - + Decline, uninstall %1 拒否して %1 をアンインストール @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID ドングル番号 (Dongle ID) - + N/A N/A - + Serial シリアル番号 - + Driver Camera 車内カメラ - + PREVIEW 見る - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 車内カメラをプレビューして、ドライバー監視システムの視界を確認ができます。(車両の電源を切る必要があります) - + Reset Calibration キャリブレーションをリセット - + RESET リセット - + Are you sure you want to reset calibration? キャリブレーションをリセットしてもよろしいですか? - + Review Training Guide 入門書を見る - + REVIEW 見る - + Review the rules, features, and limitations of openpilot openpilot の特徴を見る - + Are you sure you want to review the training guide? 入門書を見てもよろしいですか? - + Regulatory 認証情報 - + VIEW 見る - + Change Language 言語を変更 - + CHANGE 変更 - + Select a language 言語を選択 - + Reboot 再起動 - + Power Off 電源を切る - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot は、左または右の4°以内、上の5°または下の8°以内にデバイスを取付ける必要があります。キャリブレーションを引き続きます、リセットはほとんど必要ありません。 - + Your device is pointed %1° %2 and %3° %4. このデバイスは%2の%1°、%4の%3°に向けます。 - + down - + up - + left - + right - + Are you sure you want to reboot? 再起動してもよろしいですか? - + Disengage to Reboot openpilot をキャンセルして再起動ができます - + Are you sure you want to power off? シャットダウンしてもよろしいですか? - + Disengage to Power Off openpilot をキャンセルしてシャットダウンができます @@ -261,32 +261,32 @@ DriveStats - + Drives 運転履歴 - + Hours 時間 - + ALL TIME 累計 - + PAST WEEK 先週 - + KM km - + Miles マイル @@ -294,7 +294,7 @@ DriverViewScene - + camera starting カメラを起動しています @@ -302,12 +302,12 @@ InputDialog - + Cancel キャンセル - + Need at least %n character(s)! %n文字以上でお願いします! @@ -317,22 +317,22 @@ Installer - + Installing... インストールしています... - + Receiving objects: オブジェクトをダウンロードしています: - + Resolving deltas: デルタを解決しています: - + Updating files: ファイルを更新しています: @@ -340,27 +340,27 @@ MapETA - + eta 予定到着時間 - + min - + hr 時間 - + km キロメートル - + mi マイル @@ -368,22 +368,22 @@ MapInstructions - + km キロメートル - + m メートル - + mi マイル - + ft フィート @@ -391,48 +391,48 @@ MapPanel - + Current Destination 現在の目的地 - + CLEAR 削除 - + Recent Destinations 最近の目的地 - + Try the Navigation Beta β版ナビゲーションを試す - + Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai より詳細な案内情報を得ることができます。 詳しくはこちら:https://connect.comma.ai - + No home location set 自宅の住所はまだ 設定されていません - + No work location set 職場の住所はまだ 設定されていません - + no recent destinations 最近の目的地履歴がありません @@ -440,12 +440,12 @@ location set MapWindow - + Map Loading マップを読み込んでいます - + Waiting for GPS GPS信号を探しています @@ -453,12 +453,12 @@ location set MultiOptionDialog - + Select 選択 - + Cancel キャンセル @@ -466,23 +466,23 @@ location set Networking - + Advanced 詳細 - + Enter password パスワードを入力 - - + + for "%1" ネットワーク名:%1 - + Wrong password パスワードが間違っています @@ -490,30 +490,30 @@ location set NvgWindow - + km/h km/h - + mph mph - - + + MAX 最高速度 - - + + SPEED 速度 - - + + LIMIT 制限速度 @@ -521,17 +521,17 @@ location set OffroadHome - + UPDATE 更新 - + ALERTS 警告 - + ALERT 警告 @@ -539,22 +539,22 @@ location set PairingPopup - + Pair your device to your comma account デバイスと comma アカウントを連携する - + Go to https://connect.comma.ai on your phone モバイルデバイスで「connect.comma.ai」にアクセスして - + Click "add new device" and scan the QR code on the right 「新しいデバイスを追加」を押すと、右側のQRコードをスキャンしてください - + Bookmark connect.comma.ai to your home screen to use it like an app 「connect.comma.ai」をホーム画面に追加して、アプリのように使うことができます @@ -562,32 +562,32 @@ location set PrimeAdWidget - + Upgrade Now 今すぐアップグレート - + Become a comma prime member at connect.comma.ai connect.comma.ai でプライム会員に登録できます - + PRIME FEATURES: 特典: - + Remote access リモートアクセス - + 1 year of storage 一年間の保存期間 - + Developer perks 開発者向け特典 @@ -595,22 +595,22 @@ location set PrimeUserWidget - + ✓ SUBSCRIBED ✓ 入会しました - + comma prime comma prime - + CONNECT.COMMA.AI CONNECT.COMMA.AI - + COMMA POINTS COMMA POINTS @@ -618,41 +618,41 @@ location set QObject - + Reboot 再起動 - + Exit 閉じる - + dashcam ドライブレコーダー - + openpilot openpilot - + %n minute(s) ago %n 分前 - + %n hour(s) ago %n 時間前 - + %n day(s) ago %n 日前 @@ -662,47 +662,47 @@ location set Reset - + Reset failed. Reboot to try again. 初期化に失敗しました。再起動後に再試行してください。 - + Are you sure you want to reset your device? 初期化してもよろしいですか? - + Resetting device... デバイスが初期化されます... - + System Reset システムを初期化 - + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. システムの初期化をリクエストしました。「確認」ボタンを押すとデバイスが初期化されます。「キャンセル」ボタンを押すと起動を続行します。 - + Cancel キャンセル - + Reboot 再起動 - + Confirm 確認 - + Unable to mount data partition. Press confirm to reset your device. 「data」パーティションをマウントできません。「確認」ボタンを押すとデバイスが初期化されます。 @@ -710,7 +710,7 @@ location set RichTextDialog - + Ok OK @@ -718,33 +718,33 @@ location set SettingsWindow - + × × - + Device デバイス - - + + Network ネットワーク - + Toggles 切り替え - + Software ソフトウェア - + Navigation ナビゲーション @@ -752,105 +752,105 @@ location set Setup - + WARNING: Low Voltage 警告:低電圧 - + Power your device in a car with a harness or proceed at your own risk. 自己責任でハーネスから電源を供給してください。 - + Power off 電源を切る - - - + + + Continue 続ける - + Getting Started はじめに - + Before we get on the road, let’s finish installation and cover some details. その前に、インストールを完了し、いくつかの詳細を説明します。 - + Connect to Wi-Fi Wi-Fi に接続 - - + + Back 戻る - + Continue without Wi-Fi Wi-Fi に未接続で続行 - + Waiting for internet インターネット接続を待機中 - + Choose Software to Install インストールするソフトウェアを選びます - + Dashcam ドライブレコーダー - + Custom Software カスタムソフトウェア - + Enter URL URL を入力 - + for Custom Software カスタムソフトウェア - + Downloading... ダウンロード中... - + Download Failed ダウンロード失敗 - + Ensure the entered URL is valid, and the device’s internet connection is good. 入力された URL を確認し、デバイスがインターネットに接続されていることを確認してください。 - + Reboot device デバイスを再起動 - + Start over 最初からやり直す @@ -858,17 +858,17 @@ location set SetupWidget - + Finish Setup セットアップ完了 - + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. デバイスを comma connect (connect.comma.ai)でペアリングし comma prime 特典を申請してください。 - + Pair device デバイスをペアリング @@ -876,106 +876,106 @@ location set Sidebar - - + + CONNECT 接続 - + OFFLINE オフライン - - + + ONLINE オンライン - + ERROR エラー - - - + + + TEMP 温度 - + HIGH 高温 - + GOOD 最適 - + OK OK - + VEHICLE 車両 - + NO NO - + PANDA PANDA - + GPS GPS - + SEARCH 検索 - + -- -- - + Wi-Fi Wi-Fi - + ETH ETH - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G @@ -983,89 +983,89 @@ location set SoftwarePanel - + Git Branch Git ブランチ - + Git Commit Git コミット - + OS Version OS バージョン - + Version バージョン - + Last Update Check 最終更新確認 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. openpilotが最後にアップデートの確認に成功してからの時間です。アップデート処理は、車の電源が切れているときのみ実行されます。 - + Check for Update 更新プログラムをチェック - + CHECKING 確認中 - + Switch Branch ブランチの切り替え - + ENTER 切替 - - + + The new branch will be pulled the next time the updater runs. updater を実行する時にブランチを切り替えます。 - + Enter branch name ブランチ名を入力 - + UNINSTALL アンインストール - + Uninstall %1 %1をアンインストール - + Are you sure you want to uninstall? アンインストールしてもよろしいですか? - + failed to fetch update 更新のダウンロードにエラーが発生しました - - + + CHECK 確認 @@ -1073,48 +1073,48 @@ location set SshControl - + SSH Keys SSH 鍵 - + Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. 警告: これは、GitHub の設定にあるすべての公開鍵への SSH アクセスを許可するものです。自分以外の GitHub のユーザー名を入力しないでください。コンマのスタッフが GitHub のユーザー名を追加するようお願いすることはありません。 - - + + ADD 追加 - + Enter your GitHub username GitHub のユーザー名を入力してください - + LOADING ローディング - + REMOVE 削除 - + Username '%1' has no keys on GitHub ユーザー名 “%1” は GitHub に鍵がありません - + Request timed out リクエストタイムアウト - + Username '%1' doesn't exist on GitHub ユーザー名 '%1' は GitHub に存在しません @@ -1122,7 +1122,7 @@ location set SshToggle - + Enable SSH SSH を有効化 @@ -1130,22 +1130,22 @@ location set TermsPage - + Terms & Conditions 利用規約 - + Decline 拒否 - + Scroll to accept スクロールして同意 - + Agree 同意 @@ -1153,92 +1153,92 @@ location set TogglesPanel - + Enable openpilot openpilot を有効化 - + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. アダプティブクルーズコントロールとレーンキーピングドライバーアシスト(openpilotシステム)。この機能を使用するには、常に注意が必要です。この設定を変更すると、車の電源が切れたときに有効になります。 - + Enable Lane Departure Warnings 車線逸脱警報機能を有効化 - + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). 時速31マイル(50km)を超えるスピードで走行中、方向指示器を作動させずに検出された車線ライン上に車両が触れた場合、車線に戻るアラートを受信します。 - + Use Metric System メートル法を有効化 - + Display speed in km/h instead of mph. 速度は mph ではなく km/h で表示されます。 - + Record and Upload Driver Camera 車内カメラの録画とアップロード - + Upload data from the driver facing camera and help improve the driver monitoring algorithm. 車内カメラの映像をアップロードし、ドライバー監視システムのアルゴリズムの向上に役立てます。 - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal アクセル踏むと openpilot をキャンセル - + When enabled, pressing the accelerator pedal will disengage openpilot. 有効な場合は、アクセルを踏むと openpilot をキャンセルします。 - + Show ETA in 24h Format 24時間表示 - + Use 24h format instead of am/pm AM/PM の代わりに24時間形式を使用します - + Show Map on Left Side of UI ディスプレイの左側にマップを表示 - + Show map on left side when in split screen view. 分割画面表示の場合、ディスプレイの左側にマップを表示します。 - + openpilot Longitudinal Control openpilot 縦方向制御 - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot は、車のレーダーを無効化し、アクセルとブレーキの制御を引き継ぎます。注意:AEB を無効化にします! @@ -1246,42 +1246,42 @@ location set Updater - + Update Required 更新が必要です - + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. オペレーティングシステムのアップデートが必要です。Wi-Fi に接続することで、最速のアップデートを体験できます。ダウンロードサイズは約 1GB です。 - + Connect to Wi-Fi Wi-Fi に接続 - + Install インストール - + Back 戻る - + Loading... 読み込み中... - + Reboot 再起動 - + Update failed 更新失敗 @@ -1289,23 +1289,23 @@ location set WifiUI - - + + Scanning for networks... ネットワークをスキャン中... - + CONNECTING... 接続中... - + FORGET 削除 - + Forget Wi-Fi Network "%1"? Wi-Fiネットワーク%1を削除してもよろしいですか? diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 73a5da5ad7..ff83057a93 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -4,17 +4,17 @@ AbstractAlert - + Close 닫기 - + Snooze Update 업데이트 일시중지 - + Reboot and Update 업데이트 및 재부팅 @@ -22,53 +22,53 @@ AdvancedNetworking - + Back 뒤로 - + Enable Tethering 테더링 사용 - + Tethering Password 테더링 비밀번호 - - + + EDIT 편집 - + Enter new tethering password 새 테더링 비밀번호를 입력하세요 - + IP Address IP 주소 - + Enable Roaming 로밍 사용 - + APN Setting APN 설정 - + Enter APN APN 입력 - + leave blank for automatic configuration 자동설정을 하려면 공백으로 두세요 @@ -76,13 +76,13 @@ ConfirmationDialog - - + + Ok 확인 - + Cancel 취소 @@ -90,17 +90,17 @@ DeclinePage - + You must accept the Terms and Conditions in order to use openpilot. openpilot을 사용하려면 이용 약관에 동의해야 합니다. - + Back 뒤로 - + Decline, uninstall %1 거절, %1 제거 @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID Dongle ID - + N/A N/A - + Serial Serial - + Driver Camera 운전자 카메라 - + PREVIEW 미리보기 - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 운전자 모니터링이 좋은 가시성을 갖도록 운전자를 향한 카메라를 미리 봅니다. (차량연결은 해제되어있어야 합니다) - + Reset Calibration 캘리브레이션 재설정 - + RESET 재설정 - + Are you sure you want to reset calibration? 캘리브레이션을 재설정하시겠습니까? - + Review Training Guide 트레이닝 가이드 다시보기 - + REVIEW 다시보기 - + Review the rules, features, and limitations of openpilot openpilot의 규칙, 기능 및 제한 다시보기 - + Are you sure you want to review the training guide? 트레이닝 가이드를 다시보시겠습니까? - + Regulatory 규제 - + VIEW 보기 - + Change Language 언어 변경 - + CHANGE 변경 - + Select a language 언어를 선택하세요 - + Reboot 재부팅 - + Power Off 전원 종료 - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot은 장치를 좌측 또는 우측은 4° 이내, 위쪽 5° 또는 아래쪽은 8° 이내로 설치해야 합니다. openpilot은 지속적으로 보정되므로 리셋이 거의 필요하지 않습니다. - + Your device is pointed %1° %2 and %3° %4. 사용자의 장치가 %1° %2 및 %3° %4를 가리키고 있습니다. - + down 아래로 - + up 위로 - + left 좌측으로 - + right 우측으로 - + Are you sure you want to reboot? 재부팅 하시겠습니까? - + Disengage to Reboot 재부팅 하려면 해제하세요 - + Are you sure you want to power off? 전원을 종료하시겠습니까? - + Disengage to Power Off 전원을 종료하려면 해제하세요 @@ -261,32 +261,32 @@ DriveStats - + Drives 주행 - + Hours 시간 - + ALL TIME 전체 - + PAST WEEK 지난주 - + KM Km - + Miles Miles @@ -294,7 +294,7 @@ DriverViewScene - + camera starting 카메라 시작중 @@ -302,12 +302,12 @@ InputDialog - + Cancel 취소 - + Need at least %n character(s)! 최소 %n 자가 필요합니다! @@ -317,22 +317,22 @@ Installer - + Installing... 설치중... - + Receiving objects: 수신중: - + Resolving deltas: 델타병합: - + Updating files: 파일갱신: @@ -340,27 +340,27 @@ MapETA - + eta 도착 - + min - + hr 시간 - + km km - + mi mi @@ -368,22 +368,22 @@ MapInstructions - + km km - + m m - + mi mi - + ft ft @@ -391,48 +391,48 @@ MapPanel - + Current Destination 현재 목적지 - + CLEAR 삭제 - + Recent Destinations 최근 목적지 - + Try the Navigation Beta 네비게이션(베타)를 사용해보세요 - + Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai 자세한 경로안내를 원하시면 comma prime을 구독하세요. 등록:https://connect.comma.ai - + No home location set 집 설정되지않음 - + No work location set 회사 설정되지않음 - + no recent destinations 최근 목적지 없음 @@ -440,12 +440,12 @@ location set MapWindow - + Map Loading 지도 로딩 - + Waiting for GPS GPS를 기다리는 중 @@ -453,12 +453,12 @@ location set MultiOptionDialog - + Select 선택 - + Cancel 취소 @@ -466,23 +466,23 @@ location set Networking - + Advanced 고급 설정 - + Enter password 비밀번호를 입력하세요 - - + + for "%1" 하기위한 "%1" - + Wrong password 비밀번호가 틀렸습니다 @@ -490,30 +490,30 @@ location set NvgWindow - + km/h km/h - + mph mph - - + + MAX MAX - - + + SPEED SPEED - - + + LIMIT LIMIT @@ -521,17 +521,17 @@ location set OffroadHome - + UPDATE 업데이트 - + ALERTS 알림 - + ALERT 알림 @@ -539,22 +539,22 @@ location set PairingPopup - + Pair your device to your comma account 장치를 콤마 계정과 페어링합니다 - + Go to https://connect.comma.ai on your phone https://connect.comma.ai에 접속하세요 - + Click "add new device" and scan the QR code on the right "새 장치 추가"를 클릭하고 오른쪽 QR 코드를 검색합니다 - + Bookmark connect.comma.ai to your home screen to use it like an app connect.comma.ai을 앱처럼 사용하려면 홈 화면에 바로가기를 만드십시오 @@ -562,32 +562,32 @@ location set PrimeAdWidget - + Upgrade Now 지금 업그레이드 - + Become a comma prime member at connect.comma.ai connect.comma.ai에서 comma prime에 가입합니다 - + PRIME FEATURES: PRIME 기능: - + Remote access 원격 접속 - + 1 year of storage 1년간 저장 - + Developer perks 개발자 혜택 @@ -595,22 +595,22 @@ location set PrimeUserWidget - + ✓ SUBSCRIBED ✓ 구독함 - + comma prime comma prime - + CONNECT.COMMA.AI CONNECT.COMMA.AI - + COMMA POINTS COMMA POINTS @@ -618,41 +618,41 @@ location set QObject - + Reboot 재부팅 - + Exit 종료 - + dashcam dashcam - + openpilot openpilot - + %n minute(s) ago %n 분전 - + %n hour(s) ago %n 시간전 - + %n day(s) ago %n 일전 @@ -662,47 +662,47 @@ location set Reset - + Reset failed. Reboot to try again. 초기화 실패. 재부팅후 다시 시도하세요. - + Are you sure you want to reset your device? 장치를 초기화 하시겠습니까? - + Resetting device... 장치 초기화중... - + System Reset 장치 초기화 - + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. 장치를 초기화 합니다. 확인버튼을 누르면 모든 내용과 설정이 초기화됩니다. 취소를 누르면 다시 부팅합니다. - + Cancel 취소 - + Reboot 재부팅 - + Confirm 확인 - + Unable to mount data partition. Press confirm to reset your device. 데이터 파티션을 마운트할 수 없습니다. 확인 버튼을 눌러 장치를 리셋합니다. @@ -710,7 +710,7 @@ location set RichTextDialog - + Ok 확인 @@ -718,33 +718,33 @@ location set SettingsWindow - + × × - + Device 장치 - - + + Network 네트워크 - + Toggles 토글 - + Software 소프트웨어 - + Navigation 네비게이션 @@ -752,105 +752,105 @@ location set Setup - + WARNING: Low Voltage 경고: 전압이 낮습니다 - + Power your device in a car with a harness or proceed at your own risk. 하네스 보드에 차량의 전원을 연결하세요. - + Power off 전원 종료 - - - + + + Continue 계속 - + Getting Started 설정 시작 - + Before we get on the road, let’s finish installation and cover some details. 출발하기 전에 설정을 완료하고 몇 가지 세부 사항을 살펴보겠습니다. - + Connect to Wi-Fi wifi 연결 - - + + Back 뒤로 - + Continue without Wi-Fi wifi 없이 계속 - + Waiting for internet 네트워크 접속을 기다립니다 - + Choose Software to Install 설치할 소프트웨어를 선택하세요 - + Dashcam Dashcam - + Custom Software Custom Software - + Enter URL URL 입력 - + for Custom Software for Custom Software - + Downloading... 다운로드중... - + Download Failed 다운로드 실패 - + Ensure the entered URL is valid, and the device’s internet connection is good. 입력된 URL이 유효하고 장치의 인터넷 연결이 잘 되어 있는지 확인합니다. - + Reboot device 재부팅 - + Start over 다시 시작 @@ -858,17 +858,17 @@ location set SetupWidget - + Finish Setup 설정 완료 - + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. 장치를 (connect.comma.ai)에서 페어링하고 comma prime 오퍼를 청구합니다. - + Pair device 장치 페어링 @@ -876,106 +876,106 @@ location set Sidebar - - + + CONNECT 연결 - + OFFLINE 오프라인 - - + + ONLINE 온라인 - + ERROR 오류 - - - + + + TEMP 온도 - + HIGH 높음 - + GOOD 좋음 - + OK 경고 - + VEHICLE 차량 - + NO NO - + PANDA PANDA - + GPS GPS - + SEARCH 검색중 - + -- -- - + Wi-Fi Wi-Fi - + ETH 이더넷 - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G @@ -983,89 +983,89 @@ location set SoftwarePanel - + Git Branch Git 브렌치 - + Git Commit Git 커밋 - + OS Version OS 버전 - + Version 버전 - + Last Update Check 최신 업데이트 검사 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. 최근에 openpilot이 업데이트를 성공적으로 확인했습니다. 업데이트 프로그램은 차량 연결이 해제되었을때만 작동합니다. - + Check for Update 업데이트 확인 - + CHECKING 확인중 - + Switch Branch 브랜치 변경 - + ENTER 입력하세요 - - + + The new branch will be pulled the next time the updater runs. 다음 업데이트 프로그램이 실행될 때 새 브랜치가 적용됩니다. - + Enter branch name 브랜치명 입력 - + UNINSTALL 제거 - + Uninstall %1 %1 제거 - + Are you sure you want to uninstall? 제거하시겠습니까? - + failed to fetch update 업데이트를 가져올수없습니다 - - + + CHECK 확인 @@ -1073,48 +1073,48 @@ location set SshControl - + SSH Keys SSH 키 - + Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. 경고:이렇게 하면 GitHub 설정의 모든 공용 키에 대한 SSH 액세스 권한이 부여됩니다. 자신의 사용자 이름이 아닌 GitHub 사용자 이름을 입력하지 마십시오. comma 직원은 GitHub 사용자 이름을 추가하도록 요청하지 않습니다. - - + + ADD 추가 - + Enter your GitHub username GitHub 사용자 ID - + LOADING 로딩 - + REMOVE 제거 - + Username '%1' has no keys on GitHub '%1'의 키가 GitHub에 없습니다 - + Request timed out 요청 시간 초과 - + Username '%1' doesn't exist on GitHub '%1'은 GitHub에 없습니다 @@ -1122,7 +1122,7 @@ location set SshToggle - + Enable SSH SSH 사용 @@ -1130,22 +1130,22 @@ location set TermsPage - + Terms & Conditions 약관 - + Decline 거절 - + Scroll to accept 허용하려면 아래로 스크롤하세요 - + Agree 동의 @@ -1153,92 +1153,92 @@ location set TogglesPanel - + Enable openpilot openpilot 사용 - + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. 어댑티브 크루즈 컨트롤 및 차선 유지 운전자 보조를 위해 openpilot 시스템을 사용하십시오. 이 기능을 사용하려면 항상 주의를 기울여야 합니다. 이 설정을 변경하면 차량 전원이 꺼질 때 적용됩니다. - + Enable Lane Departure Warnings 차선 이탈 경고 사용 - + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). 차량이 50km/h(31mph) 이상의 속도로 주행하는 동안 방향 지시등이 활성화되지 않은 상태에서 감지된 차선 위를 주행할 경우 차선이탈 경고를 사용합니다. - + Use Metric System 미터법 사용 - + Display speed in km/h instead of mph. mph 대신 km/h로 속도를 표시합니다. - + Record and Upload Driver Camera 운전자 카메라 녹화 및 업로드 - + Upload data from the driver facing camera and help improve the driver monitoring algorithm. 운전자 카메라에서 데이터를 업로드하고 운전자 모니터링 알고리즘을 개선합니다. - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 🌮 e2e long 사용 (매우 실험적) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. 주행모델이 가속과 감속을 제어하도록 하면 openpilot은 운전자가 생각하는것처럼 운전합니다. (매우 실험적) - + Disengage On Accelerator Pedal 가속페달 조작시 해제 - + When enabled, pressing the accelerator pedal will disengage openpilot. 활성화된 경우 가속 페달을 누르면 openpilot이 해제됩니다. - + Show ETA in 24h Format 24시간 형식으로 도착예정시간 표시 - + Use 24h format instead of am/pm 오전/오후 대신 24시간 형식 사용 - + Show Map on Left Side of UI UI 왼쪽에 지도 표시 - + Show map on left side when in split screen view. 분할 화면 보기에서 지도를 왼쪽에 표시합니다. - + openpilot Longitudinal Control openpilot Longitudinal Control - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot은 차량'의 레이더를 무력화시키고 가속페달과 브레이크의 제어를 인계받을 것이다. 경고: AEB를 비활성화합니다! @@ -1246,42 +1246,42 @@ location set Updater - + Update Required 업데이트 필요 - + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. OS 업데이트가 필요합니다. 장치를 wifi에 연결하여 가장 빠른 업데이트 경험을 제공합니다. 다운로드 크기는 약 1GB입니다. - + Connect to Wi-Fi wifi 연결 - + Install 설치 - + Back 뒤로 - + Loading... 로딩중... - + Reboot 재부팅 - + Update failed 업데이트 실패 @@ -1289,23 +1289,23 @@ location set WifiUI - - + + Scanning for networks... 네트워크 검색 중... - + CONNECTING... 연결중... - + FORGET 저장안함 - + Forget Wi-Fi Network "%1"? wifi 네트워크 저장안함 "%1"? diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index f50cf65e15..622d8ee443 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -4,17 +4,17 @@ AbstractAlert - + Close Fechar - + Snooze Update Adiar Atualização - + Reboot and Update Reiniciar e Atualizar @@ -22,53 +22,53 @@ AdvancedNetworking - + Back Voltar - + Enable Tethering Ativar Tether - + Tethering Password Senha Tethering - - + + EDIT EDITAR - + Enter new tethering password Insira nova senha tethering - + IP Address Endereço IP - + Enable Roaming Ativar Roaming - + APN Setting APN Config - + Enter APN Insira APN - + leave blank for automatic configuration deixe em branco para configuração automática @@ -76,13 +76,13 @@ ConfirmationDialog - - + + Ok OK - + Cancel Cancelar @@ -90,17 +90,17 @@ DeclinePage - + You must accept the Terms and Conditions in order to use openpilot. Você precisa aceitar os Termos e Condições para utilizar openpilot. - + Back Voltar - + Decline, uninstall %1 Rejeitar, desintalar %1 @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID Dongle ID - + N/A N/A - + Serial Serial - + Driver Camera Câmera voltada para o Motorista - + PREVIEW PREVISUAL - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) Pré-visualizar a câmera voltada para o motorista para garantir que monitor tem uma boa visibilidade (veículo precisa estar desligado) - + Reset Calibration Resetar Calibragem - + RESET RESET - + Are you sure you want to reset calibration? Tem certeza que quer resetar a calibragem? - + Review Training Guide Revisar o Treinamento - + REVIEW REVISAR - + Review the rules, features, and limitations of openpilot Revisar regras, aprimoramentos e limitações do openpilot - + Are you sure you want to review the training guide? Tem certeza que quer rever o treinamento? - + Regulatory Regulatório - + VIEW VER - + Change Language Mudar Linguagem - + CHANGE MUDAR - + Select a language Selecione uma linguagem - + Reboot Reiniciar - + Power Off Desligar - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. o openpilot requer que o dispositivo seja montado dentro de 4° esquerda ou direita e dentro de 5° para cima ou 8° para baixo. o openpilot está continuamente calibrando, resetar raramente é necessário. - + Your device is pointed %1° %2 and %3° %4. Seu dispositivo está montado %1° %2 e %3° %4. - + down baixo - + up cima - + left esquerda - + right direita - + Are you sure you want to reboot? Tem certeza que quer reiniciar? - + Disengage to Reboot Desacione para Reiniciar - + Are you sure you want to power off? Tem certeza que quer desligar? - + Disengage to Power Off Desacione para Desligar @@ -261,32 +261,32 @@ DriveStats - + Drives Dirigidas - + Hours Horas - + ALL TIME TOTAL - + PAST WEEK SEMANA PASSADA - + KM KM - + Miles Milhas @@ -294,7 +294,7 @@ DriverViewScene - + camera starting câmera iniciando @@ -302,12 +302,12 @@ InputDialog - + Cancel Cancelar - + Need at least %n character(s)! Necessita no mínimo %n caractere! @@ -318,22 +318,22 @@ Installer - + Installing... Instalando... - + Receiving objects: Recebendo objetos: - + Resolving deltas: Resolvendo deltas: - + Updating files: Atualizando arquivos: @@ -341,27 +341,27 @@ MapETA - + eta eta - + min min - + hr hr - + km km - + mi mi @@ -369,22 +369,22 @@ MapInstructions - + km km - + m m - + mi milha - + ft pés @@ -392,48 +392,48 @@ MapPanel - + Current Destination Destino Atual - + CLEAR LIMPAR - + Recent Destinations Destinos Recentes - + Try the Navigation Beta Experimente a Navegação Beta - + Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai Obtenha instruções passo a passo exibidas e muito mais com uma assinatura prime Inscreva-se agora: https://connect.comma.ai - + No home location set Sem local residência definido - + No work location set Sem local de trabalho definido - + no recent destinations sem destinos recentes @@ -441,12 +441,12 @@ trabalho definido MapWindow - + Map Loading Carregando Mapa - + Waiting for GPS Esperando por GPS @@ -454,12 +454,12 @@ trabalho definido MultiOptionDialog - + Select Selecione - + Cancel Cancelar @@ -467,23 +467,23 @@ trabalho definido Networking - + Advanced Avançado - + Enter password Insira a senha - - + + for "%1" para "%1" - + Wrong password Senha incorreta @@ -491,30 +491,30 @@ trabalho definido NvgWindow - + km/h km/h - + mph mph - - + + MAX LIMITE - - + + SPEED MAX - - + + LIMIT VELO @@ -522,17 +522,17 @@ trabalho definido OffroadHome - + UPDATE ATUALIZAÇÃO - + ALERTS ALERTAS - + ALERT ALERTA @@ -540,22 +540,22 @@ trabalho definido PairingPopup - + Pair your device to your comma account Pareie seu dispositivo à sua conta comma - + Go to https://connect.comma.ai on your phone navegue até https://connect.comma.ai no seu telefone - + Click "add new device" and scan the QR code on the right Clique "add new device" e escaneie o QR code a seguir - + Bookmark connect.comma.ai to your home screen to use it like an app Salve connect.comma.ai como sua página inicial para utilizar como um app @@ -563,32 +563,32 @@ trabalho definido PrimeAdWidget - + Upgrade Now Atualizar Agora - + Become a comma prime member at connect.comma.ai Torne-se um membro comma prime em connect.comma.ai - + PRIME FEATURES: APRIMORAMENTOS PRIME: - + Remote access Acesso remoto - + 1 year of storage 1 ano de armazenamento - + Developer perks Benefícios para desenvolvedor @@ -596,22 +596,22 @@ trabalho definido PrimeUserWidget - + ✓ SUBSCRIBED ✓ INSCRITO - + comma prime comma prime - + CONNECT.COMMA.AI CONNECT.COMMA.AI - + COMMA POINTS PONTOS COMMA @@ -619,27 +619,27 @@ trabalho definido QObject - + Reboot Reiniciar - + Exit Sair - + dashcam dashcam - + openpilot openpilot - + %n minute(s) ago há %n minuto @@ -647,7 +647,7 @@ trabalho definido - + %n hour(s) ago há %n hora @@ -655,7 +655,7 @@ trabalho definido - + %n day(s) ago há %n dia @@ -666,47 +666,47 @@ trabalho definido Reset - + Reset failed. Reboot to try again. Reset falhou. Reinicie para tentar novamente. - + Are you sure you want to reset your device? Tem certeza que quer resetar seu dispositivo? - + Resetting device... Resetando dispositivo... - + System Reset Resetar Sistema - + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. Solicitado reset do sistema. Confirme para apagar todo conteúdo e configurações. Aperte cancelar para continuar boot. - + Cancel Cancelar - + Reboot Reiniciar - + Confirm Confirmar - + Unable to mount data partition. Press confirm to reset your device. Não foi possível montar a partição de dados. Pressione confirmar para resetar seu dispositivo. @@ -714,7 +714,7 @@ trabalho definido RichTextDialog - + Ok Ok @@ -722,33 +722,33 @@ trabalho definido SettingsWindow - + × × - + Device Dispositivo - - + + Network Rede - + Toggles Ajustes - + Software Software - + Navigation Navegação @@ -756,105 +756,105 @@ trabalho definido Setup - + WARNING: Low Voltage ALERTA: Baixa Voltagem - + Power your device in a car with a harness or proceed at your own risk. Ligue seu dispositivo em um carro com um chicote ou prossiga por sua conta e risco. - + Power off Desligar - - - + + + Continue Continuar - + Getting Started Começando - + Before we get on the road, let’s finish installation and cover some details. Antes de pegarmos a estrada, vamos terminar a instalação e cobrir alguns detalhes. - + Connect to Wi-Fi Conectar ao Wi-Fi - - + + Back Voltar - + Continue without Wi-Fi Continuar sem Wi-Fi - + Waiting for internet Esperando pela internet - + Choose Software to Install Escolher Software para Instalar - + Dashcam Dashcam - + Custom Software Sofware Customizado - + Enter URL Preencher URL - + for Custom Software para o Software Customizado - + Downloading... Baixando... - + Download Failed Download Falhou - + Ensure the entered URL is valid, and the device’s internet connection is good. Garanta que a URL inserida é valida, e uma boa conexão à internet. - + Reboot device Reiniciar Dispositivo - + Start over Inicializar @@ -862,17 +862,17 @@ trabalho definido SetupWidget - + Finish Setup Concluir - + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. Pareie seu dispositivo com comma connect (connect.comma.ai) e reivindique sua oferta de comma prime. - + Pair device Parear dispositivo @@ -880,106 +880,106 @@ trabalho definido Sidebar - - + + CONNECT CONEXÃO - + OFFLINE DESCONEC - - + + ONLINE CONECTADO - + ERROR ERRO - - - + + + TEMP TEMP - + HIGH ALTA - + GOOD BOA - + OK OK - + VEHICLE VEÍCULO - + NO SEM - + PANDA PANDA - + GPS GPS - + SEARCH PROCURA - + -- -- - + Wi-Fi Wi-Fi - + ETH ETH - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G @@ -987,89 +987,89 @@ trabalho definido SoftwarePanel - + Git Branch Ramo Git - + Git Commit Commit Git - + OS Version Versão do Sistema - + Version Versão - + Last Update Check Verificação da última atualização - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. A última vez que o openpilot verificou com sucesso uma atualização. O atualizador só funciona com o carro desligado. - + Check for Update Verifique atualizações - + CHECKING VERIFICANDO - + Switch Branch Trocar Branch - + ENTER INSERIR - - + + The new branch will be pulled the next time the updater runs. A nova branch será aplicada ao verificar atualizações. - + Enter branch name Inserir o nome da branch - + UNINSTALL DESINSTALAR - + Uninstall %1 Desintalar o %1 - + Are you sure you want to uninstall? Tem certeza que quer desinstalar? - + failed to fetch update falha ao buscar atualização - - + + CHECK VERIFICAR @@ -1077,48 +1077,48 @@ trabalho definido SshControl - + SSH Keys Chave SSH - + Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. Aviso: isso concede acesso SSH a todas as chaves públicas nas configurações do GitHub. Nunca insira um nome de usuário do GitHub que não seja o seu. Um funcionário da comma NUNCA pedirá que você adicione seu nome de usuário do GitHub. - - + + ADD ADICIONAR - + Enter your GitHub username Insira seu nome de usuário do GitHub - + LOADING CARREGANDO - + REMOVE REMOVER - + Username '%1' has no keys on GitHub Usuário "%1” não possui chaves no GitHub - + Request timed out A solicitação expirou - + Username '%1' doesn't exist on GitHub Usuário '%1' não existe no GitHub @@ -1126,7 +1126,7 @@ trabalho definido SshToggle - + Enable SSH Habilitar SSH @@ -1134,22 +1134,22 @@ trabalho definido TermsPage - + Terms & Conditions Termos & Condições - + Decline Declinar - + Scroll to accept Role a tela para aceitar - + Agree Concordo @@ -1157,92 +1157,92 @@ trabalho definido TogglesPanel - + Enable openpilot Ativar openpilot - + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. Use o sistema openpilot para controle de cruzeiro adaptativo e assistência ao motorista de manutenção de faixa. Sua atenção é necessária o tempo todo para usar esse recurso. A alteração desta configuração tem efeito quando o carro é desligado. - + Enable Lane Departure Warnings Ativar Avisos de Saída de Faixa - + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). Receba alertas para voltar para a pista se o seu veículo sair da faixa e a seta não tiver sido acionada previamente quando em velocidades superiores a 50 km/h. - + Use Metric System Usar Sistema Métrico - + Display speed in km/h instead of mph. Exibir velocidade em km/h invés de mph. - + Record and Upload Driver Camera Gravar e Upload Câmera Motorista - + Upload data from the driver facing camera and help improve the driver monitoring algorithm. Upload dados da câmera voltada para o motorista e ajude a melhorar o algoritmo de monitoramentor. - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 🌮 End-to-end longitudinal (experimental) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. Deixe o modelo de direção controlar o acelerador e o freio, o openpilot dirigirá da maneira como ele entende que um humano o faria. Super experimental. - + Disengage On Accelerator Pedal Desacionar Com Pedal Do Acelerador - + When enabled, pressing the accelerator pedal will disengage openpilot. Quando ativado, pressionar o pedal do acelerador desacionará o openpilot. - + Show ETA in 24h Format Mostrar ETA em formato 24h - + Use 24h format instead of am/pm Use o formato 24h em vez de am/pm - + Show Map on Left Side of UI Exibir Mapa no Lado Esquerdo - + Show map on left side when in split screen view. Exibir mapa do lado esquerdo quando a tela for dividida. - + openpilot Longitudinal Control openpilot Controle Longitudinal - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot desativará o radar do carro e assumirá o controle do acelerador e freios. Atenção: isso desativa AEB! @@ -1250,42 +1250,42 @@ trabalho definido Updater - + Update Required Atualização Necessária - + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. Uma atualização do sistema operacional é necessária. Conecte seu dispositivo ao Wi-Fi para a experiência de atualização mais rápida. O tamanho do download é de aproximadamente 1GB. - + Connect to Wi-Fi Conecte-se ao Wi-Fi - + Install Instalar - + Back Voltar - + Loading... Carregando... - + Reboot Reiniciar - + Update failed Falha na atualização @@ -1293,23 +1293,23 @@ trabalho definido WifiUI - - + + Scanning for networks... Procurando redes... - + CONNECTING... CONECTANDO... - + FORGET ESQUECER - + Forget Wi-Fi Network "%1"? Esquecer Rede Wi-Fi "%1"? diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 1a384482da..79a08899cb 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -4,17 +4,17 @@ AbstractAlert - + Close 关闭 - + Snooze Update 暂停更新 - + Reboot and Update 重启并更新 @@ -22,53 +22,53 @@ AdvancedNetworking - + Back 返回 - + Enable Tethering 启用WiFi热点 - + Tethering Password WiFi热点密码 - - + + EDIT 编辑 - + Enter new tethering password 输入新的WiFi热点密码 - + IP Address IP地址 - + Enable Roaming 启用数据漫游 - + APN Setting APN设置 - + Enter APN 输入APN - + leave blank for automatic configuration 留空以自动配置 @@ -76,13 +76,13 @@ ConfirmationDialog - - + + Ok 好的 - + Cancel 取消 @@ -90,17 +90,17 @@ DeclinePage - + You must accept the Terms and Conditions in order to use openpilot. 您必须接受条款和条件以使用openpilot。 - + Back 返回 - + Decline, uninstall %1 拒绝并卸载%1 @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID 设备ID(Dongle ID) - + N/A N/A - + Serial 序列号 - + Driver Camera 驾驶员摄像头 - + PREVIEW 预览 - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 打开并预览驾驶员摄像头,以确保驾驶员监控具有良好视野。仅熄火时可用。 - + Reset Calibration 重置设备校准 - + RESET 重置 - + Are you sure you want to reset calibration? 您确定要重置设备校准吗? - + Review Training Guide 新手指南 - + REVIEW 查看 - + Review the rules, features, and limitations of openpilot 查看openpilot的使用规则,以及其功能和限制。 - + Are you sure you want to review the training guide? 您确定要查看新手指南吗? - + Regulatory 监管信息 - + VIEW 查看 - + Change Language 切换语言 - + CHANGE 切换 - + Select a language 选择语言 - + Reboot 重启 - + Power Off 关机 - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot要求设备安装的偏航角在左4°和右4°之间,俯仰角在上5°和下8°之间。一般来说,openpilot会持续更新校准,很少需要重置。 - + Your device is pointed %1° %2 and %3° %4. 您的设备校准为%1° %2、%3° %4。 - + down 朝下 - + up 朝上 - + left 朝左 - + right 朝右 - + Are you sure you want to reboot? 您确定要重新启动吗? - + Disengage to Reboot 取消openpilot以重新启动 - + Are you sure you want to power off? 您确定要关机吗? - + Disengage to Power Off 取消openpilot以关机 @@ -261,32 +261,32 @@ DriveStats - + Drives 旅程数 - + Hours 小时 - + ALL TIME 全部 - + PAST WEEK 过去一周 - + KM 公里 - + Miles 英里 @@ -294,7 +294,7 @@ DriverViewScene - + camera starting 正在启动相机 @@ -302,12 +302,12 @@ InputDialog - + Cancel 取消 - + Need at least %n character(s)! 至少需要 %n 个字符! @@ -317,22 +317,22 @@ Installer - + Installing... 正在安装…… - + Receiving objects: 正在接收: - + Resolving deltas: 正在处理: - + Updating files: 正在更新文件: @@ -340,27 +340,27 @@ MapETA - + eta 埃塔 - + min 分钟 - + hr 小时 - + km km - + mi mi @@ -368,22 +368,22 @@ MapInstructions - + km km - + m m - + mi mi - + ft ft @@ -391,46 +391,46 @@ MapPanel - + Current Destination 当前目的地 - + CLEAR 清空 - + Recent Destinations 最近目的地 - + Try the Navigation Beta 试用导航测试版 - + Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai 订阅comma prime以获取导航。 立即注册:https://connect.comma.ai - + No home location set 家:未设定 - + No work location set 工作:未设定 - + no recent destinations 无最近目的地 @@ -438,12 +438,12 @@ location set MapWindow - + Map Loading 地图加载中 - + Waiting for GPS 等待 GPS @@ -451,12 +451,12 @@ location set MultiOptionDialog - + Select 选择 - + Cancel 取消 @@ -464,23 +464,23 @@ location set Networking - + Advanced 高级 - + Enter password 输入密码 - - + + for "%1" 网络名称:"%1" - + Wrong password 密码错误 @@ -488,30 +488,30 @@ location set NvgWindow - + km/h km/h - + mph mph - - + + MAX 最高定速 - - + + SPEED SPEED - - + + LIMIT LIMIT @@ -519,17 +519,17 @@ location set OffroadHome - + UPDATE 更新 - + ALERTS 警报 - + ALERT 警报 @@ -537,22 +537,22 @@ location set PairingPopup - + Pair your device to your comma account 将您的设备与comma账号配对 - + Go to https://connect.comma.ai on your phone 在手机上访问 https://connect.comma.ai - + Click "add new device" and scan the QR code on the right 点击“添加新设备”,扫描右侧二维码 - + Bookmark connect.comma.ai to your home screen to use it like an app 将 connect.comma.ai 收藏到您的主屏幕,以便像应用程序一样使用它 @@ -560,32 +560,32 @@ location set PrimeAdWidget - + Upgrade Now 现在升级 - + Become a comma prime member at connect.comma.ai 打开connect.comma.ai以注册comma prime会员 - + PRIME FEATURES: comma prime特权: - + Remote access 远程访问 - + 1 year of storage 1年数据存储 - + Developer perks 开发者福利 @@ -593,22 +593,22 @@ location set PrimeUserWidget - + ✓ SUBSCRIBED ✓ 已订阅 - + comma prime comma prime - + CONNECT.COMMA.AI CONNECT.COMMA.AI - + COMMA POINTS COMMA POINTS点数 @@ -616,41 +616,41 @@ location set QObject - + Reboot 重启 - + Exit 退出 - + dashcam 行车记录仪 - + openpilot openpilot - + %n minute(s) ago %n 分钟前 - + %n hour(s) ago %n 小时前 - + %n day(s) ago %n 天前 @@ -660,47 +660,47 @@ location set Reset - + Reset failed. Reboot to try again. 重置失败。 重新启动以重试。 - + Are you sure you want to reset your device? 您确定要重置您的设备吗? - + Resetting device... 正在重置设备…… - + System Reset 恢复出厂设置 - + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. 已触发系统重置:确认以删除所有内容和设置。取消以正常启动设备。 - + Cancel 取消 - + Reboot 重启 - + Confirm 确认 - + Unable to mount data partition. Press confirm to reset your device. 无法挂载数据分区。 确认以重置您的设备。 @@ -708,7 +708,7 @@ location set RichTextDialog - + Ok 好的 @@ -716,33 +716,33 @@ location set SettingsWindow - + × × - + Device 设备 - - + + Network 网络 - + Toggles 设定 - + Software 软件 - + Navigation 导航 @@ -750,105 +750,105 @@ location set Setup - + WARNING: Low Voltage 警告:低电压 - + Power your device in a car with a harness or proceed at your own risk. 请使用car harness线束为您的设备供电,或自行承担风险。 - + Power off 关机 - - - + + + Continue 继续 - + Getting Started 开始设置 - + Before we get on the road, let’s finish installation and cover some details. 开始旅程之前,让我们完成安装并介绍一些细节。 - + Connect to Wi-Fi 连接到WiFi - - + + Back 返回 - + Continue without Wi-Fi 不连接WiFi并继续 - + Waiting for internet 等待网络连接 - + Choose Software to Install 选择要安装的软件 - + Dashcam Dashcam(行车记录仪) - + Custom Software 自定义软件 - + Enter URL 输入网址 - + for Custom Software 以下载自定义软件 - + Downloading... 正在下载…… - + Download Failed 下载失败 - + Ensure the entered URL is valid, and the device’s internet connection is good. 请确保互联网连接良好且输入的URL有效。 - + Reboot device 重启设备 - + Start over 重来 @@ -856,17 +856,17 @@ location set SetupWidget - + Finish Setup 完成设置 - + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. 将您的设备与comma connect (connect.comma.ai)配对并领取您的comma prime优惠。 - + Pair device 配对设备 @@ -874,106 +874,106 @@ location set Sidebar - - + + CONNECT CONNECT - + OFFLINE 离线 - - + + ONLINE 在线 - + ERROR 连接出错 - - - + + + TEMP 设备温度 - + HIGH 过热 - + GOOD 良好 - + OK 一般 - + VEHICLE 车辆连接 - + NO - + PANDA PANDA - + GPS GPS - + SEARCH 搜索中 - + -- -- - + Wi-Fi Wi-Fi - + ETH 以太网 - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G @@ -981,89 +981,89 @@ location set SoftwarePanel - + Git Branch Git Branch - + Git Commit Git Commit - + OS Version 系统版本 - + Version 软件版本 - + Last Update Check 上次检查更新 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. 上一次成功检查更新的时间。更新程序仅在汽车熄火时运行。 - + Check for Update 检查更新 - + CHECKING 正在检查更新 - + Switch Branch 切换分支 - + ENTER 输入 - - + + The new branch will be pulled the next time the updater runs. 分支将在更新服务下次启动时自动切换。 - + Enter branch name 输入分支名称 - + UNINSTALL 卸载 - + Uninstall %1 卸载 %1 - + Are you sure you want to uninstall? 您确定要卸载吗? - + failed to fetch update 获取更新失败 - - + + CHECK 查看 @@ -1071,48 +1071,48 @@ location set SshControl - + SSH Keys SSH密钥 - + Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. 警告:这将授予SSH访问权限给您GitHub设置中的所有公钥。切勿输入您自己以外的GitHub用户名。comma员工永远不会要求您添加他们的GitHub用户名。 - - + + ADD 添加 - + Enter your GitHub username 输入您的GitHub用户名 - + LOADING 正在加载 - + REMOVE 删除 - + Username '%1' has no keys on GitHub 用户名“%1”在GitHub上没有密钥 - + Request timed out 请求超时 - + Username '%1' doesn't exist on GitHub GitHub上不存在用户名“%1” @@ -1120,7 +1120,7 @@ location set SshToggle - + Enable SSH 启用SSH @@ -1128,22 +1128,22 @@ location set TermsPage - + Terms & Conditions 条款和条件 - + Decline 拒绝 - + Scroll to accept 滑动以接受 - + Agree 同意 @@ -1151,92 +1151,92 @@ location set TogglesPanel - + Enable openpilot 启用openpilot - + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. 使用openpilot进行自适应巡航和车道保持辅助。使用此功能时您必须时刻保持注意力。该设置的更改在熄火时生效。 - + Enable Lane Departure Warnings 启用车道偏离警告 - + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). 车速超过31mph(50km/h)时,若检测到车辆越过车道线且未打转向灯,系统将发出警告以提醒您返回车道。 - + Use Metric System 使用公制单位 - + Display speed in km/h instead of mph. 显示车速时,以km/h代替mph。 - + Record and Upload Driver Camera 录制并上传驾驶员摄像头 - + Upload data from the driver facing camera and help improve the driver monitoring algorithm. 上传驾驶员摄像头的数据,帮助改进驾驶员监控算法。 - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal 踩油门时取消控制 - + When enabled, pressing the accelerator pedal will disengage openpilot. 启用后,踩下油门踏板将取消openpilot。 - + Show ETA in 24h Format 以24小时格式显示预计到达时间 - + Use 24h format instead of am/pm 使用24小时制代替am/pm - + Show Map on Left Side of UI 在介面左侧显示地图 - + Show map on left side when in split screen view. 在分屏模式中,将地图置于屏幕左侧。 - + openpilot Longitudinal Control openpilot纵向控制 - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot将禁用车辆的雷达并接管油门和刹车的控制。警告:AEB将被禁用! @@ -1244,42 +1244,42 @@ location set Updater - + Update Required 需要更新 - + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. 操作系统需要更新。请将您的设备连接到WiFi以获取更快的更新体验。下载大小约为1GB。 - + Connect to Wi-Fi 连接到WiFi - + Install 安装 - + Back 返回 - + Loading... 正在加载…… - + Reboot 重启 - + Update failed 更新失败 @@ -1287,23 +1287,23 @@ location set WifiUI - - + + Scanning for networks... 正在扫描网络…… - + CONNECTING... 正在连接…… - + FORGET 忘记 - + Forget Wi-Fi Network "%1"? 忘记WiFi网络 "%1"? diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index d7dd5cb563..0d51e6d286 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -4,17 +4,17 @@ AbstractAlert - + Close 關閉 - + Snooze Update 暫停更新 - + Reboot and Update 重啟並更新 @@ -22,53 +22,53 @@ AdvancedNetworking - + Back 回上頁 - + Enable Tethering 啟用網路分享 - + Tethering Password 網路分享密碼 - - + + EDIT 編輯 - + Enter new tethering password 輸入新的網路分享密碼 - + IP Address IP 地址 - + Enable Roaming 啟用漫遊 - + APN Setting APN 設置 - + Enter APN 輸入 APN - + leave blank for automatic configuration 留空白將自動配置 @@ -76,13 +76,13 @@ ConfirmationDialog - - + + Ok 確定 - + Cancel 取消 @@ -90,17 +90,17 @@ DeclinePage - + You must accept the Terms and Conditions in order to use openpilot. 您必須先接受條款和條件才能使用 openpilot。 - + Back 回上頁 - + Decline, uninstall %1 拒絕並卸載 %1 @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID Dongle ID - + N/A 無法使用 - + Serial 序號 - + Driver Camera 駕駛員攝像頭 - + PREVIEW 預覽 - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 預覽駕駛員監控鏡頭畫面,以確保其具有良好視野。(僅在熄火時可用) - + Reset Calibration 重置校準 - + RESET 重置 - + Are you sure you want to reset calibration? 您確定要重置校準嗎? - + Review Training Guide 觀看使用教學 - + REVIEW 觀看 - + Review the rules, features, and limitations of openpilot 觀看 openpilot 的使用規則、功能和限制 - + Are you sure you want to review the training guide? 您確定要觀看使用教學嗎? - + Regulatory 法規/監管 - + VIEW 觀看 - + Change Language 更改語言 - + CHANGE 更改 - + Select a language 選擇語言 - + Reboot 重新啟動 - + Power Off 關機 - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot 需要將裝置固定在左右偏差 4° 以內,朝上偏差 5° 以内或朝下偏差 8° 以内。鏡頭在後台會持續自動校準,很少有需要重置的情况。 - + Your device is pointed %1° %2 and %3° %4. 你的設備目前朝%2 %1° 以及朝%4 %3° 。 - + down - + up - + left - + right - + Are you sure you want to reboot? 您確定要重新啟動嗎? - + Disengage to Reboot 請先取消控車才能重新啟動 - + Are you sure you want to power off? 您確定您要關機嗎? - + Disengage to Power Off 請先取消控車才能關機 @@ -261,32 +261,32 @@ DriveStats - + Drives 旅程 - + Hours 小時 - + ALL TIME 總共 - + PAST WEEK 上周 - + KM 公里 - + Miles 英里 @@ -294,7 +294,7 @@ DriverViewScene - + camera starting 開啟相機中 @@ -302,12 +302,12 @@ InputDialog - + Cancel 取消 - + Need at least %n character(s)! 需要至少 %n 個字元! @@ -317,22 +317,22 @@ Installer - + Installing... 安裝中… - + Receiving objects: 接收對象: - + Resolving deltas: 分析差異: - + Updating files: 更新檔案: @@ -340,27 +340,27 @@ MapETA - + eta 抵達 - + min 分鐘 - + hr 小時 - + km km - + mi mi @@ -368,22 +368,22 @@ MapInstructions - + km km - + m m - + mi mi - + ft ft @@ -391,48 +391,48 @@ MapPanel - + Current Destination 當前目的地 - + CLEAR 清除 - + Recent Destinations 最近目的地 - + Try the Navigation Beta 試用導航功能 - + Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai 成為 comma 高級會員來使用導航功能 立即註冊:https://connect.comma.ai - + No home location set 未設定 住家位置 - + No work location set 未設定 工作位置 - + no recent destinations 沒有最近的導航記錄 @@ -440,12 +440,12 @@ location set MapWindow - + Map Loading 地圖加載中 - + Waiting for GPS 等待 GPS @@ -453,12 +453,12 @@ location set MultiOptionDialog - + Select 選擇 - + Cancel 取消 @@ -466,23 +466,23 @@ location set Networking - + Advanced 進階 - + Enter password 輸入密碼 - - + + for "%1" 給 "%1" - + Wrong password 密碼錯誤 @@ -490,30 +490,30 @@ location set NvgWindow - + km/h km/h - + mph mph - - + + MAX 最高 - - + + SPEED 速度 - - + + LIMIT 速限 @@ -521,17 +521,17 @@ location set OffroadHome - + UPDATE 更新 - + ALERTS 提醒 - + ALERT 提醒 @@ -539,22 +539,22 @@ location set PairingPopup - + Pair your device to your comma account 將設備與您的 comma 帳號配對 - + Go to https://connect.comma.ai on your phone 用手機連至 https://connect.comma.ai - + Click "add new device" and scan the QR code on the right 點選 "add new device" 後掃描右邊的二維碼 - + Bookmark connect.comma.ai to your home screen to use it like an app 將 connect.comma.ai 加入您的主屏幕,以便像手機 App 一樣使用它 @@ -562,32 +562,32 @@ location set PrimeAdWidget - + Upgrade Now 馬上升級 - + Become a comma prime member at connect.comma.ai 成為 connect.comma.ai 的高級會員 - + PRIME FEATURES: 高級會員特點: - + Remote access 遠程訪問 - + 1 year of storage 一年的雲端行車記錄 - + Developer perks 開發者福利 @@ -595,22 +595,22 @@ location set PrimeUserWidget - + ✓ SUBSCRIBED ✓ 已訂閱 - + comma prime comma 高級會員 - + CONNECT.COMMA.AI CONNECT.COMMA.AI - + COMMA POINTS COMMA 積分 @@ -618,41 +618,41 @@ location set QObject - + Reboot 重新啟動 - + Exit 離開 - + dashcam 行車記錄器 - + openpilot openpilot - + %n minute(s) ago %n 分鐘前 - + %n hour(s) ago %n 小時前 - + %n day(s) ago %n 天前 @@ -662,47 +662,47 @@ location set Reset - + Reset failed. Reboot to try again. 重置失敗。請重新啟動後再試。 - + Are you sure you want to reset your device? 您確定要重置你的設備嗎? - + Resetting device... 重置設備中… - + System Reset 系統重置 - + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. 系統重置已觸發。請按確認刪除所有內容和設置。按取消恢復啟動。 - + Cancel 取消 - + Reboot 重新啟動 - + Confirm 確認 - + Unable to mount data partition. Press confirm to reset your device. 無法掛載數據分區。請按確認重置您的設備。 @@ -710,7 +710,7 @@ location set RichTextDialog - + Ok 確定 @@ -718,33 +718,33 @@ location set SettingsWindow - + × × - + Device 設備 - - + + Network 網路 - + Toggles 設定 - + Software 軟體 - + Navigation 導航 @@ -752,105 +752,105 @@ location set Setup - + WARNING: Low Voltage 警告:電壓過低 - + Power your device in a car with a harness or proceed at your own risk. 請使用車上 harness 提供的電源,若繼續的話您需要自擔風險。 - + Power off 關機 - - - + + + Continue 繼續 - + Getting Started 入門 - + Before we get on the road, let’s finish installation and cover some details. 在我們上路之前,讓我們完成安裝並介紹一些細節。 - + Connect to Wi-Fi 連接到無線網絡 - - + + Back 回上頁 - + Continue without Wi-Fi 在沒有 Wi-Fi 的情況下繼續 - + Waiting for internet 連接至網路中 - + Choose Software to Install 選擇要安裝的軟體 - + Dashcam 行車記錄器 - + Custom Software 定制的軟體 - + Enter URL 輸入網址 - + for Custom Software 定制的軟體 - + Downloading... 下載中… - + Download Failed 下載失敗 - + Ensure the entered URL is valid, and the device’s internet connection is good. 請確定您輸入的是有效的安裝網址,並且確定設備的網路連線狀態良好。 - + Reboot device 重新啟動 - + Start over 重新開始 @@ -858,17 +858,17 @@ location set SetupWidget - + Finish Setup 完成設置 - + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. 將您的設備與 comma connect (connect.comma.ai) 配對並領取您的 comma 高級會員優惠。 - + Pair device 配對設備 @@ -876,106 +876,106 @@ location set Sidebar - - + + CONNECT 雲端服務 - + OFFLINE 已離線 - - + + ONLINE 已連線 - + ERROR 錯誤 - - - + + + TEMP 溫度 - + HIGH 偏高 - + GOOD 正常 - + OK 一般 - + VEHICLE 車輛通訊 - + NO 未連線 - + PANDA 車輛通訊 - + GPS GPS - + SEARCH 車輛通訊 - + -- -- - + Wi-Fi - + ETH - + 2G - + 3G - + LTE - + 5G @@ -983,89 +983,89 @@ location set SoftwarePanel - + Git Branch Git 分支 - + Git Commit Git 提交 - + OS Version 系統版本 - + Version 版本 - + Last Update Check 上次檢查時間 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. 上次成功檢查更新的時間。更新系統只會在車子熄火時執行。 - + Check for Update 檢查更新 - + CHECKING 檢查中 - + Switch Branch 切換分支 - + ENTER 切換 - - + + The new branch will be pulled the next time the updater runs. 新的分支將會在下次檢查更新時切換過去。 - + Enter branch name 輸入分支名稱 - + UNINSTALL 卸載 - + Uninstall %1 卸載 %1 - + Are you sure you want to uninstall? 您確定您要卸載嗎? - + failed to fetch update 下載更新失敗 - - + + CHECK 檢查 @@ -1073,48 +1073,48 @@ location set SshControl - + SSH Keys SSH 密鑰 - + Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. 警告:這將授權給 GitHub 帳號中所有公鑰 SSH 訪問權限。切勿輸入非您自己的 GitHub 用戶名。comma 員工「永遠不會」要求您添加他們的 GitHub 用戶名。 - - + + ADD 新增 - + Enter your GitHub username 請輸入您 GitHub 的用戶名 - + LOADING 載入中 - + REMOVE 移除 - + Username '%1' has no keys on GitHub GitHub 用戶 '%1' 沒有設定任何密鑰 - + Request timed out 請求超時 - + Username '%1' doesn't exist on GitHub GitHub 用戶 '%1' 不存在 @@ -1122,7 +1122,7 @@ location set SshToggle - + Enable SSH 啟用 SSH 服務 @@ -1130,22 +1130,22 @@ location set TermsPage - + Terms & Conditions 條款和條件 - + Decline 拒絕 - + Scroll to accept 滑動至頁尾接受條款 - + Agree 接受 @@ -1153,92 +1153,92 @@ location set TogglesPanel - + Enable openpilot 啟用 openpilot - + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. 使用 openpilot 的主動式巡航和車道保持功能,開啟後您需要持續集中注意力,設定變更在重新啟動車輛後生效。 - + Enable Lane Departure Warnings 啟用車道偏離警告 - + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). 車速在時速 50 公里 (31 英里) 以上且未打方向燈的情況下,如果偵測到車輛駛出目前車道線時,發出車道偏離警告。 - + Use Metric System 使用公制單位 - + Display speed in km/h instead of mph. 啟用後,速度單位顯示將從 mp/h 改為 km/h。 - + Record and Upload Driver Camera 記錄並上傳駕駛監控影像 - + Upload data from the driver facing camera and help improve the driver monitoring algorithm. 上傳駕駛監控的錄像來協助我們提升駕駛監控的準確率。 - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal 油門取消控車 - + When enabled, pressing the accelerator pedal will disengage openpilot. 啟用後,踩踏油門將會取消 openpilot 控制。 - + Show ETA in 24h Format 預計到達時間單位改用 24 小時制 - + Use 24h format instead of am/pm 使用 24 小時制。(預設值為 12 小時制) - + Show Map on Left Side of UI 將地圖顯示在畫面的左側 - + Show map on left side when in split screen view. 進入分割畫面後,地圖將會顯示在畫面的左側。 - + openpilot Longitudinal Control openpilot 縱向控制 - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot 將會關閉雷達訊號並接管油門和剎車的控制。注意:這也會關閉自動緊急煞車 (AEB) 系統! @@ -1246,42 +1246,42 @@ location set Updater - + Update Required 系統更新 - + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. 設備的操作系統需要更新。請將您的設備連接到 Wi-Fi 以獲得最快的更新體驗。下載大小約為 1GB。 - + Connect to Wi-Fi 連接到無線網絡 - + Install 安裝 - + Back 回上頁 - + Loading... 載入中… - + Reboot 重新啟動 - + Update failed 更新失敗 @@ -1289,23 +1289,23 @@ location set WifiUI - - + + Scanning for networks... 掃描無線網路中... - + CONNECTING... 連線中... - + FORGET 清除 - + Forget Wi-Fi Network "%1"? 清除 Wi-Fi 網路 "%1"? diff --git a/selfdrive/ui/update_translations.py b/selfdrive/ui/update_translations.py index e509168ad6..afd42c3b3a 100755 --- a/selfdrive/ui/update_translations.py +++ b/selfdrive/ui/update_translations.py @@ -19,7 +19,7 @@ def update_translations(vanish=False, plural_only=None, translations_dir=TRANSLA for file in translation_files.values(): tr_file = os.path.join(translations_dir, f"{file}.ts") - args = f"lupdate -recursive {UI_DIR} -ts {tr_file}" + args = f"lupdate -locations relative -recursive {UI_DIR} -ts {tr_file}" if vanish: args += " -no-obsolete" if file in plural_only: From 50d117ed9a0c75a7374e76ec6e42d1a603bb11b0 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 6 Sep 2022 19:30:34 -0700 Subject: [PATCH 038/152] =?UTF-8?q?Toyota:=20remove=20100=C2=B0/sec=20stee?= =?UTF-8?q?ring=20lockout=20(#24067)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * try a method to kill those faults * cut torque for 1 frame * sign doesn't seem to matter * clean up * better name * Toyota allows you to keep your apply_steer, better control * the logic was wrong entire time? * cut steer for two frames * Revert "cut steer for two frames" This reverts commit 13a68ecc568fe1c0cd1f6f0b5f7ff6560efaf9e0. * better variable names and comments better variable names and comments * should be good * add safety * actual number of frames * constant * bump panda * bump panda * bump panda * bump panda * bump panda * bump panda * bump panda * fix to use min valid frames * rm line * simplify check * bump panda * bump panda to master --- panda | 2 +- selfdrive/car/toyota/carcontroller.py | 17 +++++++++++++++-- 2 files changed, 16 insertions(+), 3 deletions(-) diff --git a/panda b/panda index 13d64d4cc3..0ca23b6778 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 13d64d4cc38295401ff1ffcf6a233a4b9625fd9f +Subproject commit 0ca23b67786d0fa2a3162371aadeca52d24a8958 diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 3288bcaedf..511017a551 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -10,6 +10,10 @@ from opendbc.can.packer import CANPacker VisualAlert = car.CarControl.HUDControl.VisualAlert +# constants for fault workaround +MAX_STEER_RATE = 100 # deg/s +MAX_STEER_RATE_FRAMES = 18 # control frames allowed where steering rate >= MAX_STEER_RATE + class CarController: def __init__(self, dbc_name, CP, VM): @@ -20,6 +24,7 @@ class CarController: self.alert_active = False self.last_standstill = False self.standstill_req = False + self.steer_rate_counter = 0 self.packer = CANPacker(dbc_name) self.gas = 0 @@ -52,11 +57,19 @@ class CarController: new_steer = int(round(actuators.steer * CarControllerParams.STEER_MAX)) apply_steer = apply_toyota_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.torque_rate_limits) + # Count up to MAX_STEER_RATE_FRAMES, at which point we need to cut torque to avoid a steering fault + if CC.latActive and abs(CS.out.steeringRateDeg) >= MAX_STEER_RATE: + self.steer_rate_counter += 1 + else: + self.steer_rate_counter = 0 + + apply_steer_req = 1 if not CC.latActive: apply_steer = 0 apply_steer_req = 0 - else: - apply_steer_req = 1 + elif self.steer_rate_counter > MAX_STEER_RATE_FRAMES: + apply_steer_req = 0 + self.steer_rate_counter = 0 # TODO: probably can delete this. CS.pcm_acc_status uses a different signal # than CS.cruiseState.enabled. confirm they're not meaningfully different From 210a6163ac9a8ccc425114fd722e864befa77966 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Tue, 6 Sep 2022 21:30:10 -0700 Subject: [PATCH 039/152] Let planner decide stopping state (#25643) * Let planner decide stopping * Refactor stop/start state machine * Stay stoppe condition * 1sec from target * Add starting state * Add starting state logic * Undo some changes * Update ref --- cereal | 2 +- selfdrive/car/toyota/tunes.py | 2 +- selfdrive/controls/lib/longcontrol.py | 91 ++++++++++++++---------- selfdrive/test/process_replay/ref_commit | 2 +- 4 files changed, 56 insertions(+), 41 deletions(-) diff --git a/cereal b/cereal index 6323950101..3248f6658f 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 632395010102aabdd0ed87aba50d25042cdcb70e +Subproject commit 3248f6658f58551ce0de9e3ea712d67896e196fd diff --git a/selfdrive/car/toyota/tunes.py b/selfdrive/car/toyota/tunes.py index a8b8758d89..fc538b9698 100644 --- a/selfdrive/car/toyota/tunes.py +++ b/selfdrive/car/toyota/tunes.py @@ -38,7 +38,7 @@ def set_long_tune(tune, name): # Default longitudinal tune elif name == LongTunes.TSS: tune.deadzoneBP = [0., 9.] - tune.deadzoneV = [0., .15] + tune.deadzoneV = [.0, .15] tune.kpBP = [0., 5., 35.] tune.kiBP = [0., 35.] tune.kpV = [3.6, 2.4, 1.5] diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index e9458607d5..082e7725d7 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -11,16 +11,21 @@ LongCtrlState = car.CarControl.Actuators.LongControlState ACCEL_MIN_ISO = -3.5 # m/s^2 ACCEL_MAX_ISO = 2.0 # m/s^2 - def long_control_state_trans(CP, active, long_control_state, v_ego, v_target, - v_target_future, brake_pressed, cruise_standstill): - """Update longitudinal control state machine""" - accelerating = v_target_future > v_target - stopping_condition = (v_ego < 2.0 and cruise_standstill) or \ - (v_ego < CP.vEgoStopping and - ((v_target_future < CP.vEgoStopping and not accelerating) or brake_pressed)) - - starting_condition = v_target_future > CP.vEgoStarting and accelerating and not cruise_standstill + v_target_1sec, brake_pressed, cruise_standstill): + accelerating = v_target_1sec > v_target + planned_stop = (v_target < CP.vEgoStopping and + v_target_1sec < CP.vEgoStopping and + not accelerating) + stay_stopped = (v_ego < CP.vEgoStopping and + (brake_pressed or cruise_standstill)) + stopping_condition = planned_stop or stay_stopped + + starting_condition = (v_target_1sec > CP.vEgoStarting and + accelerating and + not cruise_standstill and + not brake_pressed) + started_condition = v_ego > CP.vEgoStarting if not active: long_control_state = LongCtrlState.off @@ -34,9 +39,21 @@ def long_control_state_trans(CP, active, long_control_state, v_ego, v_target, long_control_state = LongCtrlState.stopping elif long_control_state == LongCtrlState.stopping: - if starting_condition: + if starting_condition and CP.startingState: + long_control_state = LongCtrlState.starting + elif starting_condition: + long_control_state = LongCtrlState.pid + + elif long_control_state == LongCtrlState.starting: + if stopping_condition: + long_control_state = LongCtrlState.stopping + elif started_condition: long_control_state = LongCtrlState.pid + + + + return long_control_state @@ -60,64 +77,62 @@ class LongControl: # Interp control trajectory speeds = long_plan.speeds if len(speeds) == CONTROL_N: - v_target = interp(t_since_plan, T_IDXS[:CONTROL_N], speeds) - a_target = interp(t_since_plan, T_IDXS[:CONTROL_N], long_plan.accels) + v_target_now = interp(t_since_plan, T_IDXS[:CONTROL_N], speeds) + a_target_now = interp(t_since_plan, T_IDXS[:CONTROL_N], long_plan.accels) v_target_lower = interp(self.CP.longitudinalActuatorDelayLowerBound + t_since_plan, T_IDXS[:CONTROL_N], speeds) - a_target_lower = 2 * (v_target_lower - v_target) / self.CP.longitudinalActuatorDelayLowerBound - a_target + a_target_lower = 2 * (v_target_lower - v_target_now) / self.CP.longitudinalActuatorDelayLowerBound - a_target_now v_target_upper = interp(self.CP.longitudinalActuatorDelayUpperBound + t_since_plan, T_IDXS[:CONTROL_N], speeds) - a_target_upper = 2 * (v_target_upper - v_target) / self.CP.longitudinalActuatorDelayUpperBound - a_target + a_target_upper = 2 * (v_target_upper - v_target_now) / self.CP.longitudinalActuatorDelayUpperBound - a_target_now + + v_target = min(v_target_lower, v_target_upper) a_target = min(a_target_lower, a_target_upper) - v_target_future = speeds[-1] + v_target_1sec = interp(self.CP.longitudinalActuatorDelayUpperBound + t_since_plan + 1.0, T_IDXS[:CONTROL_N], speeds) else: v_target = 0.0 - v_target_future = 0.0 + v_target_1sec = 0.0 a_target = 0.0 - # TODO: This check is not complete and needs to be enforced by MPC - a_target = clip(a_target, ACCEL_MIN_ISO, ACCEL_MAX_ISO) - self.pid.neg_limit = accel_limits[0] self.pid.pos_limit = accel_limits[1] - # Update state machine output_accel = self.last_output_accel self.long_control_state = long_control_state_trans(self.CP, active, self.long_control_state, CS.vEgo, - v_target, v_target_future, CS.brakePressed, + v_target, v_target_1sec, CS.brakePressed, CS.cruiseState.standstill) if self.long_control_state == LongCtrlState.off: self.reset(CS.vEgo) output_accel = 0. - # tracking objects and driving + elif self.long_control_state == LongCtrlState.stopping: + if output_accel > self.CP.stopAccel: + output_accel -= self.CP.stoppingDecelRate * DT_CTRL + self.reset(CS.vEgo) + + elif self.long_control_state == LongCtrlState.starting: + output_accel = self.CP.startAccel + self.reset(CS.vEgo) + elif self.long_control_state == LongCtrlState.pid: - self.v_pid = v_target + self.v_pid = v_target_now # Toyota starts braking more when it thinks you want to stop # Freeze the integrator so we don't accelerate to compensate, and don't allow positive acceleration - prevent_overshoot = not self.CP.stoppingControl and CS.vEgo < 1.5 and v_target_future < 0.7 and v_target_future < self.v_pid + # TODO too complex, needs to be simplified and tested on toyotas + prevent_overshoot = not self.CP.stoppingControl and CS.vEgo < 1.5 and v_target_1sec < 0.7 and v_target_1sec < self.v_pid deadzone = interp(CS.vEgo, self.CP.longitudinalTuning.deadzoneBP, self.CP.longitudinalTuning.deadzoneV) freeze_integrator = prevent_overshoot error = self.v_pid - CS.vEgo error_deadzone = apply_deadzone(error, deadzone) - output_accel = self.pid.update(error_deadzone, speed=CS.vEgo, feedforward=a_target, freeze_integrator=freeze_integrator) - - if prevent_overshoot: - output_accel = min(output_accel, 0.0) + output_accel = self.pid.update(error_deadzone, speed=CS.vEgo, + feedforward=a_target, + freeze_integrator=freeze_integrator) - # Intention is to stop, switch to a different brake control until we stop - elif self.long_control_state == LongCtrlState.stopping: - # Keep applying brakes until the car is stopped - if not CS.standstill or output_accel > self.CP.stopAccel: - output_accel -= self.CP.stoppingDecelRate * DT_CTRL - output_accel = clip(output_accel, accel_limits[0], accel_limits[1]) - self.reset(CS.vEgo) - self.last_output_accel = output_accel - final_accel = clip(output_accel, accel_limits[0], accel_limits[1]) + self.last_output_accel = clip(output_accel, accel_limits[0], accel_limits[1]) - return final_accel + return self.last_output_accel diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 20bb4c82f3..0e2a5d84e3 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -915309019fef256512ee30cf92cfae2e479dd04e \ No newline at end of file +209423f468194c77443110078639ff67a8b99073 From 7899fb79c1b3c56034dea3ceb70955f94fdb5ff4 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Tue, 6 Sep 2022 21:52:34 -0700 Subject: [PATCH 040/152] More conservative lead policy in e2e long mode (#25684) * Add params for lead and danger * fix long params * E2e passes simple maneuver tests * Make tests run with e2e long mode * Slightly more error allowed in e2e mode * FCW back and populate long source field * Fix planner name * FCW still doesnt work * Slightly less aggressive * Doesn't need to simulate from stop --- .../lib/longitudinal_mpc_lib/long_mpc.py | 40 ++++++++++++++----- .../controls/lib/longitudinal_planner.py | 2 +- selfdrive/controls/plannerd.py | 4 +- selfdrive/controls/tests/test_cruise_speed.py | 20 ++++++---- .../controls/tests/test_following_distance.py | 23 ++++++----- .../test/longitudinal_maneuvers/maneuver.py | 4 +- .../test/longitudinal_maneuvers/plant.py | 21 +++++++++- .../test_longitudinal.py | 11 ++++- 8 files changed, 91 insertions(+), 34 deletions(-) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index 405ef81916..ea9b0683a4 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -24,7 +24,7 @@ SOURCES = ['lead0', 'lead1', 'cruise', 'e2e'] X_DIM = 3 U_DIM = 1 -PARAM_DIM = 4 +PARAM_DIM = 6 COST_E_DIM = 5 COST_DIM = COST_E_DIM + 1 CONSTR_DIM = 4 @@ -37,6 +37,7 @@ J_EGO_COST = 5.0 A_CHANGE_COST = 200. DANGER_ZONE_COST = 100. CRASH_DISTANCE = .5 +LEAD_DANGER_FACTOR = 0.75 LIMIT_COST = 1e6 ACADOS_SOLVER_TYPE = 'SQP_RTI' @@ -58,8 +59,8 @@ STOP_DISTANCE = 6.0 def get_stopped_equivalence_factor(v_lead): return (v_lead**2) / (2 * COMFORT_BRAKE) -def get_safe_obstacle_distance(v_ego): - return (v_ego**2) / (2 * COMFORT_BRAKE) + T_FOLLOW * v_ego + STOP_DISTANCE +def get_safe_obstacle_distance(v_ego, t_follow=T_FOLLOW): + return (v_ego**2) / (2 * COMFORT_BRAKE) + t_follow * v_ego + STOP_DISTANCE def desired_follow_distance(v_ego, v_lead): return get_safe_obstacle_distance(v_ego) - get_stopped_equivalence_factor(v_lead) @@ -90,7 +91,9 @@ def gen_long_model(): a_max = SX.sym('a_max') x_obstacle = SX.sym('x_obstacle') prev_a = SX.sym('prev_a') - model.p = vertcat(a_min, a_max, x_obstacle, prev_a) + lead_t_follow = SX.sym('lead_t_follow') + lead_danger_factor = SX.sym('lead_danger_factor') + model.p = vertcat(a_min, a_max, x_obstacle, prev_a, lead_t_follow, lead_danger_factor) # dynamics model f_expl = vertcat(v_ego, a_ego, j_ego) @@ -124,11 +127,13 @@ def gen_long_ocp(): a_min, a_max = ocp.model.p[0], ocp.model.p[1] x_obstacle = ocp.model.p[2] prev_a = ocp.model.p[3] + lead_t_follow = ocp.model.p[4] + lead_danger_factor = ocp.model.p[5] ocp.cost.yref = np.zeros((COST_DIM, )) ocp.cost.yref_e = np.zeros((COST_E_DIM, )) - desired_dist_comfort = get_safe_obstacle_distance(v_ego) + desired_dist_comfort = get_safe_obstacle_distance(v_ego, lead_t_follow) # The main cost in normal operation is how close you are to the "desired" distance # from an obstacle at every timestep. This obstacle can be a lead car @@ -149,12 +154,12 @@ def gen_long_ocp(): constraints = vertcat(v_ego, (a_ego - a_min), (a_max - a_ego), - ((x_obstacle - x_ego) - (3/4) * (desired_dist_comfort)) / (v_ego + 10.)) + ((x_obstacle - x_ego) - lead_danger_factor * (desired_dist_comfort)) / (v_ego + 10.)) ocp.model.con_h_expr = constraints x0 = np.zeros(X_DIM) ocp.constraints.x0 = x0 - ocp.parameter_values = np.array([-1.2, 1.2, 0.0, 0.0]) + ocp.parameter_values = np.array([-1.2, 1.2, 0.0, 0.0, T_FOLLOW, LEAD_DANGER_FACTOR]) # We put all constraint cost weights to 0 and only set them at runtime cost_weights = np.zeros(CONSTR_DIM) @@ -249,7 +254,7 @@ class LongitudinalMpc: constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, DANGER_ZONE_COST] elif self.mode == 'blended': cost_weights = [0., 0.2, 0.25, 1.0, 0.0, 1.0] - constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 5.0] + constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 50.0] elif self.mode == 'e2e': cost_weights = [0., 0.2, 0.25, 1., 0.0, .1] constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 0.0] @@ -317,6 +322,7 @@ class LongitudinalMpc: if self.mode == 'acc': self.params[:,0] = MIN_ACCEL if self.status else self.cruise_min_a self.params[:,1] = self.cruise_max_a + self.params[:,5] = LEAD_DANGER_FACTOR # Fake an obstacle for cruise, this ensures smooth acceleration to set speed # when the leads are no factor. @@ -335,6 +341,7 @@ class LongitudinalMpc: elif self.mode == 'blended': self.params[:,0] = MIN_ACCEL self.params[:,1] = MAX_ACCEL + self.params[:,5] = 1.0 x_obstacles = np.column_stack([lead_0_obstacle, lead_1_obstacle]) @@ -344,7 +351,8 @@ class LongitudinalMpc: x_and_cruise = np.column_stack([x, cruise_target]) x = np.min(x_and_cruise, axis=1) - self.source = 'e2e' + + self.source = 'e2e' if x_and_cruise[0,0] < x_and_cruise[0,1] else 'cruise' else: raise NotImplementedError(f'Planner mode {self.mode} not recognized in planner update') @@ -359,6 +367,7 @@ class LongitudinalMpc: self.params[:,2] = np.min(x_obstacles, axis=1) self.params[:,3] = np.copy(self.prev_a) + self.params[:,4] = T_FOLLOW self.run() if (np.any(lead_xv_0[:,0] - self.x_sol[:,0] < CRASH_DISTANCE) and @@ -367,10 +376,23 @@ class LongitudinalMpc: else: self.crash_cnt = 0 + # Check if it got within lead comfort range + # TODO This should be done cleaner + 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): + 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 \ + (lead_1_obstacle[0] - lead_0_obstacle[0]): + self.source = 'lead1' + + + def update_with_xva(self, x, v, a): self.params[:,0] = -10. self.params[:,1] = 10. self.params[:,2] = 1e5 + self.params[:,4] = T_FOLLOW + self.params[:,5] = LEAD_DANGER_FACTOR # v, and a are in local frame, but x is wrt the x[0] position # In >90degree turns, x goes to 0 (and may even be -ve) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index b6120d2451..b9bf5dcbf7 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -45,7 +45,7 @@ def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): return [a_target[0], min(a_target[1], a_x_allowed)] -class Planner: +class LongitudinalPlanner: def __init__(self, CP, init_v=0.0, init_a=0.0): self.CP = CP params = Params() diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py index 513131a33b..93d0c80dac 100755 --- a/selfdrive/controls/plannerd.py +++ b/selfdrive/controls/plannerd.py @@ -3,7 +3,7 @@ from cereal import car from common.params import Params from common.realtime import Priority, config_realtime_process from system.swaglog import cloudlog -from selfdrive.controls.lib.longitudinal_planner import Planner +from selfdrive.controls.lib.longitudinal_planner import LongitudinalPlanner from selfdrive.controls.lib.lateral_planner import LateralPlanner import cereal.messaging as messaging @@ -16,7 +16,7 @@ def plannerd_thread(sm=None, pm=None): CP = car.CarParams.from_bytes(params.get("CarParams", block=True)) cloudlog.info("plannerd got CarParams: %s", CP.carName) - longitudinal_planner = Planner(CP) + longitudinal_planner = LongitudinalPlanner(CP) lateral_planner = LateralPlanner(CP) if sm is None: diff --git a/selfdrive/controls/tests/test_cruise_speed.py b/selfdrive/controls/tests/test_cruise_speed.py index 364be8db79..a972bfb073 100644 --- a/selfdrive/controls/tests/test_cruise_speed.py +++ b/selfdrive/controls/tests/test_cruise_speed.py @@ -1,13 +1,16 @@ #!/usr/bin/env python3 import unittest import numpy as np +from common.params import Params + + from selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver -def run_cruise_simulation(cruise, t_end=100.): +def run_cruise_simulation(cruise, t_end=20.): man = Maneuver( '', duration=t_end, - initial_speed=float(0.), + initial_speed=max(cruise - 1., 0.0), lead_relevancy=True, initial_distance_lead=100, cruise_values=[cruise], @@ -21,12 +24,15 @@ def run_cruise_simulation(cruise, t_end=100.): class TestCruiseSpeed(unittest.TestCase): def test_cruise_speed(self): - for speed in np.arange(5, 40, 5): - print(f'Testing {speed} m/s') - cruise_speed = float(speed) + params = Params() + for e2e in [False, True]: + params.put_bool("EndToEndLong", e2e) + for speed in np.arange(5, 40, 5): + print(f'Testing {speed} m/s') + cruise_speed = float(speed) - simulation_steady_state = run_cruise_simulation(cruise_speed) - self.assertAlmostEqual(simulation_steady_state, cruise_speed, delta=.01, msg=f'Did not reach {speed} m/s') + simulation_steady_state = run_cruise_simulation(cruise_speed) + self.assertAlmostEqual(simulation_steady_state, cruise_speed, delta=.01, msg=f'Did not reach {speed} m/s') if __name__ == "__main__": diff --git a/selfdrive/controls/tests/test_following_distance.py b/selfdrive/controls/tests/test_following_distance.py index ebe4776739..3534f58235 100644 --- a/selfdrive/controls/tests/test_following_distance.py +++ b/selfdrive/controls/tests/test_following_distance.py @@ -1,11 +1,13 @@ #!/usr/bin/env python3 import unittest import numpy as np +from common.params import Params + from selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import desired_follow_distance from selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver -def run_following_distance_simulation(v_lead, t_end=100.0): +def run_following_distance_simulation(v_lead, t_end=100.0, e2e=False): man = Maneuver( '', duration=t_end, @@ -14,6 +16,7 @@ def run_following_distance_simulation(v_lead, t_end=100.0): initial_distance_lead=100, speed_lead_values=[v_lead], breakpoints=[0.], + e2e=e2e ) valid, output = man.evaluate() assert valid @@ -22,14 +25,16 @@ def run_following_distance_simulation(v_lead, t_end=100.0): class TestFollowingDistance(unittest.TestCase): def test_following_distance(self): - for speed in np.arange(0, 40, 5): - print(f'Testing {speed} m/s') - v_lead = float(speed) - - simulation_steady_state = run_following_distance_simulation(v_lead) - correct_steady_state = desired_follow_distance(v_lead, v_lead) - - self.assertAlmostEqual(simulation_steady_state, correct_steady_state, delta=(correct_steady_state*.1 + .5)) + params = Params() + for e2e in [False, True]: + params.put_bool("EndToEndLong", e2e) + for speed in np.arange(0, 40, 5): + print(f'Testing {speed} m/s') + v_lead = float(speed) + simulation_steady_state = run_following_distance_simulation(v_lead) + correct_steady_state = desired_follow_distance(v_lead, v_lead) + err_ratio = 0.2 if e2e else 0.1 + self.assertAlmostEqual(simulation_steady_state, correct_steady_state, delta=(err_ratio * correct_steady_state + .5)) if __name__ == "__main__": diff --git a/selfdrive/test/longitudinal_maneuvers/maneuver.py b/selfdrive/test/longitudinal_maneuvers/maneuver.py index 0d605a5fc7..dad5d89844 100644 --- a/selfdrive/test/longitudinal_maneuvers/maneuver.py +++ b/selfdrive/test/longitudinal_maneuvers/maneuver.py @@ -27,7 +27,7 @@ class Maneuver(): speed=self.speed, distance_lead=self.distance_lead, only_lead2=self.only_lead2, - only_radar=self.only_radar + only_radar=self.only_radar, ) valid = True @@ -54,7 +54,7 @@ class Maneuver(): valid = False if self.ensure_start and log['v_rel'] > 0 and log['speeds'][-1] <= 0.1: - print('Planner not starting!') + print('LongitudinalPlanner not starting!') valid = False print("maneuver end", valid) diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index b11f6bef35..21af1cd3b1 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -6,7 +6,8 @@ from cereal import log import cereal.messaging as messaging from common.realtime import Ratekeeper, DT_MDL from selfdrive.controls.lib.longcontrol import LongCtrlState -from selfdrive.controls.lib.longitudinal_planner import Planner +from selfdrive.modeld.constants import T_IDXS +from selfdrive.controls.lib.longitudinal_planner import LongitudinalPlanner class Plant(): @@ -43,7 +44,8 @@ class Plant(): from selfdrive.car.honda.values import CAR from selfdrive.car.honda.interface import CarInterface - self.planner = Planner(CarInterface.get_params(CAR.CIVIC), init_v=self.speed) + + self.planner = LongitudinalPlanner(CarInterface.get_params(CAR.CIVIC), init_v=self.speed) def current_time(self): return float(self.rk.frame) / self.rate @@ -88,6 +90,21 @@ class Plant(): radar.radarState.leadOne = lead radar.radarState.leadTwo = lead + # Simulate model predicting slightly faster speed + # this is to ensure lead policy is effective when model + # does not predict slowdown in e2e mode + position = log.ModelDataV2.XYZTData.new_message() + position.x = [float(x) for x in (self.speed + 0.5) * np.array(T_IDXS)] + model.modelV2.position = position + velocity = log.ModelDataV2.XYZTData.new_message() + velocity.x = [float(x) for x in (self.speed + 0.5) * np.ones_like(T_IDXS)] + model.modelV2.velocity = velocity + acceleration = log.ModelDataV2.XYZTData.new_message() + acceleration.x = [float(x) for x in np.zeros_like(T_IDXS)] + model.modelV2.acceleration = acceleration + + + control.controlsState.longControlState = LongCtrlState.pid control.controlsState.vCruise = float(v_cruise * 3.6) car_state.carState.vEgo = float(self.speed) diff --git a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py index ec698d88fa..c7c2915878 100755 --- a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py +++ b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py @@ -140,16 +140,23 @@ class LongitudinalControl(unittest.TestCase): def run_maneuver_worker(k): def run(self): + params = Params() + man = maneuvers[k] - print(man.title) + params.put_bool("EndToEndLong", True) + print(man.title, ' in e2e mode') + valid, _ = man.evaluate() + self.assertTrue(valid, msg=man.title) + params.put_bool("EndToEndLong", False) + print(man.title, ' in acc mode') valid, _ = man.evaluate() self.assertTrue(valid, msg=man.title) return run - for k in range(len(maneuvers)): setattr(LongitudinalControl, f"test_longitudinal_maneuvers_{k+1}", run_maneuver_worker(k)) + if __name__ == "__main__": unittest.main(failfast=True) From 285ce30996e75e80e419ff2ef2d43cdb96fcb530 Mon Sep 17 00:00:00 2001 From: Bruce Wayne Date: Tue, 6 Sep 2022 22:00:09 -0700 Subject: [PATCH 041/152] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 3248f6658f..f26ee5a28d 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 3248f6658f58551ce0de9e3ea712d67896e196fd +Subproject commit f26ee5a28d778bd1833e47036398fd6b6f5f44bd From c5dc10bd2f063e2233795a66e45b6f17dffbd5c1 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 7 Sep 2022 00:18:01 -0700 Subject: [PATCH 042/152] Toyota: fix permanent LKAS faults (#25620) * Fix permanent LKAS Toyota faults * comment and global variable * EPS * comments * move up * comment --- selfdrive/car/toyota/carcontroller.py | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 511017a551..b34a31a01c 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -10,9 +10,12 @@ from opendbc.can.packer import CANPacker VisualAlert = car.CarControl.HUDControl.VisualAlert -# constants for fault workaround +# EPS faults if you apply torque while the steering rate is above 100 deg/s for too long MAX_STEER_RATE = 100 # deg/s -MAX_STEER_RATE_FRAMES = 18 # control frames allowed where steering rate >= MAX_STEER_RATE +MAX_STEER_RATE_FRAMES = 18 # tx control frames needed before torque can be cut + +# EPS allows user torque above threshold for 50 frames before permanently faulting +MAX_USER_TORQUE = 500 class CarController: @@ -34,6 +37,7 @@ class CarController: actuators = CC.actuators hud_control = CC.hudControl pcm_cancel_cmd = CC.cruiseControl.cancel + lat_active = CC.latActive and abs(CS.out.steeringTorque) < MAX_USER_TORQUE # gas and brake if self.CP.enableGasInterceptor and CC.longActive: @@ -58,13 +62,13 @@ class CarController: apply_steer = apply_toyota_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.torque_rate_limits) # Count up to MAX_STEER_RATE_FRAMES, at which point we need to cut torque to avoid a steering fault - if CC.latActive and abs(CS.out.steeringRateDeg) >= MAX_STEER_RATE: + if lat_active and abs(CS.out.steeringRateDeg) >= MAX_STEER_RATE: self.steer_rate_counter += 1 else: self.steer_rate_counter = 0 apply_steer_req = 1 - if not CC.latActive: + if not lat_active: apply_steer = 0 apply_steer_req = 0 elif self.steer_rate_counter > MAX_STEER_RATE_FRAMES: From c317bb464d1daa73e870fb55ae95377a580cf7af Mon Sep 17 00:00:00 2001 From: AlexandreSato <66435071+AlexandreSato@users.noreply.github.com> Date: Wed, 7 Sep 2022 04:26:37 -0300 Subject: [PATCH 043/152] Multilang: formal pt-BR translations (#25669) * fix and improve pt-BR translation * Shorter phrase for Finish Setup * Concluir are better than Encerrar bacause means sucessfuly * improve pt-BR, DEVbrazilians use english as default * fix "atualizador" text cutoff * miss mark as finish on qt linguist * Multilang: improve pt-BR translation * Update selfdrive/ui/translations/main_pt-BR.ts looks good! Co-authored-by: Shane Smiskol Co-authored-by: Shane Smiskol --- selfdrive/ui/translations/main_pt-BR.ts | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 622d8ee443..5a2167ea87 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -155,7 +155,7 @@ Review Training Guide - Revisar o Treinamento + Revisar Guia de Treinamento @@ -185,17 +185,17 @@ Change Language - Mudar Linguagem + Alterar Idioma CHANGE - MUDAR + ALTERAR Select a language - Selecione uma linguagem + Selecione o Idioma @@ -989,12 +989,12 @@ trabalho definido Git Branch - Ramo Git + Git Branch Git Commit - Commit Git + Último Commit @@ -1029,7 +1029,7 @@ trabalho definido Switch Branch - Trocar Branch + Alterar Branch From a8134f226589675b2d1619bc6ed8b0d9c6a37ba7 Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Wed, 7 Sep 2022 08:58:33 -0700 Subject: [PATCH 044/152] e2e long yellow path (#25679) * yellow brick road * live toggling * path color from acceleration * more yellow --- selfdrive/ui/qt/onroad.cc | 46 +++++++++++++++++++++++++++++---------- selfdrive/ui/ui.cc | 1 + selfdrive/ui/ui.h | 2 +- 3 files changed, 36 insertions(+), 13 deletions(-) diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 4414e602e6..3920453a47 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -459,19 +459,41 @@ void NvgWindow::drawLaneLines(QPainter &painter, const UIState *s) { // paint path QLinearGradient bg(0, height(), 0, height() / 4); - const auto &orientation = (*s->sm)["modelV2"].getModelV2().getOrientation(); - float orientation_future = 0; - if (orientation.getZ().size() > 16) { - orientation_future = std::abs(orientation.getZ()[16]); // 2.5 seconds + float start_hue, end_hue; + if (scene.end_to_end_long) { + const auto &acceleration = (*s->sm)["modelV2"].getModelV2().getAcceleration(); + float acceleration_future = 0; + if (acceleration.getZ().size() > 16) { + acceleration_future = acceleration.getX()[16]; // 2.5 seconds + } + start_hue = 60; + // speed up: 120, slow down: 0 + end_hue = fmax(fmin(start_hue + acceleration_future * 30, 120), 0); + + // FIXME: painter.drawPolygon can be slow if hue is not rounded + end_hue = int(end_hue * 100 + 0.5) / 100; + + bg.setColorAt(0.0, QColor::fromHslF(start_hue / 360., 0.97, 0.56, 0.4)); + bg.setColorAt(0.5, QColor::fromHslF(end_hue / 360., 1.0, 0.68, 0.35)); + bg.setColorAt(1.0, QColor::fromHslF(end_hue / 360., 1.0, 0.68, 0.0)); + } else { + const auto &orientation = (*s->sm)["modelV2"].getModelV2().getOrientation(); + float orientation_future = 0; + if (orientation.getZ().size() > 16) { + orientation_future = std::abs(orientation.getZ()[16]); // 2.5 seconds + } + start_hue = 148; + // straight: 112, in turns: 70 + end_hue = fmax(70, 112 - (orientation_future * 420)); + + // FIXME: painter.drawPolygon can be slow if hue is not rounded + end_hue = int(end_hue * 100 + 0.5) / 100; + + bg.setColorAt(0.0, QColor::fromHslF(start_hue / 360., 0.94, 0.51, 0.4)); + bg.setColorAt(0.5, QColor::fromHslF(end_hue / 360., 1.0, 0.68, 0.35)); + bg.setColorAt(1.0, QColor::fromHslF(end_hue / 360., 1.0, 0.68, 0.0)); } - // straight: 112, in turns: 70 - float curve_hue = fmax(70, 112 - (orientation_future * 420)); - // FIXME: painter.drawPolygon can be slow if hue is not rounded - curve_hue = int(curve_hue * 100 + 0.5) / 100; - - bg.setColorAt(0.0, QColor::fromHslF(148 / 360., 0.94, 0.51, 0.4)); - bg.setColorAt(0.75 / 1.5, QColor::fromHslF(curve_hue / 360., 1.0, 0.68, 0.35)); - bg.setColorAt(1.0, QColor::fromHslF(curve_hue / 360., 1.0, 0.68, 0.0)); + painter.setBrush(bg); painter.drawPolygon(scene.track_vertices); diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 317ef497a5..b208945fe2 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -195,6 +195,7 @@ void ui_update_params(UIState *s) { auto params = Params(); s->scene.is_metric = params.getBool("IsMetric"); s->scene.map_on_left = params.getBool("NavSettingLeftSide"); + s->scene.end_to_end_long = params.getBool("EndToEndLong"); } void UIState::updateStatus() { diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index 16f78cdef4..08ae16ab24 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -101,7 +101,7 @@ typedef struct UIScene { QPointF lead_vertices[2]; float light_sensor, accel_sensor, gyro_sensor; - bool started, ignition, is_metric, map_on_left, longitudinal_control; + bool started, ignition, is_metric, map_on_left, longitudinal_control, end_to_end_long; uint64_t started_frame; } UIScene; From 8857e02dd4e141680476644a07fa3c9cd2ae9364 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Wed, 7 Sep 2022 11:29:19 -0700 Subject: [PATCH 045/152] Live e2e long toggling (#25685) Live toggling --- selfdrive/controls/lib/longitudinal_planner.py | 17 ++++++++++++----- 1 file changed, 12 insertions(+), 5 deletions(-) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index b9bf5dcbf7..8162d10071 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -48,10 +48,11 @@ def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): class LongitudinalPlanner: def __init__(self, CP, init_v=0.0, init_a=0.0): self.CP = CP - params = Params() - # TODO read param in the loop for live toggling - mode = 'blended' if params.get_bool('EndToEndLong') else 'acc' - self.mpc = LongitudinalMpc(mode=mode) + self.params = Params() + self.param_read_counter = 0 + + self.mpc = LongitudinalMpc() + self.read_param() self.fcw = False @@ -64,6 +65,9 @@ class LongitudinalPlanner: self.j_desired_trajectory = np.zeros(CONTROL_N) self.solverExecutionTime = 0.0 + def read_param(self): + self.mpc.mode = 'blended' if self.params.get_bool('EndToEndLong') else 'acc' + def parse_model(self, model_msg): if (len(model_msg.position.x) == 33 and len(model_msg.velocity.x) == 33 and @@ -83,8 +87,11 @@ class LongitudinalPlanner: return x, v, a, j def update(self, sm): - v_ego = sm['carState'].vEgo + if self.param_read_counter % 50 == 0: + self.read_param() + self.param_read_counter += 1 + v_ego = sm['carState'].vEgo v_cruise_kph = sm['controlsState'].vCruise v_cruise_kph = min(v_cruise_kph, V_CRUISE_MAX) v_cruise = v_cruise_kph * CV.KPH_TO_MS From 9bb29240b04e979bc79d929fa526fd29bd4071a6 Mon Sep 17 00:00:00 2001 From: ioniq5-cz <111085918+ioniq5-cz@users.noreply.github.com> Date: Wed, 7 Sep 2022 22:25:48 +0200 Subject: [PATCH 046/152] Hyuyndai: add missing FW versions for 2022 Ioniq 5 (#25691) --- selfdrive/car/hyundai/values.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 79e3ea4190..4354f13440 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1290,6 +1290,8 @@ FW_VERSIONS = { (Ecu.esp, 0x7d1, None): [ b'\xf1\x00NE1 IEB \x07 106!\x11) 58520-GI010', b'\xf1\x8758520GI010\xf1\x00NE1 IEB \x07 106!\x11) 58520-GI010', + b'\xf1\x00NE1 IEB \x08 104!\x04\x05 58520-GI000', + b'\xf1\x8758520GI000\xf1\x00NE1 IEB \x08 104!\x04\x05 58520-GI000', ], (Ecu.eps, 0x7d4, None): [ b'\xf1\x00NE MDPS R 1.00 1.06 57700GI000 4NEDR106', @@ -1301,6 +1303,7 @@ FW_VERSIONS = { ], (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.02 99211-GI010 211206', + b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.06 99211-GI000 210813', ], }, CAR.TUCSON_HYBRID_4TH_GEN: { From e9c87daef6534906c728da9a191866926bbfbfe4 Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Wed, 7 Sep 2022 14:25:57 -0700 Subject: [PATCH 047/152] rename esp ECU to abs (#25640) * rename esp ecu to abs * bump cereal --- cereal | 2 +- selfdrive/car/chrysler/values.py | 6 +- selfdrive/car/ford/values.py | 4 +- selfdrive/car/fw_versions.py | 10 +-- selfdrive/car/hyundai/values.py | 38 +++++----- selfdrive/car/mazda/values.py | 12 ++-- selfdrive/car/nissan/values.py | 4 +- selfdrive/car/subaru/values.py | 20 +++--- selfdrive/car/toyota/values.py | 90 ++++++++++++------------ selfdrive/controls/tests/test_startup.py | 4 +- 10 files changed, 95 insertions(+), 95 deletions(-) diff --git a/cereal b/cereal index f26ee5a28d..cea51afd67 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit f26ee5a28d778bd1833e47036398fd6b6f5f44bd +Subproject commit cea51afd67b5c56f7a18207ef91c5e45d6345526 diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 0df2c18868..f495d06a10 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -132,7 +132,7 @@ FINGERPRINTS = { FW_VERSIONS = { CAR.PACIFICA_2019_HYBRID: { (Ecu.hcp, 0x7e2, None): [], - (Ecu.esp, 0x7e4, None): [], + (Ecu.abs, 0x7e4, None): [], }, CAR.RAM_1500: { @@ -149,7 +149,7 @@ FW_VERSIONS = { b'68428609AB', b'68500728AA', ], - (Ecu.esp, 0x747, None): [ + (Ecu.abs, 0x747, None): [ b'68432418AD', b'68432418AB', b'68436004AE', @@ -205,7 +205,7 @@ FW_VERSIONS = { b'68428503AA', b'68428505AA', ], - (Ecu.esp, 0x747, None): [ + (Ecu.abs, 0x747, None): [ b'68334977AH', b'68504022AB', b'68530686AB', diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index 825d515da9..2624fd2524 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -51,7 +51,7 @@ FW_VERSIONS = { (Ecu.eps, 0x730, None): [ b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'LX6C-2D053-NS\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ @@ -68,7 +68,7 @@ FW_VERSIONS = { (Ecu.eps, 0x730, None): [ b'JX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'JX61-2D053-CJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 363b852ebe..e6faa0e950 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -16,7 +16,7 @@ from selfdrive.car.toyota.values import CAR as TOYOTA from system.swaglog import cloudlog Ecu = car.CarParams.Ecu -ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.esp, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa] +ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa] def p16(val): @@ -213,14 +213,14 @@ REQUESTS: List[Request] = [ "chrysler", [CHRYSLER_VERSION_REQUEST], [CHRYSLER_VERSION_RESPONSE], - whitelist_ecus=[Ecu.esp, Ecu.eps, Ecu.srs, Ecu.gateway, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter], + whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.srs, Ecu.gateway, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter], rx_offset=CHRYSLER_RX_OFFSET, ), Request( "chrysler", [CHRYSLER_VERSION_REQUEST], [CHRYSLER_VERSION_RESPONSE], - whitelist_ecus=[Ecu.esp, Ecu.hcp, Ecu.engine, Ecu.transmission], + whitelist_ecus=[Ecu.abs, Ecu.hcp, Ecu.engine, Ecu.transmission], ), Request( "chrysler", @@ -240,7 +240,7 @@ REQUESTS: List[Request] = [ [TESTER_PRESENT_REQUEST, FORD_VERSION_REQUEST], [TESTER_PRESENT_RESPONSE, FORD_VERSION_RESPONSE], bus=0, - whitelist_ecus=[Ecu.eps, Ecu.esp, Ecu.fwdRadar, Ecu.fwdCamera], + whitelist_ecus=[Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera], ), ] @@ -328,7 +328,7 @@ def match_fw_to_car_exact(fw_versions_dict): ecu_type = ecu[0] addr = ecu[1:] found_versions = fw_versions_dict.get(addr, set()) - if ecu_type == Ecu.esp and candidate in (TOYOTA.RAV4, TOYOTA.COROLLA, TOYOTA.HIGHLANDER, TOYOTA.SIENNA, TOYOTA.LEXUS_IS) and not len(found_versions): + if ecu_type == Ecu.abs and candidate in (TOYOTA.RAV4, TOYOTA.COROLLA, TOYOTA.HIGHLANDER, TOYOTA.SIENNA, TOYOTA.LEXUS_IS) and not len(found_versions): continue # On some Toyota models, the engine can show on two different addresses diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 4354f13440..e2374a1c09 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -398,7 +398,7 @@ FW_VERSIONS = { b'\xf1\x8799110L0000\xf1\x00DN8_ SCC F-CUP 1.00 1.00 99110-L0000 ', b'\xf1\x8799110L0000\xf1\x00DN8_ SCC FHCUP 1.00 1.00 99110-L0000 ', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00DN ESC \x07 106 \x07\x01 58910-L0100', b'\xf1\x00DN ESC \x01 102\x19\x04\x13 58910-L1300', b'\xf1\x00DN ESC \x03 100 \x08\x01 58910-L0300', @@ -518,7 +518,7 @@ FW_VERSIONS = { (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00LF__ SCC F-CUP 1.00 1.00 96401-C2200 ', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00LF ESC \f 11 \x17\x01\x13 58920-C2610', b'\xf1\x00LF ESC \t 11 \x17\x01\x13 58920-C2610', ], @@ -565,7 +565,7 @@ FW_VERSIONS = { b'\xf1\x00TM__ SCC F-CUP 1.00 1.02 99110-S2000 ', b'\xf1\x00TM__ SCC F-CUP 1.00 1.03 99110-S2000 ', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00TM ESC \r 100\x18\x031 58910-S2650', b'\xf1\x00TM ESC \r 103\x18\x11\x08 58910-S2650', b'\xf1\x00TM ESC \r 104\x19\a\b 58910-S2650', @@ -623,7 +623,7 @@ FW_VERSIONS = { b'\xf1\x8799110S1500\xf1\x00TM__ SCC FHCUP 1.00 1.00 99110-S1500 ', b'\xf1\x00TM__ SCC FHCUP 1.00 1.00 99110-S1500 ', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00TM ESC \x02 101 \x08\x04 58910-S2GA0', b'\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', b'\xf1\x8758910-S2DA0\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', @@ -744,7 +744,7 @@ FW_VERSIONS = { b'\xf1\x00LX2_ SCC FHCUP 1.00 1.05 99110-S8100 ', b'\xf1\x00ON__ FCA FHCUP 1.00 1.02 99110-S9100 ', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00LX ESC \x01 103\x19\t\x10 58910-S8360', b'\xf1\x00LX ESC \x01 1031\t\x10 58910-S8360', b'\xf1\x00LX ESC \x0b 101\x19\x03\x17 58910-S8330', @@ -834,7 +834,7 @@ FW_VERSIONS = { b'\xf1\x00JS__ SCC H-CUP 1.00 1.02 95650-J3200 ', b'\xf1\x00JS__ SCC HNCUP 1.00 1.02 95650-J3100 ', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00\x00\x00\x00\x00\x00\x00', b'\xf1\x816V8RAC00121.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', ], @@ -895,7 +895,7 @@ FW_VERSIONS = { }, CAR.KONA: { (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00OS__ SCC F-CUP 1.00 1.00 95655-J9200 ', ], - (Ecu.esp, 0x7d1, None): [b'\xf1\x816V5RAK00018.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', ], + (Ecu.abs, 0x7d1, None): [b'\xf1\x816V5RAK00018.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [b'"\x01TOS-0NU06F301J02', ], (Ecu.eps, 0x7d4, None): [b'\xf1\x00OS MDPS C 1.00 1.05 56310J9030\x00 4OSDC105', ], (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00OS9 LKAS AT USA LHD 1.00 1.00 95740-J9300 g21', ], @@ -910,7 +910,7 @@ FW_VERSIONS = { b'\xf1\x816U2V7051\000\000\xf1\0006U2V0_C2\000\0006U2V7051\000\000DCD0T14US1\000\000\000\000', b'\xf1\x816U2V7051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V7051\x00\x00DCD0T14US1U\x867Z', ], - (Ecu.esp, 0x7D1, None): [b'\xf1\000CD ESC \003 102\030\b\005 58920-J7350', ], + (Ecu.abs, 0x7D1, None): [b'\xf1\000CD ESC \003 102\030\b\005 58920-J7350', ], }, CAR.KIA_FORTE: { (Ecu.eps, 0x7D4, None): [ @@ -928,7 +928,7 @@ FW_VERSIONS = { b'\x01TBDM1NU06F200H01', b'391182B945\x00', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x816VGRAH00018.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.transmission, 0x7e1, None): [ @@ -952,7 +952,7 @@ FW_VERSIONS = { b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.03 99210-L3000 200915', b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.04 99210-L3000 210208', ], - (Ecu.esp, 0x7D1, None): [ + (Ecu.abs, 0x7D1, None): [ b'\xf1\000DL ESC \006 101 \004\002 58910-L3200', b'\xf1\x8758910-L3200\xf1\000DL ESC \006 101 \004\002 58910-L3200', b'\xf1\x8758910-L3800\xf1\x00DL ESC \t 101 \x07\x02 58910-L3800', @@ -972,7 +972,7 @@ FW_VERSIONS = { ], }, CAR.KONA_EV: { - (Ecu.esp, 0x7D1, None): [ + (Ecu.abs, 0x7D1, None): [ b'\xf1\x00OS IEB \r 105\x18\t\x18 58520-K4000', b'\xf1\x00OS IEB \x01 212 \x11\x13 58520-K4000', b'\xf1\x00OS IEB \x02 212 \x11\x13 58520-K4000', @@ -999,7 +999,7 @@ FW_VERSIONS = { ], }, CAR.KONA_EV_2022: { - (Ecu.esp, 0x7D1, None): [ + (Ecu.abs, 0x7D1, None): [ b'\xf1\x8758520-K4010\xf1\x00OS IEB \x02 101 \x11\x13 58520-K4010', b'\xf1\x8758520-K4010\xf1\x00OS IEB \x04 101 \x11\x13 58520-K4010', b'\xf1\x8758520-K4010\xf1\x00OS IEB \x03 101 \x11\x13 58520-K4010', @@ -1093,7 +1093,7 @@ FW_VERSIONS = { }, CAR.KIA_SELTOS: { (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x8799110Q5100\xf1\000SP2_ SCC FHCUP 1.01 1.05 99110-Q5100 ',], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x8758910-Q5450\xf1\000SP ESC \a 101\031\t\005 58910-Q5450', b'\xf1\x8758910-Q5450\xf1\000SP ESC \t 101\031\t\005 58910-Q5450', ], @@ -1121,7 +1121,7 @@ FW_VERSIONS = { (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4110 ', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00JF ESC \x0b 11 \x18\x030 58920-D5180', ], (Ecu.engine, 0x7e0, None): [ @@ -1158,7 +1158,7 @@ FW_VERSIONS = { b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.01 99210-AB000 210205', b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.06 99210-AA000 220111', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800', b'\xf1\x8758910-AA800\xf1\x00CN ESC \t 104 \x08\x03 58910-AA800', b'\xf1\x8758910-AB800\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800', @@ -1204,7 +1204,7 @@ FW_VERSIONS = { ] }, CAR.KONA_HEV: { - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00OS IEB \x01 104 \x11 58520-CM000', ], (Ecu.fwdRadar, 0x7d0, None): [ @@ -1258,7 +1258,7 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00UMP LKAS AT USA LHD 1.01 1.01 95740-C6550 d01' ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00UM ESC \x0c 12 \x18\x05\x06 58910-C6330' ], (Ecu.fwdRadar, 0x7D0, None): [ @@ -1272,7 +1272,7 @@ FW_VERSIONS = { ], }, CAR.KIA_EV6: { - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x8758520CV100\xf1\x00CV IEB \x02 101!\x10\x18 58520-CV100', ], (Ecu.eps, 0x7d4, None): [ @@ -1287,7 +1287,7 @@ FW_VERSIONS = { ], }, CAR.IONIQ_5: { - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00NE1 IEB \x07 106!\x11) 58520-GI010', b'\xf1\x8758520GI010\xf1\x00NE1 IEB \x07 106!\x11) 58520-GI010', b'\xf1\x00NE1 IEB \x08 104!\x04\x05 58520-GI000', diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index ed246f15da..95f140422e 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -72,7 +72,7 @@ FW_VERSIONS = { (Ecu.fwdRadar, 0x764, None): [ b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'KSD5-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x706, None): [ @@ -116,7 +116,7 @@ FW_VERSIONS = { b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'KBJ5-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'KL2K-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -173,7 +173,7 @@ FW_VERSIONS = { b'TK80-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'TK80-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'TK79-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'TK79-437K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -217,7 +217,7 @@ FW_VERSIONS = { b'GHP9-67Y10---41\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'B45A-437AS-0-08\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x706, None): [ @@ -248,7 +248,7 @@ FW_VERSIONS = { b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-E\000\000\000\000\000\000\000\000\000\000\000\000', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'GBVH-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'GDDM-437K2-A\000\000\000\000\000\000\000\000\000\000\000\000', ], @@ -275,7 +275,7 @@ FW_VERSIONS = { b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x706, None): [ diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index 2126e550ef..440c682490 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -95,7 +95,7 @@ FW_VERSIONS = { b'5SH1BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', b'5SK0ADB\x04\x18\x00\x00\x00\x00\x00_(5\x07\x9aQ\x00\x00\x00\x80', ], - (Ecu.esp, 0x740, None): [ + (Ecu.abs, 0x740, None): [ b'476605SH1D', b'476605SK2A', ], @@ -112,7 +112,7 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x707, None): [ b'284N86FR2A', ], - (Ecu.esp, 0x740, None): [ + (Ecu.abs, 0x740, None): [ b'6FU1BD\x11\x02\x00\x02e\x95e\x80iX#\x01\x00\x00\x00\x00\x00\x80', b'6FU0AD\x11\x02\x00\x02e\x95e\x80iQ#\x01\x00\x00\x00\x00\x00\x80', ], diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index d04e5f2cc6..53dd4a763f 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -74,7 +74,7 @@ CAR_INFO: Dict[str, Union[SubaruCarInfo, List[SubaruCarInfo]]] = { FW_VERSIONS = { CAR.ASCENT: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\xa5 \x19\x02\x00', b'\xa5 !\002\000', b'\xf1\x82\xa5 \x19\x02\x00', @@ -104,7 +104,7 @@ FW_VERSIONS = { ], }, CAR.LEGACY: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\xa1\\ x04\x01', b'\xa1 \x03\x03' ], @@ -126,7 +126,7 @@ FW_VERSIONS = { ], }, CAR.IMPREZA: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x7a\x94\x3f\x90\x00', b'\xa2 \x185\x00', b'\xa2 \x193\x00', @@ -201,7 +201,7 @@ FW_VERSIONS = { ], }, CAR.IMPREZA_2020: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\xa2 \0314\000', b'\xa2 \0313\000', b'\xa2 !i\000', @@ -239,7 +239,7 @@ FW_VERSIONS = { ], }, CAR.FORESTER: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\xa3 \x18\x14\x00', b'\xa3 \024\000', b'\xa3 \031\024\000', @@ -274,7 +274,7 @@ FW_VERSIONS = { ], }, CAR.FORESTER_PREGLOBAL: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x7d\x97\x14\x40', b'\xf1\x00\xbb\x0c\x04', ], @@ -303,7 +303,7 @@ FW_VERSIONS = { ], }, CAR.LEGACY_PREGLOBAL: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'k\x97D\x00', b'[\xba\xc4\x03', b'{\x97D\x00', @@ -333,7 +333,7 @@ FW_VERSIONS = { ], }, CAR.OUTBACK_PREGLOBAL: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'{\x9a\xac\x00', b'k\x97\xac\x00', b'\x5b\xf7\xbc\x03', @@ -387,7 +387,7 @@ FW_VERSIONS = { ], }, CAR.OUTBACK_PREGLOBAL_2018: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x8b\x97\xac\x00', b'\x8b\x9a\xac\x00', b'\x9b\x97\xac\x00', @@ -430,7 +430,7 @@ FW_VERSIONS = { ], }, CAR.OUTBACK: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\xa1 \x06\x01', b'\xa1 \a\x00', b'\xa1 \b\001', diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 18b6db0db7..af2fc9f56e 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -200,7 +200,7 @@ STATIC_DSU_MSGS = [ FW_VERSIONS = { CAR.AVALON: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152607060\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ @@ -225,7 +225,7 @@ FW_VERSIONS = { ], }, CAR.AVALON_2019: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152607140\x00\x00\x00\x00\x00\x00', b'F152607171\x00\x00\x00\x00\x00\x00', b'F152607110\x00\x00\x00\x00\x00\x00', @@ -253,7 +253,7 @@ FW_VERSIONS = { ], }, CAR.AVALONH_2019: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152641040\x00\x00\x00\x00\x00\x00', b'F152641061\x00\x00\x00\x00\x00\x00', b'F152641050\x00\x00\x00\x00\x00\x00', @@ -280,7 +280,7 @@ FW_VERSIONS = { ], }, CAR.AVALON_TSS2: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F152607240\x00\x00\x00\x00\x00\x00', b'\x01F152607280\x00\x00\x00\x00\x00\x00', ], @@ -300,7 +300,7 @@ FW_VERSIONS = { ], }, CAR.AVALONH_TSS2: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152641080\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ @@ -356,7 +356,7 @@ FW_VERSIONS = { b'8821F0608200 ', b'8821F0609100 ', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152606210\x00\x00\x00\x00\x00\x00', b'F152606230\x00\x00\x00\x00\x00\x00', b'F152606270\x00\x00\x00\x00\x00\x00', @@ -420,7 +420,7 @@ FW_VERSIONS = { b'\x028966306S0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', b'\x028966306S1100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152633214\x00\x00\x00\x00\x00\x00', b'F152633660\x00\x00\x00\x00\x00\x00', b'F152633712\x00\x00\x00\x00\x00\x00', @@ -486,7 +486,7 @@ FW_VERSIONS = { (Ecu.eps, 0x7a1, None): [ b'8965B33630\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F152606370\x00\x00\x00\x00\x00\x00', b'\x01F152606390\x00\x00\x00\x00\x00\x00', b'\x01F152606400\x00\x00\x00\x00\x00\x00', @@ -512,7 +512,7 @@ FW_VERSIONS = { (Ecu.eps, 0x7a1, None): [ b'8965B33630\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152633D00\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x700, None): [ @@ -547,7 +547,7 @@ FW_VERSIONS = { b'8821FF406000 ', b'8821FF407100 ', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152610020\x00\x00\x00\x00\x00\x00', b'F152610153\x00\x00\x00\x00\x00\x00', b'F152610210\x00\x00\x00\x00\x00\x00', @@ -599,7 +599,7 @@ FW_VERSIONS = { b'\x0289663F431000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x0189663F438000\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152610012\x00\x00\x00\x00\x00\x00', b'F152610013\x00\x00\x00\x00\x00\x00', b'F152610014\x00\x00\x00\x00\x00\x00', @@ -658,7 +658,7 @@ FW_VERSIONS = { b'881510201100\x00\x00\x00\x00', b'881510201200\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152602190\x00\x00\x00\x00\x00\x00', b'F152602191\x00\x00\x00\x00\x00\x00', ], @@ -735,7 +735,7 @@ FW_VERSIONS = { b'\x018965B12510\x00\x00\x00\x00\x00\x00', b'\x018965B1256000\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F152602280\x00\x00\x00\x00\x00\x00', b'\x01F152602560\x00\x00\x00\x00\x00\x00', b'\x01F152602590\x00\x00\x00\x00\x00\x00', @@ -813,7 +813,7 @@ FW_VERSIONS = { b'\x018965B12520\x00\x00\x00\x00\x00\x00', b'\x018965B12530\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152612590\x00\x00\x00\x00\x00\x00', b'F152612691\x00\x00\x00\x00\x00\x00', b'F152612692\x00\x00\x00\x00\x00\x00', @@ -885,7 +885,7 @@ FW_VERSIONS = { b'8965B48150\x00\x00\x00\x00\x00\x00', b'8965B48210\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [b'F15260E011\x00\x00\x00\x00\x00\x00'], + (Ecu.abs, 0x7b0, None): [b'F15260E011\x00\x00\x00\x00\x00\x00'], (Ecu.dsu, 0x791, None): [ b'881510E01100\x00\x00\x00\x00', b'881510E01200\x00\x00\x00\x00', @@ -903,7 +903,7 @@ FW_VERSIONS = { (Ecu.eps, 0x7a1, None): [ b'8965B48160\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152648541\x00\x00\x00\x00\x00\x00', b'F152648542\x00\x00\x00\x00\x00\x00', ], @@ -928,7 +928,7 @@ FW_VERSIONS = { b'8965B48310\x00\x00\x00\x00\x00\x00', b'8965B48320\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F15260E051\x00\x00\x00\x00\x00\x00', b'\x01F15260E061\x00\x00\x00\x00\x00\x00', b'\x01F15260E110\x00\x00\x00\x00\x00\x00', @@ -967,7 +967,7 @@ FW_VERSIONS = { b'8965B48241\x00\x00\x00\x00\x00\x00', b'8965B48310\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F15264872300\x00\x00\x00\x00', b'\x01F15264872400\x00\x00\x00\x00', b'\x01F15264872500\x00\x00\x00\x00', @@ -1015,7 +1015,7 @@ FW_VERSIONS = { b'\x02353P7000\x00\x00\x00\x00\x00\x00\x00\x00530J5000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02353P9000\x00\x00\x00\x00\x00\x00\x00\x00553C1000\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152653300\x00\x00\x00\x00\x00\x00', b'F152653301\x00\x00\x00\x00\x00\x00', b'F152653310\x00\x00\x00\x00\x00\x00', @@ -1099,7 +1099,7 @@ FW_VERSIONS = { b'8965B47050\x00\x00\x00\x00\x00\x00', b'8965B47060\x00\x00\x00\x00\x00\x00', # This is the EPS with good angle sensor ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152647290\x00\x00\x00\x00\x00\x00', b'F152647300\x00\x00\x00\x00\x00\x00', b'F152647310\x00\x00\x00\x00\x00\x00', @@ -1140,7 +1140,7 @@ FW_VERSIONS = { ], }, CAR.PRIUS_V: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152647280\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [ @@ -1173,7 +1173,7 @@ FW_VERSIONS = { b'8965B42082\x00\x00\x00\x00\x00\x00', b'8965B42083\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F15260R102\x00\x00\x00\x00\x00\x00', b'F15260R103\x00\x00\x00\x00\x00\x00', b'F152642493\x00\x00\x00\x00\x00\x00', @@ -1210,7 +1210,7 @@ FW_VERSIONS = { b'8965B42162\x00\x00\x00\x00\x00\x00', b'8965B42163\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152642090\x00\x00\x00\x00\x00\x00', b'F152642110\x00\x00\x00\x00\x00\x00', b'F152642120\x00\x00\x00\x00\x00\x00', @@ -1272,7 +1272,7 @@ FW_VERSIONS = { b'\x02896634A47000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', b'\x028966342Z8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F15260R210\x00\x00\x00\x00\x00\x00', b'\x01F15260R220\x00\x00\x00\x00\x00\x00', b'\x01F15260R290\x00\x00\x00\x00\x00\x00', @@ -1313,7 +1313,7 @@ FW_VERSIONS = { ], }, CAR.RAV4_TSS2_2022: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F15260R350\x00\x00\x00\x00\x00\x00', b'\x01F15260R361\x00\x00\x00\x00\x00\x00', ], @@ -1353,7 +1353,7 @@ FW_VERSIONS = { b'\x02896634A14001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', b'\x02896634A14101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152642291\x00\x00\x00\x00\x00\x00', b'F152642290\x00\x00\x00\x00\x00\x00', b'F152642322\x00\x00\x00\x00\x00\x00', @@ -1392,7 +1392,7 @@ FW_VERSIONS = { ], }, CAR.RAV4H_TSS2_2022: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F15264283100\x00\x00\x00\x00', b'\x01F15264286200\x00\x00\x00\x00', b'\x01F15264286100\x00\x00\x00\x00', @@ -1440,7 +1440,7 @@ FW_VERSIONS = { b'8965B45080\x00\x00\x00\x00\x00\x00', b'8965B45082\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152608130\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ @@ -1459,7 +1459,7 @@ FW_VERSIONS = { (Ecu.dsu, 0x791, None): [ b'881517601100\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152676144\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [ @@ -1481,7 +1481,7 @@ FW_VERSIONS = { b'\x018966333X6000\x00\x00\x00\x00', b'\x01896633T07000\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F152606281\x00\x00\x00\x00\x00\x00', b'\x01F152606340\x00\x00\x00\x00\x00\x00', b'\x01F152606461\x00\x00\x00\x00\x00\x00', @@ -1518,7 +1518,7 @@ FW_VERSIONS = { b'\x02896633T09000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', b'\x01896633T38000\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152633423\x00\x00\x00\x00\x00\x00', b'F152633680\x00\x00\x00\x00\x00\x00', b'F152633681\x00\x00\x00\x00\x00\x00', @@ -1551,7 +1551,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\x02333M4200\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152633171\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ @@ -1577,7 +1577,7 @@ FW_VERSIONS = { b'\x01896637854000\x00\x00\x00\x00', b'\x01896637878000\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152678130\x00\x00\x00\x00\x00\x00', b'F152678140\x00\x00\x00\x00\x00\x00', ], @@ -1604,7 +1604,7 @@ FW_VERSIONS = { b'\x018966378B3000\x00\x00\x00\x00', b'\x018966378G3000\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F152678221\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ @@ -1624,7 +1624,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\x0237887000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152678210\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ @@ -1645,7 +1645,7 @@ FW_VERSIONS = { b'\x0237882000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x0237886000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152678160\x00\x00\x00\x00\x00\x00', b'F152678170\x00\x00\x00\x00\x00\x00', b'F152678171\x00\x00\x00\x00\x00\x00', @@ -1672,7 +1672,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\x0232484000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152624221\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ @@ -1708,7 +1708,7 @@ FW_VERSIONS = { b'\x018966348R8500\x00\x00\x00\x00', b'\x018966348W1300\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152648472\x00\x00\x00\x00\x00\x00', b'F152648473\x00\x00\x00\x00\x00\x00', b'F152648492\x00\x00\x00\x00\x00\x00', @@ -1755,7 +1755,7 @@ FW_VERSIONS = { b'\x02348V6000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02348Z3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152648361\x00\x00\x00\x00\x00\x00', b'F152648501\x00\x00\x00\x00\x00\x00', b'F152648502\x00\x00\x00\x00\x00\x00', @@ -1803,7 +1803,7 @@ FW_VERSIONS = { b'\x01896634D43000\x00\x00\x00\x00', b'\x01896634D44000\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F15260E031\x00\x00\x00\x00\x00\x00', b'\x01F15260E041\x00\x00\x00\x00\x00\x00', b'\x01F152648781\x00\x00\x00\x00\x00\x00', @@ -1833,7 +1833,7 @@ FW_VERSIONS = { b'\x0234D16000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02348X4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152648831\x00\x00\x00\x00\x00\x00', b'F152648891\x00\x00\x00\x00\x00\x00', b'F152648D00\x00\x00\x00\x00\x00\x00', @@ -1863,7 +1863,7 @@ FW_VERSIONS = { b'\x038966347C5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', b'\x038966347C5100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152647500\x00\x00\x00\x00\x00\x00', b'F152647510\x00\x00\x00\x00\x00\x00', b'F152647520\x00\x00\x00\x00\x00\x00', @@ -1883,8 +1883,8 @@ FW_VERSIONS = { ], }, CAR.MIRAI: { - (Ecu.esp, 0x7D1, None): [b'\x01898A36203000\x00\x00\x00\x00',], - (Ecu.esp, 0x7B0, None): [ # a second ESP ECU + (Ecu.abs, 0x7D1, None): [b'\x01898A36203000\x00\x00\x00\x00',], + (Ecu.abs, 0x7B0, None): [ # a second ABS ECU b'\x01F15266203200\x00\x00\x00\x00', b'\x01F15266203500\x00\x00\x00\x00', ], @@ -1917,7 +1917,7 @@ FW_VERSIONS = { (Ecu.eps, 0x7a1, None): [ b'8965B58040\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152658341\x00\x00\x00\x00\x00\x00' ], (Ecu.fwdRadar, 0x750, 0xf): [ diff --git a/selfdrive/controls/tests/test_startup.py b/selfdrive/controls/tests/test_startup.py index a94311c8c7..63af4c7d95 100755 --- a/selfdrive/controls/tests/test_startup.py +++ b/selfdrive/controls/tests/test_startup.py @@ -18,7 +18,7 @@ Ecu = car.CarParams.Ecu COROLLA_FW_VERSIONS = [ (Ecu.engine, 0x7e0, None, b'\x0230ZC2000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.esp, 0x7b0, None, b'F152602190\x00\x00\x00\x00\x00\x00'), + (Ecu.abs, 0x7b0, None, b'F152602190\x00\x00\x00\x00\x00\x00'), (Ecu.eps, 0x7a1, None, b'8965B02181\x00\x00\x00\x00\x00\x00'), (Ecu.fwdRadar, 0x750, 0xf, b'8821F4702100\x00\x00\x00\x00'), (Ecu.fwdCamera, 0x750, 0x6d, b'8646F0201101\x00\x00\x00\x00'), @@ -29,7 +29,7 @@ COROLLA_FW_VERSIONS_NO_DSU = COROLLA_FW_VERSIONS[:-1] CX5_FW_VERSIONS = [ (Ecu.engine, 0x7e0, None, b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.esp, 0x760, None, b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), + (Ecu.abs, 0x760, None, b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), (Ecu.eps, 0x730, None, b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), (Ecu.fwdRadar, 0x764, None, b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), (Ecu.fwdCamera, 0x706, None, b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), From 445492a6d8d9bceb78def0511552f154be0ffd4f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 7 Sep 2022 16:50:25 -0700 Subject: [PATCH 048/152] reduce min lane change speed to 15mph (#25689) --- selfdrive/controls/lib/desire_helper.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/desire_helper.py b/selfdrive/controls/lib/desire_helper.py index 19ab2da214..d41d6780e3 100644 --- a/selfdrive/controls/lib/desire_helper.py +++ b/selfdrive/controls/lib/desire_helper.py @@ -5,7 +5,7 @@ from common.realtime import DT_MDL LaneChangeState = log.LateralPlan.LaneChangeState LaneChangeDirection = log.LateralPlan.LaneChangeDirection -LANE_CHANGE_SPEED_MIN = 30 * CV.MPH_TO_MS +LANE_CHANGE_SPEED_MIN = 15 * CV.MPH_TO_MS LANE_CHANGE_TIME_MAX = 10. DESIRES = { From 655a64b60318ce44ef0271e03de16e8b135b5268 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 7 Sep 2022 17:12:49 -0700 Subject: [PATCH 049/152] single longitudinal toggle for e2e and disable radar (#25688) * single longitudinal toggle for e2e and disable radar * write disable radar param * rename * better param name * clean that up * update refs * update translations * not live for experimental * write it out * vanish --- common/params.cc | 4 +- docs/CARS.md | 62 +++++++++--------- selfdrive/car/body/interface.py | 2 +- selfdrive/car/car_helpers.py | 4 +- selfdrive/car/chrysler/interface.py | 2 +- selfdrive/car/docs.py | 6 +- selfdrive/car/docs_definitions.py | 2 +- selfdrive/car/ford/interface.py | 2 +- selfdrive/car/gm/interface.py | 2 +- selfdrive/car/honda/interface.py | 5 +- selfdrive/car/hyundai/interface.py | 5 +- selfdrive/car/interfaces.py | 2 +- selfdrive/car/mazda/interface.py | 2 +- selfdrive/car/mock/interface.py | 2 +- selfdrive/car/nissan/interface.py | 2 +- selfdrive/car/subaru/interface.py | 2 +- selfdrive/car/tesla/interface.py | 2 +- selfdrive/car/tests/test_models.py | 6 +- selfdrive/car/toyota/interface.py | 2 +- selfdrive/car/volkswagen/interface.py | 5 +- selfdrive/controls/controlsd.py | 6 +- selfdrive/debug/set_car_params.py | 17 ++++- selfdrive/manager/manager.py | 3 - selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/ui/installer/installer.cc | 1 - selfdrive/ui/qt/offroad/settings.cc | 81 ++++++++++++++++++++---- selfdrive/ui/qt/offroad/settings.h | 7 ++ selfdrive/ui/qt/widgets/controls.h | 13 +++- selfdrive/ui/translations/main_ja.ts | 20 ++---- selfdrive/ui/translations/main_ko.ts | 22 ++----- selfdrive/ui/translations/main_pt-BR.ts | 22 ++----- selfdrive/ui/translations/main_zh-CHS.ts | 20 ++---- selfdrive/ui/translations/main_zh-CHT.ts | 20 ++---- 33 files changed, 191 insertions(+), 164 deletions(-) diff --git a/common/params.cc b/common/params.cc index 5c8002dfb7..5c8c94be53 100644 --- a/common/params.cc +++ b/common/params.cc @@ -93,6 +93,7 @@ std::unordered_map keys = { {"CarBatteryCapacity", PERSISTENT}, {"CarParams", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"CarParamsCache", CLEAR_ON_MANAGER_START}, + {"CarParamsPersistent", PERSISTENT}, {"CarVin", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"CompletedTrainingVersion", PERSISTENT}, {"ControlsReady", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, @@ -101,8 +102,7 @@ std::unordered_map keys = { {"DisableLogging", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"DisablePowerDown", PERSISTENT}, {"EndToEndLong", PERSISTENT}, - {"DisableRadar_Allow", PERSISTENT}, - {"DisableRadar", PERSISTENT}, // WARNING: THIS DISABLES AEB + {"ExperimentalLongitudinalEnabled", PERSISTENT}, // WARNING: THIS MAY DISABLE AEB {"DisableUpdates", PERSISTENT}, {"DisengageOnAccelerator", PERSISTENT}, {"DongleId", PERSISTENT}, diff --git a/docs/CARS.md b/docs/CARS.md index 1f0e24865d..e3cbea95c2 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -10,7 +10,7 @@ A supported vehicle is one that just works when you install a comma three. All s |---|---|---|:---:|:---:|:---:|:---:|:---:|:---:| |Acura|ILX 2016-19|AcuraWatch Plus|openpilot|25 mph|25 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| |Acura|RDX 2016-18|AcuraWatch Plus|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| -|Acura|RDX 2019-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Acura|RDX 2019-22|All|openpilot|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| |Audi|A3 2014-19|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| |Audi|A3 Sportback e-tron 2017-18|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| |Audi|Q2 2018|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| @@ -26,77 +26,77 @@ A supported vehicle is one that just works when you install a comma three. All s |Chrysler|Pacifica 2021|All|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Chrysler|Pacifica Hybrid 2019-22|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| -|comma|body|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|None| +|comma|body|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|None| |Genesis|G70 2018-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| |Genesis|G70 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| |Genesis|G80 2017-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| -|Genesis|G90 2017-18|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Genesis|G90 2017-18|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| |GMC|Sierra 1500 2020-21|Driver Alert Package II|Stock|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| -|Honda|Accord 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| -|Honda|Accord Hybrid 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|Accord 2018-22|All|openpilot|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|Accord Hybrid 2018-22|All|openpilot|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| |Honda|Civic 2016-18|Honda Sensing|openpilot|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| -|Honda|Civic 2019-21|All|Stock|0 mph|2 mph[2](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|Civic 2019-21|All|openpilot|0 mph|2 mph[2](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| |Honda|Civic 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch B| -|Honda|Civic Hatchback 2017-21|Honda Sensing|Stock|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|Civic Hatchback 2017-21|Honda Sensing|openpilot|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| |Honda|Civic Hatchback 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch B| |Honda|CR-V 2015-16|Touring Trim|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| -|Honda|CR-V 2017-22|Honda Sensing|Stock|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| -|Honda|CR-V Hybrid 2017-19|Honda Sensing|Stock|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| -|Honda|e 2020|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|CR-V 2017-22|Honda Sensing|openpilot|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|CR-V Hybrid 2017-19|Honda Sensing|openpilot|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|e 2020|All|openpilot|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| |Honda|Fit 2018-20|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| |Honda|Freed 2020|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| |Honda|HR-V 2019-22|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| -|Honda|Insight 2019-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| -|Honda|Inspire 2018|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|Insight 2019-22|All|openpilot|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|Inspire 2018|All|openpilot|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| |Honda|Odyssey 2018-20|Honda Sensing|openpilot|25 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| |Honda|Passport 2019-21|All|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| |Honda|Pilot 2016-22|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| |Honda|Ridgeline 2017-22|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| |Hyundai|Elantra 2017-19|Smart Cruise Control (SCC) & LKAS|Stock|19 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| -|Hyundai|Elantra 2021-22|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| -|Hyundai|Elantra Hybrid 2021-22|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| +|Hyundai|Elantra 2021-22|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| +|Hyundai|Elantra Hybrid 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| |Hyundai|Genesis 2015-16|Smart Cruise Control (SCC) & LKAS|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai J| -|Hyundai|Ioniq 5 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai Q| +|Hyundai|Ioniq 5 2022|Highway Driving Assist II|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai Q| |Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |Hyundai|Ioniq Electric 2020|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |Hyundai|Ioniq Hybrid 2020-22|Smart Cruise Control (SCC) & LFA|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| -|Hyundai|Ioniq Plug-in Hybrid 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Hyundai|Ioniq Plug-in Hybrid 2019|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |Hyundai|Ioniq Plug-in Hybrid 2020-21|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| -|Hyundai|Kona 2020|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| +|Hyundai|Kona 2020|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| |Hyundai|Kona Electric 2018-21|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| |Hyundai|Kona Electric 2022|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai O| -|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai I| +|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai I| |Hyundai|Palisade 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Hyundai|Santa Fe 2019-20|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai D| -|Hyundai|Santa Fe 2021-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| -|Hyundai|Santa Fe Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| -|Hyundai|Santa Fe Plug-in Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Santa Fe 2021-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Santa Fe Hybrid 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Santa Fe Plug-in Hybrid 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| |Hyundai|Sonata 2018-19|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Hyundai|Sonata 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| |Hyundai|Sonata Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| -|Hyundai|Tucson 2021|Smart Cruise Control (SCC)|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| -|Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| -|Hyundai|Tucson Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai N| +|Hyundai|Tucson 2021|Smart Cruise Control (SCC)|openpilot|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Tucson Hybrid 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai N| |Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Kia|Ceed 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| -|Kia|EV6 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P| -|Kia|Forte 2018|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| -|Kia|Forte 2019-21|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| -|Kia|K5 2021-22|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| +|Kia|EV6 2022|Highway Driving Assist II|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P| +|Kia|Forte 2018|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| +|Kia|Forte 2019-21|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| +|Kia|K5 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| |Kia|Niro Electric 2019|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Kia|Niro Electric 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| |Kia|Niro Electric 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |Kia|Niro Electric 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| -|Kia|Niro Hybrid 2021|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| -|Kia|Niro Hybrid 2022|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Kia|Niro Hybrid 2021|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| +|Kia|Niro Hybrid 2022|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Kia|Niro Plug-in Hybrid 2018-19|Smart Cruise Control (SCC) & LKAS|openpilot|10 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |Kia|Optima 2017|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| |Kia|Optima 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| -|Kia|Seltos 2021|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| +|Kia|Seltos 2021|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| |Kia|Sorento 2018|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |Kia|Sorento 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Kia|Stinger 2018-20|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| diff --git a/selfdrive/car/body/interface.py b/selfdrive/car/body/interface.py index e85735b1a6..ae7ab89aab 100644 --- a/selfdrive/car/body/interface.py +++ b/selfdrive/car/body/interface.py @@ -8,7 +8,7 @@ from selfdrive.car.body.values import SPEED_FROM_RPM class CarInterface(CarInterfaceBase): @staticmethod - def get_params(candidate, fingerprint=None, car_fw=None, disable_radar=False): + def get_params(candidate, fingerprint=None, car_fw=None, experimental_long=False): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 9e1260a6d5..4f098fadb5 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -177,10 +177,10 @@ def get_car(logcan, sendcan): cloudlog.warning("car doesn't match any fingerprints: %r", fingerprints) candidate = "mock" - disable_radar = Params().get_bool("DisableRadar") + experimental_long = Params().get_bool("ExperimentalLongitudinalEnabled") CarInterface, CarController, CarState = interfaces[candidate] - CP = CarInterface.get_params(candidate, fingerprints, car_fw, disable_radar) + CP = CarInterface.get_params(candidate, fingerprints, car_fw, experimental_long) CP.carVin = vin CP.carFw = car_fw CP.fingerprintSource = source diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 131f813c6c..245e10650c 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -8,7 +8,7 @@ from selfdrive.car.interfaces import CarInterfaceBase class CarInterface(CarInterfaceBase): @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, disable_radar=False): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "chrysler" diff --git a/selfdrive/car/docs.py b/selfdrive/car/docs.py index 4d79cbfc76..e948698cb4 100755 --- a/selfdrive/car/docs.py +++ b/selfdrive/car/docs.py @@ -11,7 +11,6 @@ from common.basedir import BASEDIR from selfdrive.car import gen_empty_fingerprint from selfdrive.car.docs_definitions import CarInfo, Column from selfdrive.car.car_helpers import interfaces, get_interface_attr -from selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR as HKG_RADAR_START_ADDR def get_all_footnotes() -> Dict[Enum, int]: @@ -29,10 +28,7 @@ def get_all_car_info() -> List[CarInfo]: all_car_info: List[CarInfo] = [] footnotes = get_all_footnotes() for model, car_info in get_interface_attr("CAR_INFO", combine_brands=True).items(): - # Hyundai exception: those with radar have openpilot longitudinal - fingerprint = gen_empty_fingerprint() - fingerprint[1] = {HKG_RADAR_START_ADDR: 8} - CP = interfaces[model][0].get_params(model, fingerprint=fingerprint, disable_radar=True) + CP = interfaces[model][0].get_params(model, fingerprint=gen_empty_fingerprint(), experimental_long=True) if CP.dashcamOnly or car_info is None: continue diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index 3f9d51b433..015877dcb4 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -132,7 +132,7 @@ class CarInfo: Column.MAKE: self.make, Column.MODEL: self.model, Column.PACKAGE: self.package, - Column.LONGITUDINAL: "openpilot" if CP.openpilotLongitudinalControl and not CP.radarOffCan else "Stock", + Column.LONGITUDINAL: "openpilot" if CP.openpilotLongitudinalControl or CP.experimentalLongitudinalAvailable else "Stock", Column.FSR_LONGITUDINAL: f"{max(self.min_enable_speed * CV.MS_TO_MPH, 0):.0f} mph", Column.FSR_STEERING: f"{max(self.min_steer_speed * CV.MS_TO_MPH, 0):.0f} mph", Column.STEERING_TORQUE: Star.EMPTY, diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py index 405579fa60..271b347148 100644 --- a/selfdrive/car/ford/interface.py +++ b/selfdrive/car/ford/interface.py @@ -11,7 +11,7 @@ EventName = car.CarEvent.EventName class CarInterface(CarInterfaceBase): @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, disable_radar=False): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "ford" diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index ac8bc45809..be28890484 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -45,7 +45,7 @@ class CarInterface(CarInterfaceBase): return CarInterfaceBase.get_steer_feedforward_default @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, disable_radar=False): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "gm" ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.gm)] diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index a235ba6cda..c884f586a0 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -29,7 +29,7 @@ class CarInterface(CarInterfaceBase): return CarControllerParams.NIDEC_ACCEL_MIN, interp(current_speed, ACCEL_MAX_BP, ACCEL_MAX_VALS) @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[], disable_radar=False): # pylint: disable=dangerous-default-value + def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[], experimental_long=False): # pylint: disable=dangerous-default-value ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "honda" @@ -40,7 +40,8 @@ class CarInterface(CarInterfaceBase): if candidate not in HONDA_BOSCH_RADARLESS: # Disable the radar and let openpilot control longitudinal # WARNING: THIS DISABLES AEB! - ret.openpilotLongitudinalControl = disable_radar + ret.experimentalLongitudinalAvailable = True + ret.openpilotLongitudinalControl = experimental_long ret.pcmCruise = not ret.openpilotLongitudinalControl else: diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index bbb797c2e0..97b8b30dc9 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -21,14 +21,15 @@ class CarInterface(CarInterfaceBase): return CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[], disable_radar=False): # pylint: disable=dangerous-default-value + def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[], experimental_long=False): # pylint: disable=dangerous-default-value ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "hyundai" ret.radarOffCan = RADAR_START_ADDR not in fingerprint[1] or DBC[ret.carFingerprint]["radar"] is None # WARNING: disabling radar also disables AEB (and we show the same warning on the instrument cluster as if you manually disabled AEB) - ret.openpilotLongitudinalControl = disable_radar and (candidate not in (LEGACY_SAFETY_MODE_CAR | CAMERA_SCC_CAR)) + ret.experimentalLongitudinalAvailable = candidate not in (LEGACY_SAFETY_MODE_CAR | CAMERA_SCC_CAR) + ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable ret.pcmCruise = not ret.openpilotLongitudinalControl diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 1e14aca8cf..a33560cd0e 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -85,7 +85,7 @@ class CarInterfaceBase(ABC): @staticmethod @abstractmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, disable_radar=False): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False): pass @staticmethod diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index 8640903444..89ed5638cb 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -15,7 +15,7 @@ class CarInterface(CarInterfaceBase): return float(accel) / 4.0 @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, disable_radar=False): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "mazda" diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py index 715850c227..2c7f4611ee 100755 --- a/selfdrive/car/mock/interface.py +++ b/selfdrive/car/mock/interface.py @@ -33,7 +33,7 @@ class CarInterface(CarInterfaceBase): return accel @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, disable_radar=False): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "mock" ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.noOutput)] diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index 494573f498..e095ceb461 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -8,7 +8,7 @@ from selfdrive.car.nissan.values import CAR class CarInterface(CarInterfaceBase): @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, disable_radar=False): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "nissan" diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index b842912256..a920c02534 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -9,7 +9,7 @@ from selfdrive.car.subaru.values import CAR, GLOBAL_GEN2, PREGLOBAL_CARS class CarInterface(CarInterfaceBase): @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, disable_radar=False): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "subaru" diff --git a/selfdrive/car/tesla/interface.py b/selfdrive/car/tesla/interface.py index 5e78c72b60..2eb29efb41 100755 --- a/selfdrive/car/tesla/interface.py +++ b/selfdrive/car/tesla/interface.py @@ -8,7 +8,7 @@ from selfdrive.car.interfaces import CarInterfaceBase class CarInterface(CarInterfaceBase): @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, disable_radar=False): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "tesla" diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index cc7d3da874..fa07db92db 100755 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -67,7 +67,7 @@ class TestCarModelBase(unittest.TestCase): raise unittest.SkipTest raise Exception(f"missing test route for {cls.car_model}") - disable_radar = False + experimental_long = False test_segs = (2, 1, 0) if cls.test_route.segment is not None: test_segs = (cls.test_route.segment,) @@ -93,7 +93,7 @@ class TestCarModelBase(unittest.TestCase): elif msg.which() == "carParams": car_fw = msg.carParams.carFw if msg.carParams.openpilotLongitudinalControl: - disable_radar = True + experimental_long = True if cls.car_model is None and not cls.ci: cls.car_model = msg.carParams.carFingerprint @@ -105,7 +105,7 @@ class TestCarModelBase(unittest.TestCase): cls.can_msgs = sorted(can_msgs, key=lambda msg: msg.logMonoTime) cls.CarInterface, cls.CarController, cls.CarState = interfaces[cls.car_model] - cls.CP = cls.CarInterface.get_params(cls.car_model, fingerprint, car_fw, disable_radar) + cls.CP = cls.CarInterface.get_params(cls.car_model, fingerprint, car_fw, experimental_long) assert cls.CP assert cls.CP.carFingerprint == cls.car_model diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index a0d3ce9b8d..8528005eb5 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -16,7 +16,7 @@ class CarInterface(CarInterfaceBase): return CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[], disable_radar=False): # pylint: disable=dangerous-default-value + def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[], experimental_long=False): # pylint: disable=dangerous-default-value ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "toyota" diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 6f0bb9a197..3ed7a6244d 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -21,7 +21,7 @@ class CarInterface(CarInterfaceBase): self.cp_ext = self.cp_cam @staticmethod - def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, disable_radar=False): + def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "volkswagen" ret.radarOffCan = True @@ -49,9 +49,10 @@ class CarInterface(CarInterfaceBase): # Panda ALLOW_DEBUG firmware required. ret.dashcamOnly = True - if disable_radar and ret.networkLocation == NetworkLocation.gateway: + if experimental_long and ret.networkLocation == NetworkLocation.gateway: # Proof-of-concept, prep for E2E only. No radar points available. Follow-to-stop not yet supported, but should # be simple to add when a suitable test car becomes available. Panda ALLOW_DEBUG firmware required. + ret.experimentalLongitudinalAvailable = True ret.openpilotLongitudinalControl = True ret.safetyConfigs[0].safetyParam |= Panda.FLAG_VOLKSWAGEN_LONG_CONTROL diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 3704389304..3054b020e1 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -12,7 +12,7 @@ import cereal.messaging as messaging from common.conversions import Conversions as CV from panda import ALTERNATIVE_EXPERIENCE from system.swaglog import cloudlog -from system.version import get_short_branch +from system.version import is_tested_branch, get_short_branch from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.car.car_helpers import get_car, get_startup_event, get_one_can from selfdrive.controls.lib.lateral_planner import CAMERA_OFFSET @@ -134,10 +134,14 @@ class Controls: safety_config.safetyModel = car.CarParams.SafetyModel.noOutput self.CP.safetyConfigs = [safety_config] + if is_tested_branch(): + self.CP.experimentalLongitudinalAvailable = False + # Write CarParams for radard cp_bytes = self.CP.to_bytes() params.put("CarParams", cp_bytes) put_nonblocking("CarParamsCache", cp_bytes) + put_nonblocking("CarParamsPersistent", cp_bytes) self.CC = car.CarControl.new_message() self.CS_prev = car.CarState.new_message() diff --git a/selfdrive/debug/set_car_params.py b/selfdrive/debug/set_car_params.py index bcdaed0778..24258db9f2 100755 --- a/selfdrive/debug/set_car_params.py +++ b/selfdrive/debug/set_car_params.py @@ -1,11 +1,22 @@ #!/usr/bin/env python3 import sys +from cereal import car from common.params import Params from tools.lib.route import Route from tools.lib.logreader import LogReader if __name__ == "__main__": - r = Route(sys.argv[1]) - cp = [m for m in LogReader(r.qlog_paths()[0]) if m.which() == 'carParams'] - Params().put("CarParams", cp[0].carParams.as_builder().to_bytes()) + CP = None + if len(sys.argv) > 1: + r = Route(sys.argv[1]) + cps = [m for m in LogReader(r.qlog_paths()[0]) if m.which() == 'carParams'] + CP = cps[0].carParams.as_builder() + else: + CP = car.CarParams.new_message() + CP.openpilotLongitudinalControl = True + CP.experimentalLongitudinalAvailable = False + + cp_bytes = CP.to_bytes() + for p in ("CarParams", "CarParamsCache", "CarParamsPersistent"): + Params().put(p, cp_bytes) diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index 772dd9488f..ff2bf4bc89 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -49,9 +49,6 @@ def manager_init() -> None: if params.get_bool("RecordFrontLock"): params.put_bool("RecordFront", True) - if not params.get_bool("DisableRadar_Allow"): - params.remove("DisableRadar") - # set unset params for k, v in default_params: if params.get(k) is None: diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 0e2a5d84e3..8878e0e1f1 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -209423f468194c77443110078639ff67a8b99073 +8137b41a0520d2b4a0ca223f9934957ae21695e5 diff --git a/selfdrive/ui/installer/installer.cc b/selfdrive/ui/installer/installer.cc index db33e1cd67..7d8bbf74e0 100644 --- a/selfdrive/ui/installer/installer.cc +++ b/selfdrive/ui/installer/installer.cc @@ -182,7 +182,6 @@ void Installer::cloneFinished(int exitCode, QProcess::ExitStatus exitStatus) { std::map params = { {"SshEnabled", "1"}, {"RecordFrontLock", "1"}, - {"DisableRadar_Allow", "1"}, {"GithubSshKeys", SSH_KEYS}, }; for (const auto& [key, value] : params) { diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index d44f4c75f6..33b16b1051 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -28,7 +28,7 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { // param, title, desc, icon - std::vector> toggles{ + std::vector> toggle_defs{ { "OpenpilotEnabledToggle", tr("Enable openpilot"), @@ -62,7 +62,7 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { { "EndToEndLong", tr("🌮 End-to-end longitudinal (extremely alpha) 🌮"), - tr("Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental."), + "", "../assets/offroad/icon_road.png", }, #ifdef ENABLE_MAPS @@ -82,22 +82,75 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { }; - Params params; - - if (params.getBool("DisableRadar_Allow")) { - toggles.push_back({ - "DisableRadar", - tr("openpilot Longitudinal Control"), - tr("openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB!"), - "../assets/offroad/icon_speed_limit.png", - }); - } - - for (auto &[param, title, desc, icon] : toggles) { + for (auto &[param, title, desc, icon] : toggle_defs) { auto toggle = new ParamControl(param, title, desc, icon, this); + bool locked = params.getBool((param + "Lock").toStdString()); toggle->setEnabled(!locked); + addItem(toggle); + toggles[param.toStdString()] = toggle; + } + + QObject::connect(toggles["EndToEndLong"], &ParamControl::toggleFlipped, [=](bool state) { + auto cp_bytes = params.get("CarParamsPersistent"); + if (!cp_bytes.empty()) { + AlignedBuffer aligned_buf; + capnp::FlatArrayMessageReader cmsg(aligned_buf.align(cp_bytes.data(), cp_bytes.size())); + cereal::CarParams::Reader CP = cmsg.getRoot(); + if (CP.getExperimentalLongitudinalAvailable()) { + params.putBool("ExperimentalLongitudinalEnabled", state); + } else { + params.remove("ExperimentalLongitudinalEnabled"); + } + } else { + params.remove("ExperimentalLongitudinalEnabled"); + } + }); + + connect(uiState(), &UIState::offroadTransition, [=]() { + updateToggles(); + }); +} + +void TogglesPanel::showEvent(QShowEvent *event) { + updateToggles(); +} + +void TogglesPanel::updateToggles() { + // update e2e toggle + auto toggle = toggles["EndToEndLong"]; + const QString e2e_description = tr("Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental."); + + auto cp_bytes = params.get("CarParamsPersistent"); + if (!cp_bytes.empty()) { + AlignedBuffer aligned_buf; + capnp::FlatArrayMessageReader cmsg(aligned_buf.align(cp_bytes.data(), cp_bytes.size())); + cereal::CarParams::Reader CP = cmsg.getRoot(); + + const bool exp_long = CP.getExperimentalLongitudinalAvailable(); + const bool op_long = CP.getOpenpilotLongitudinalControl() && !CP.getExperimentalLongitudinalAvailable(); + + if (op_long) { + // normal description and toggle + params.remove("ExperimentalLongitudinalEnabled"); + toggle->setDescription(e2e_description); + } else if (exp_long) { + toggle->setDescription("WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.

" + e2e_description); + if (params.getBool("EndToEndLong") && !params.getBool("ExperimentalLongitudinalEnabled")) { + params.remove("EndToEndLong"); + } + } else { + // no long for now + params.remove("EndToEndLong"); + params.remove("ExperimentalLongitudinalEnabled"); + toggle->setDescription("openpilot longitudinal control is not currently available for this car.

" + e2e_description); + } + + toggle->refresh(); + toggle->setEnabled(op_long || (exp_long && !uiState()->scene.started)); + } else { + toggle->setDescription(e2e_description); } } diff --git a/selfdrive/ui/qt/offroad/settings.h b/selfdrive/ui/qt/offroad/settings.h index 45efe255cf..1f823851f1 100644 --- a/selfdrive/ui/qt/offroad/settings.h +++ b/selfdrive/ui/qt/offroad/settings.h @@ -54,6 +54,13 @@ class TogglesPanel : public ListWidget { Q_OBJECT public: explicit TogglesPanel(SettingsWindow *parent); + void showEvent(QShowEvent *event) override; + +private: + Params params; + std::map toggles; + + void updateToggles(); }; class SoftwarePanel : public ListWidget { diff --git a/selfdrive/ui/qt/widgets/controls.h b/selfdrive/ui/qt/widgets/controls.h index 4245a9c04a..183fbff04d 100644 --- a/selfdrive/ui/qt/widgets/controls.h +++ b/selfdrive/ui/qt/widgets/controls.h @@ -105,7 +105,10 @@ public: QObject::connect(&toggle, &Toggle::stateChanged, this, &ToggleControl::toggleFlipped); } - void setEnabled(bool enabled) { toggle.setEnabled(enabled); toggle.update(); } + void setEnabled(bool enabled) { + toggle.setEnabled(enabled); + toggle.update(); + } signals: void toggleFlipped(bool state); @@ -121,17 +124,21 @@ class ParamControl : public ToggleControl { public: ParamControl(const QString ¶m, const QString &title, const QString &desc, const QString &icon, QWidget *parent = nullptr) : ToggleControl(title, desc, icon, false, parent) { key = param.toStdString(); - QObject::connect(this, &ToggleControl::toggleFlipped, [=](bool state) { + QObject::connect(this, &ParamControl::toggleFlipped, [=](bool state) { params.putBool(key, state); }); } - void showEvent(QShowEvent *event) override { + void refresh() { if (params.getBool(key) != toggle.on) { toggle.togglePosition(); } }; + void showEvent(QShowEvent *event) override { + refresh(); + }; + private: std::string key; Params params; diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 7d0203daed..4ce5b7b8d6 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -108,7 +108,7 @@ DevicePanel - + Dongle ID ドングル番号 (Dongle ID) @@ -1153,7 +1153,7 @@ location set TogglesPanel - + Enable openpilot openpilot を有効化 @@ -1198,12 +1198,12 @@ location set
- - Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. + + Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal アクセル踏むと openpilot をキャンセル @@ -1232,16 +1232,6 @@ location set Show map on left side when in split screen view. 分割画面表示の場合、ディスプレイの左側にマップを表示します。
- - - openpilot Longitudinal Control - openpilot 縦方向制御 - - - - openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! - openpilot は、車のレーダーを無効化し、アクセルとブレーキの制御を引き継ぎます。注意:AEB を無効化にします! -
Updater diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index ff83057a93..a38cfaf946 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -108,7 +108,7 @@ DevicePanel - + Dongle ID Dongle ID @@ -1153,7 +1153,7 @@ location set TogglesPanel - + Enable openpilot openpilot 사용 @@ -1198,12 +1198,12 @@ location set 🌮 e2e long 사용 (매우 실험적) 🌮
- - Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - 주행모델이 가속과 감속을 제어하도록 하면 openpilot은 운전자가 생각하는것처럼 운전합니다. (매우 실험적) + + Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. + - + Disengage On Accelerator Pedal 가속페달 조작시 해제 @@ -1232,16 +1232,6 @@ location set Show map on left side when in split screen view. 분할 화면 보기에서 지도를 왼쪽에 표시합니다.
- - - openpilot Longitudinal Control - openpilot Longitudinal Control - - - - openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! - openpilot은 차량'의 레이더를 무력화시키고 가속페달과 브레이크의 제어를 인계받을 것이다. 경고: AEB를 비활성화합니다! -
Updater diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 5a2167ea87..9f3bd59824 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -108,7 +108,7 @@ DevicePanel - + Dongle ID Dongle ID @@ -1157,7 +1157,7 @@ trabalho definido TogglesPanel - + Enable openpilot Ativar openpilot @@ -1202,12 +1202,12 @@ trabalho definido 🌮 End-to-end longitudinal (experimental) 🌮
- - Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - Deixe o modelo de direção controlar o acelerador e o freio, o openpilot dirigirá da maneira como ele entende que um humano o faria. Super experimental. + + Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. + - + Disengage On Accelerator Pedal Desacionar Com Pedal Do Acelerador @@ -1236,16 +1236,6 @@ trabalho definido Show map on left side when in split screen view. Exibir mapa do lado esquerdo quando a tela for dividida.
- - - openpilot Longitudinal Control - openpilot Controle Longitudinal - - - - openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! - openpilot desativará o radar do carro e assumirá o controle do acelerador e freios. Atenção: isso desativa AEB! -
Updater diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 79a08899cb..94ed832113 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -108,7 +108,7 @@ DevicePanel - + Dongle ID 设备ID(Dongle ID) @@ -1151,7 +1151,7 @@ location set TogglesPanel - + Enable openpilot 启用openpilot @@ -1196,12 +1196,12 @@ location set - - Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. + + Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal 踩油门时取消控制 @@ -1230,16 +1230,6 @@ location set Show map on left side when in split screen view. 在分屏模式中,将地图置于屏幕左侧。 - - - openpilot Longitudinal Control - openpilot纵向控制 - - - - openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! - openpilot将禁用车辆的雷达并接管油门和刹车的控制。警告:AEB将被禁用! - Updater diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 0d51e6d286..754d41bbda 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -108,7 +108,7 @@ DevicePanel - + Dongle ID Dongle ID @@ -1153,7 +1153,7 @@ location set TogglesPanel - + Enable openpilot 啟用 openpilot @@ -1198,12 +1198,12 @@ location set - - Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. + + Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal 油門取消控車 @@ -1232,16 +1232,6 @@ location set Show map on left side when in split screen view. 進入分割畫面後,地圖將會顯示在畫面的左側。 - - - openpilot Longitudinal Control - openpilot 縱向控制 - - - - openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! - openpilot 將會關閉雷達訊號並接管油門和剎車的控制。注意:這也會關閉自動緊急煞車 (AEB) 系統! - Updater From da6c7311a38b1206be5443f8447f5424458671a5 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Wed, 7 Sep 2022 19:09:37 -0700 Subject: [PATCH 050/152] Improve Hyundai long control, and conform to longcontrol API boundaries (#25696) * Variety of experimental improvements * fix start accel * typo * No jerk, no go * Set jerk limit lower * Update ref --- selfdrive/car/hyundai/carcontroller.py | 9 +++------ selfdrive/car/hyundai/hyundaican.py | 14 +++++++------- selfdrive/car/hyundai/interface.py | 10 ++++++---- selfdrive/test/process_replay/ref_commit | 2 +- 4 files changed, 17 insertions(+), 18 deletions(-) diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 586d215ffe..db80bcdf48 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -1,6 +1,6 @@ from cereal import car from common.conversions import Conversions as CV -from common.numpy_fast import clip, interp +from common.numpy_fast import clip from common.realtime import DT_CTRL from opendbc.can.packer import CANPacker from selfdrive.car import apply_std_steer_torque_limits @@ -123,12 +123,9 @@ class CarController: if self.frame % 2 == 0 and self.CP.openpilotLongitudinalControl: accel = actuators.accel - jerk = 0 - if CC.longActive: - jerk = clip(2.0 * (accel - CS.out.aEgo), -12.7, 12.7) - if accel < 0: - accel = interp(accel - CS.out.aEgo, [-1.0, -0.5], [2 * accel, accel]) + #TODO unclear if this is needed + jerk = 3.0 if actuators.longControlState == LongCtrlState.pid else 1.0 accel = clip(accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py index f94cc508a7..df5cb6ae6e 100644 --- a/selfdrive/car/hyundai/hyundaican.py +++ b/selfdrive/car/hyundai/hyundaican.py @@ -94,7 +94,7 @@ def create_lfahda_mfc(packer, enabled, hda_set_speed=0): } return packer.make_can_msg("LFAHDA_MFC", 0, values) -def create_acc_commands(packer, enabled, accel, jerk, idx, lead_visible, set_speed, stopping, gas_pressed): +def create_acc_commands(packer, enabled, accel, upper_jerk, idx, lead_visible, set_speed, stopping, gas_pressed): commands = [] scc11_values = { @@ -102,12 +102,12 @@ def create_acc_commands(packer, enabled, accel, jerk, idx, lead_visible, set_spe "TauGapSet": 4, "VSetDis": set_speed if enabled else 0, "AliveCounterACC": idx % 0x10, - "ObjValid": 0, # TODO: these two bits may allow for better longitudinal control - "ACC_ObjStatus": 0, + "ObjValid": 1, # close lead makes controls tighter + "ACC_ObjStatus": 1, # close lead makes controls tighter "ACC_ObjLatPos": 0, "ACC_ObjRelSpd": 0, - "ACC_ObjDist": 0, - } + "ACC_ObjDist": 1, # close lead makes controls tighter + } commands.append(packer.make_can_msg("SCC11", 0, scc11_values)) scc12_values = { @@ -125,8 +125,8 @@ def create_acc_commands(packer, enabled, accel, jerk, idx, lead_visible, set_spe scc14_values = { "ComfortBandUpper": 0.0, # stock usually is 0 but sometimes uses higher values "ComfortBandLower": 0.0, # stock usually is 0 but sometimes uses higher values - "JerkUpperLimit": max(jerk, 1.0) if not stopping else 0, # stock usually is 1.0 but sometimes uses higher values - "JerkLowerLimit": max(-jerk, 1.0), # stock usually is 0.5 but sometimes uses higher values + "JerkUpperLimit": upper_jerk, # stock usually is 1.0 but sometimes uses higher values + "JerkLowerLimit": 5.0, # stock usually is 0.5 but sometimes uses higher values "ACCMode": 2 if enabled and gas_pressed else 1 if enabled else 4, # stock will always be 4 instead of 0 after first disengage "ObjGap": 2 if lead_visible else 0, # 5: >30, m, 4: 25-30 m, 3: 20-25 m, 2: < 20 m, 0: no lead } diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 97b8b30dc9..f905586fbf 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -43,13 +43,15 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 1. ret.stoppingControl = True - ret.vEgoStopping = 1.0 + ret.startingState = True + ret.vEgoStarting = 0.1 + ret.startAccel = 2.0 - ret.longitudinalTuning.kpV = [0.1] + ret.longitudinalTuning.kpV = [0.5] ret.longitudinalTuning.kiV = [0.0] - ret.stopAccel = 0.0 - ret.longitudinalActuatorDelayUpperBound = 1.0 # s + ret.longitudinalActuatorDelayLowerBound = 0.5 # s + ret.longitudinalActuatorDelayUpperBound = 0.5 # s if candidate in (CAR.SANTA_FE, CAR.SANTA_FE_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022): ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3982. * CV.LB_TO_KG + STD_CARGO_KG diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 8878e0e1f1..2821f957ed 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -8137b41a0520d2b4a0ca223f9934957ae21695e5 +bd712b78c1ef351343b60e7ea527d09583e8acb7 From 3ef37fe2e848689dd3ef1e28b6cf14213c9fe069 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 7 Sep 2022 20:38:04 -0700 Subject: [PATCH 051/152] split out experimental long toggle (#25698) * split out experimental long toggle * clean up * update translations --- .../controls/lib/longitudinal_planner.py | 3 +- selfdrive/ui/qt/offroad/settings.cc | 60 ++++++++----------- selfdrive/ui/qt/widgets/controls.h | 9 ++- selfdrive/ui/translations/main_ja.ts | 20 +++++-- selfdrive/ui/translations/main_ko.ts | 20 +++++-- selfdrive/ui/translations/main_pt-BR.ts | 20 +++++-- selfdrive/ui/translations/main_zh-CHS.ts | 20 +++++-- selfdrive/ui/translations/main_zh-CHT.ts | 20 +++++-- 8 files changed, 109 insertions(+), 63 deletions(-) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 8162d10071..b9b16e34fc 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -66,7 +66,8 @@ class LongitudinalPlanner: self.solverExecutionTime = 0.0 def read_param(self): - self.mpc.mode = 'blended' if self.params.get_bool('EndToEndLong') else 'acc' + e2e = self.params.get_bool('EndToEndLong') and self.CP.openpilotLongitudinalControl + self.mpc.mode = 'blended' if e2e else 'acc' def parse_model(self, model_msg): if (len(model_msg.position.x) == 33 and diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 33b16b1051..e5e5634545 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -65,6 +65,12 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { "", "../assets/offroad/icon_road.png", }, + { + "ExperimentalLongitudinalEnabled", + tr("Experimental openpilot longitudinal control"), + tr("WARNING: openpilot longitudinal control is experimental for this car and will disable AEB."), + "../assets/offroad/icon_speed_limit.png", + }, #ifdef ENABLE_MAPS { "NavSettingTime24h", @@ -92,23 +98,7 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { toggles[param.toStdString()] = toggle; } - QObject::connect(toggles["EndToEndLong"], &ParamControl::toggleFlipped, [=](bool state) { - auto cp_bytes = params.get("CarParamsPersistent"); - if (!cp_bytes.empty()) { - AlignedBuffer aligned_buf; - capnp::FlatArrayMessageReader cmsg(aligned_buf.align(cp_bytes.data(), cp_bytes.size())); - cereal::CarParams::Reader CP = cmsg.getRoot(); - if (CP.getExperimentalLongitudinalAvailable()) { - params.putBool("ExperimentalLongitudinalEnabled", state); - } else { - params.remove("ExperimentalLongitudinalEnabled"); - } - } else { - params.remove("ExperimentalLongitudinalEnabled"); - } - }); - - connect(uiState(), &UIState::offroadTransition, [=]() { + connect(toggles["ExperimentalLongitudinalEnabled"], &ToggleControl::toggleFlipped, [=]() { updateToggles(); }); } @@ -118,8 +108,8 @@ void TogglesPanel::showEvent(QShowEvent *event) { } void TogglesPanel::updateToggles() { - // update e2e toggle - auto toggle = toggles["EndToEndLong"]; + auto e2e_toggle = toggles["EndToEndLong"]; + auto op_long_toggle = toggles["ExperimentalLongitudinalEnabled"]; const QString e2e_description = tr("Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental."); auto cp_bytes = params.get("CarParamsPersistent"); @@ -128,29 +118,31 @@ void TogglesPanel::updateToggles() { capnp::FlatArrayMessageReader cmsg(aligned_buf.align(cp_bytes.data(), cp_bytes.size())); cereal::CarParams::Reader CP = cmsg.getRoot(); - const bool exp_long = CP.getExperimentalLongitudinalAvailable(); - const bool op_long = CP.getOpenpilotLongitudinalControl() && !CP.getExperimentalLongitudinalAvailable(); + if (!CP.getExperimentalLongitudinalAvailable()) { + params.remove("ExperimentalLongitudinalEnabled"); + } + op_long_toggle->setVisible(CP.getExperimentalLongitudinalAvailable()); - if (op_long) { + const bool op_long = CP.getOpenpilotLongitudinalControl() && !CP.getExperimentalLongitudinalAvailable(); + const bool exp_long_enabled = CP.getExperimentalLongitudinalAvailable() && params.getBool("ExperimentalLongitudinalEnabled"); + if (op_long || exp_long_enabled) { // normal description and toggle - params.remove("ExperimentalLongitudinalEnabled"); - toggle->setDescription(e2e_description); - } else if (exp_long) { - toggle->setDescription("WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.

" + e2e_description); - if (params.getBool("EndToEndLong") && !params.getBool("ExperimentalLongitudinalEnabled")) { - params.remove("EndToEndLong"); - } + e2e_toggle->setEnabled(true); + e2e_toggle->setDescription(e2e_description); } else { // no long for now + e2e_toggle->setEnabled(false); params.remove("EndToEndLong"); - params.remove("ExperimentalLongitudinalEnabled"); - toggle->setDescription("openpilot longitudinal control is not currently available for this car.

" + e2e_description); + + const QString no_long = "openpilot longitudinal control is not currently available for this car."; + const QString exp_long = "Enable experimental longitudinal control to enable this."; + e2e_toggle->setDescription("" + (CP.getExperimentalLongitudinalAvailable() ? exp_long : no_long) + "

" + e2e_description); } - toggle->refresh(); - toggle->setEnabled(op_long || (exp_long && !uiState()->scene.started)); + e2e_toggle->refresh(); } else { - toggle->setDescription(e2e_description); + e2e_toggle->setDescription(e2e_description); + op_long_toggle->setVisible(false); } } diff --git a/selfdrive/ui/qt/widgets/controls.h b/selfdrive/ui/qt/widgets/controls.h index 183fbff04d..1ab7df717f 100644 --- a/selfdrive/ui/qt/widgets/controls.h +++ b/selfdrive/ui/qt/widgets/controls.h @@ -164,9 +164,12 @@ private: QPainter p(this); p.setPen(Qt::gray); for (int i = 0; i < inner_layout.count() - 1; ++i) { - QRect r = inner_layout.itemAt(i)->geometry(); - int bottom = r.bottom() + inner_layout.spacing() / 2; - p.drawLine(r.left() + 40, bottom, r.right() - 40, bottom); + QWidget *widget = inner_layout.itemAt(i)->widget(); + if (widget->isVisible()) { + QRect r = inner_layout.itemAt(i)->geometry(); + int bottom = r.bottom() + inner_layout.spacing() / 2; + p.drawLine(r.left() + 40, bottom, r.right() - 40, bottom); + } } } QVBoxLayout outer_layout; diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 4ce5b7b8d6..d6bd9e74ed 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -108,7 +108,7 @@ DevicePanel - + Dongle ID ドングル番号 (Dongle ID) @@ -1153,7 +1153,7 @@ location set TogglesPanel - + Enable openpilot openpilot を有効化 @@ -1198,12 +1198,22 @@ location set - + + Experimental openpilot longitudinal control + + + + + <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b> + + + + Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal アクセル踏むと openpilot をキャンセル @@ -1213,7 +1223,7 @@ location set 有効な場合は、アクセルを踏むと openpilot をキャンセルします。 - + Show ETA in 24h Format 24時間表示 diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index a38cfaf946..cc60ba7c89 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -108,7 +108,7 @@ DevicePanel - + Dongle ID Dongle ID @@ -1153,7 +1153,7 @@ location set TogglesPanel - + Enable openpilot openpilot 사용 @@ -1198,12 +1198,22 @@ location set 🌮 e2e long 사용 (매우 실험적) 🌮 - + + Experimental openpilot longitudinal control + + + + + <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b> + + + + Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal 가속페달 조작시 해제 @@ -1213,7 +1223,7 @@ location set 활성화된 경우 가속 페달을 누르면 openpilot이 해제됩니다. - + Show ETA in 24h Format 24시간 형식으로 도착예정시간 표시 diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 9f3bd59824..2b3acb369f 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -108,7 +108,7 @@ DevicePanel - + Dongle ID Dongle ID @@ -1157,7 +1157,7 @@ trabalho definido TogglesPanel - + Enable openpilot Ativar openpilot @@ -1202,12 +1202,22 @@ trabalho definido 🌮 End-to-end longitudinal (experimental) 🌮 - + + Experimental openpilot longitudinal control + + + + + <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b> + + + + Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal Desacionar Com Pedal Do Acelerador @@ -1217,7 +1227,7 @@ trabalho definido Quando ativado, pressionar o pedal do acelerador desacionará o openpilot. - + Show ETA in 24h Format Mostrar ETA em formato 24h diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 94ed832113..a00bf28303 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -108,7 +108,7 @@ DevicePanel - + Dongle ID 设备ID(Dongle ID) @@ -1151,7 +1151,7 @@ location set TogglesPanel - + Enable openpilot 启用openpilot @@ -1196,12 +1196,22 @@ location set - + + Experimental openpilot longitudinal control + + + + + <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b> + + + + Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal 踩油门时取消控制 @@ -1211,7 +1221,7 @@ location set 启用后,踩下油门踏板将取消openpilot。 - + Show ETA in 24h Format 以24小时格式显示预计到达时间 diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 754d41bbda..52bd301364 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -108,7 +108,7 @@ DevicePanel - + Dongle ID Dongle ID @@ -1153,7 +1153,7 @@ location set TogglesPanel - + Enable openpilot 啟用 openpilot @@ -1198,12 +1198,22 @@ location set - + + Experimental openpilot longitudinal control + + + + + <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b> + + + + Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal 油門取消控車 @@ -1213,7 +1223,7 @@ location set 啟用後,踩踏油門將會取消 openpilot 控制。 - + Show ETA in 24h Format 預計到達時間單位改用 24 小時制 From 76ead92f63a3568565b57ae189744c95b776412a Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 7 Sep 2022 20:38:24 -0700 Subject: [PATCH 052/152] bump opendbc --- opendbc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc b/opendbc index 83d4cb9fd8..e95ed311c1 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 83d4cb9fd871a563f4a0af0102992c0b52c94310 +Subproject commit e95ed311c10547026143b539a33341425cbec9ea From 613686855779187db9b20ecee34a4f8b1dd5ce67 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 8 Sep 2022 11:39:54 -0700 Subject: [PATCH 053/152] ui: fix network page crash --- selfdrive/ui/qt/widgets/controls.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/qt/widgets/controls.h b/selfdrive/ui/qt/widgets/controls.h index 1ab7df717f..d8546bb3b5 100644 --- a/selfdrive/ui/qt/widgets/controls.h +++ b/selfdrive/ui/qt/widgets/controls.h @@ -165,7 +165,7 @@ private: p.setPen(Qt::gray); for (int i = 0; i < inner_layout.count() - 1; ++i) { QWidget *widget = inner_layout.itemAt(i)->widget(); - if (widget->isVisible()) { + if (widget == nullptr || widget->isVisible()) { QRect r = inner_layout.itemAt(i)->geometry(); int bottom = r.bottom() + inner_layout.spacing() / 2; p.drawLine(r.left() + 40, bottom, r.right() - 40, bottom); From 973ea7440c1db67d89fd3b77c94ba19b4a77717d Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 8 Sep 2022 11:41:29 -0700 Subject: [PATCH 054/152] Car docs: CAN-FD cars do not yet have op long (#25707) * CAN-FD cars do not yet have op long * update refs Co-authored-by: Adeeb Shihadeh --- docs/CARS.md | 6 +++--- selfdrive/car/hyundai/interface.py | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index e3cbea95c2..47694fffee 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -57,7 +57,7 @@ A supported vehicle is one that just works when you install a comma three. All s |Hyundai|Elantra 2021-22|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| |Hyundai|Elantra Hybrid 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| |Hyundai|Genesis 2015-16|Smart Cruise Control (SCC) & LKAS|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai J| -|Hyundai|Ioniq 5 2022|Highway Driving Assist II|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai Q| +|Hyundai|Ioniq 5 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai Q| |Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |Hyundai|Ioniq Electric 2020|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| @@ -78,12 +78,12 @@ A supported vehicle is one that just works when you install a comma three. All s |Hyundai|Sonata Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| |Hyundai|Tucson 2021|Smart Cruise Control (SCC)|openpilot|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| |Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| -|Hyundai|Tucson Hybrid 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai N| +|Hyundai|Tucson Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai N| |Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Kia|Ceed 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| -|Kia|EV6 2022|Highway Driving Assist II|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P| +|Kia|EV6 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P| |Kia|Forte 2018|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| |Kia|Forte 2019-21|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| |Kia|K5 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index f905586fbf..c32cfbeec2 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -28,7 +28,7 @@ class CarInterface(CarInterfaceBase): ret.radarOffCan = RADAR_START_ADDR not in fingerprint[1] or DBC[ret.carFingerprint]["radar"] is None # WARNING: disabling radar also disables AEB (and we show the same warning on the instrument cluster as if you manually disabled AEB) - ret.experimentalLongitudinalAvailable = candidate not in (LEGACY_SAFETY_MODE_CAR | CAMERA_SCC_CAR) + ret.experimentalLongitudinalAvailable = candidate not in (LEGACY_SAFETY_MODE_CAR | CAMERA_SCC_CAR | CANFD_CAR) ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable ret.pcmCruise = not ret.openpilotLongitudinalControl diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 2821f957ed..f46f39dd27 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -bd712b78c1ef351343b60e7ea527d09583e8acb7 +48db2dee177706285226d1287912e191f1699865 From 015090de9237af02beb5414be65e97ee84c39c45 Mon Sep 17 00:00:00 2001 From: Lee Jong Mun <43285072+crwusiz@users.noreply.github.com> Date: Fri, 9 Sep 2022 03:55:21 +0900 Subject: [PATCH 055/152] Multilang: add missing translations (#25705) kor translation update Co-authored-by: Shane Smiskol --- selfdrive/ui/translations/main_ko.ts | 36 ++++++++++++++-------------- 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index cc60ba7c89..5d7df2162e 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -70,7 +70,7 @@ leave blank for automatic configuration - 자동설정을 하려면 공백으로 두세요 + 자동설정하려면 공백으로 두세요 @@ -92,7 +92,7 @@ You must accept the Terms and Conditions in order to use openpilot. - openpilot을 사용하려면 이용 약관에 동의해야 합니다. + openpilot을 사용하려면 이용약관에 동의해야 합니다. @@ -140,7 +140,7 @@ Reset Calibration - 캘리브레이션 재설정 + 캘리브레이션 @@ -155,7 +155,7 @@ Review Training Guide - 트레이닝 가이드 다시보기 + 트레이닝 가이드 @@ -210,12 +210,12 @@ openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. - openpilot은 장치를 좌측 또는 우측은 4° 이내, 위쪽 5° 또는 아래쪽은 8° 이내로 설치해야 합니다. openpilot은 지속적으로 보정되므로 리셋이 거의 필요하지 않습니다. + openpilot은 좌우측은 4° 이내, 위쪽은 5° 아래쪽은 8° 이내로 장치를 설치해야 합니다. openpilot은 지속적으로 보정되므로 리셋은 거의 필요하지 않습니다. Your device is pointed %1° %2 and %3° %4. - 사용자의 장치가 %1° %2 및 %3° %4를 가리키고 있습니다. + 사용자의 장치가 %1° %2 및 %3° %4 위치에 설치되어있습니다. @@ -479,7 +479,7 @@ location set for "%1" - 하기위한 "%1" + "%1"에 접속하려면 인증이 필요합니다 @@ -684,7 +684,7 @@ location set System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. - 장치를 초기화 합니다. 확인버튼을 누르면 모든 내용과 설정이 초기화됩니다. 취소를 누르면 다시 부팅합니다. + 장치를 초기화 합니다. 확인버튼을 누르면 모든 내용과 설정이 초기화됩니다. 부팅을 재개하려면 취소를 누르세요. @@ -797,7 +797,7 @@ location set Continue without Wi-Fi - wifi 없이 계속 + wifi 연결없이 계속하기 @@ -842,7 +842,7 @@ location set Ensure the entered URL is valid, and the device’s internet connection is good. - 입력된 URL이 유효하고 장치의 인터넷 연결이 잘 되어 있는지 확인합니다. + 입력된 URL이 유효하고 장치의 네트워크 연결이 잘 되어 있는지 확인하세요. @@ -1080,7 +1080,7 @@ location set Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. - 경고:이렇게 하면 GitHub 설정의 모든 공용 키에 대한 SSH 액세스 권한이 부여됩니다. 자신의 사용자 이름이 아닌 GitHub 사용자 이름을 입력하지 마십시오. comma 직원은 GitHub 사용자 이름을 추가하도록 요청하지 않습니다. + 경고: 허용으로 설정하면 GitHub 설정의 모든 공용 키에 대한 SSH 액세스 권한이 부여됩니다. GitHub 사용자 ID 이외에는 입력하지 마십시오. comma에서는 GitHub ID를 추가하라는 요청을 하지 않습니다. @@ -1160,7 +1160,7 @@ location set Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. - 어댑티브 크루즈 컨트롤 및 차선 유지 운전자 보조를 위해 openpilot 시스템을 사용하십시오. 이 기능을 사용하려면 항상 주의를 기울여야 합니다. 이 설정을 변경하면 차량 전원이 꺼질 때 적용됩니다. + 어댑티브 크루즈 컨트롤 및 차선 유지 운전자 보조를 위해 openpilot 시스템을 사용하십시오. 이 기능을 사용하려면 항상 주의를 기울여야 합니다. 설정변경은 장치 재부팅후 적용됩니다. @@ -1170,7 +1170,7 @@ location set Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). - 차량이 50km/h(31mph) 이상의 속도로 주행하는 동안 방향 지시등이 활성화되지 않은 상태에서 감지된 차선 위를 주행할 경우 차선이탈 경고를 사용합니다. + 차량이 50km/h(31mph) 이상의 속도로 주행하는 동안 방향지시등 없이 감지된 차선 위를 주행할 경우 차선이탈 경고를 표시합니다. @@ -1195,22 +1195,22 @@ location set 🌮 End-to-end longitudinal (extremely alpha) 🌮 - 🌮 e2e long 사용 (매우 실험적) 🌮 + 🌮 e2e 롱컨트롤 사용 (매우 실험적) 🌮 Experimental openpilot longitudinal control - + openpilot 롱컨트롤 (실험적) <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b> - + <b>경고: openpilot 롱컨트롤은 실험적인 기능으로 차량의 AEB를 비활성화합니다.</b> Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. - + 주행모델이 가속과 감속을 제어하도록 하면 openpilot은 운전자가 생각하는것처럼 운전합니다. (매우 실험적) @@ -1253,7 +1253,7 @@ location set An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. - OS 업데이트가 필요합니다. 장치를 wifi에 연결하여 가장 빠른 업데이트 경험을 제공합니다. 다운로드 크기는 약 1GB입니다. + OS 업데이트가 필요합니다. 장치를 wifi에 연결하면 가장 빠른 업데이트 경험을 제공합니다. 다운로드 크기는 약 1GB입니다. From d9ca45ed1b2bc0316aad8ff11470e1a9b96fb09c Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 9 Sep 2022 02:56:39 +0800 Subject: [PATCH 056/152] map_helpers: pass parameters by const reference (#25701) pass parameters by const reference --- selfdrive/ui/qt/maps/map_helpers.cc | 6 +++--- selfdrive/ui/qt/maps/map_helpers.h | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/selfdrive/ui/qt/maps/map_helpers.cc b/selfdrive/ui/qt/maps/map_helpers.cc index f97137a7f9..ca81545f7f 100644 --- a/selfdrive/ui/qt/maps/map_helpers.cc +++ b/selfdrive/ui/qt/maps/map_helpers.cc @@ -56,7 +56,7 @@ QMapbox::CoordinatesCollections model_to_collection( return collections; } -QMapbox::CoordinatesCollections coordinate_to_collection(QMapbox::Coordinate c) { +QMapbox::CoordinatesCollections coordinate_to_collection(const QMapbox::Coordinate &c) { QMapbox::Coordinates coordinates; coordinates.push_back(c); @@ -85,7 +85,7 @@ QMapbox::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp: } -QMapbox::CoordinatesCollections coordinate_list_to_collection(QList coordinate_list) { +QMapbox::CoordinatesCollections coordinate_list_to_collection(const QList &coordinate_list) { QMapbox::Coordinates coordinates; for (auto &c : coordinate_list) { @@ -143,7 +143,7 @@ QList polyline_to_coordinate_list(const QString &polylineString) return path; } -std::optional coordinate_from_param(std::string param) { +std::optional coordinate_from_param(const std::string ¶m) { QString json_str = QString::fromStdString(Params().get(param)); if (json_str.isEmpty()) return {}; diff --git a/selfdrive/ui/qt/maps/map_helpers.h b/selfdrive/ui/qt/maps/map_helpers.h index 2e1402ccea..6bd5b0f067 100644 --- a/selfdrive/ui/qt/maps/map_helpers.h +++ b/selfdrive/ui/qt/maps/map_helpers.h @@ -21,10 +21,10 @@ QMapbox::CoordinatesCollections model_to_collection( const cereal::LiveLocationKalman::Measurement::Reader &calibratedOrientationECEF, const cereal::LiveLocationKalman::Measurement::Reader &positionECEF, const cereal::ModelDataV2::XYZTData::Reader &line); -QMapbox::CoordinatesCollections coordinate_to_collection(QMapbox::Coordinate c); +QMapbox::CoordinatesCollections coordinate_to_collection(const QMapbox::Coordinate &c); QMapbox::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List::Reader &coordinate_list); -QMapbox::CoordinatesCollections coordinate_list_to_collection(QList coordinate_list); +QMapbox::CoordinatesCollections coordinate_list_to_collection(const QList &coordinate_list); QList polyline_to_coordinate_list(const QString &polylineString); -std::optional coordinate_from_param(std::string param); +std::optional coordinate_from_param(const std::string ¶m); double angle_difference(double angle1, double angle2); From 9241de221099f6c65fd7ed5ed87d6296c17f668d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 8 Sep 2022 15:49:51 -0700 Subject: [PATCH 057/152] Ford Explorer 2020-21 (#25614) * add model years * update Focus steer ratio * Ford: add EU label to Focus Mk4 * add packages * add Ford Explorer 2020 Package: Co-Pilot 360 Assist+ Optional on XLT Standard on Limited, Limited Hybrid, ST and Platinum https://cdn.dealereprocess.org/cdn/brochures/ford/2020-explorer.pdf * Ford: steering control with path angle * Ford: add TJA toggle to buttons * add Ford Explorer 2021 `62241b0c7fea4589|2022-08-30--11-58-24--0` Package: Co-Pilot 360 Assist+ Optional on XLT Standard on Limited, Limited Hybrid, ST and Platinum (same as 2020) https://cdn.dealereprocess.org/cdn/brochures/ford/2021-explorer.pdf * Ford: add shiftByWire ECU fw * angle/steer refactor * try always stop and go for US models * no dashcam * car info * send resume button * skip explorer * escape and focus back in dashcam * passthru buttons * fordcan set bus for button message * toggle off stock traffic jam assist so camera does not enforce driver presence checks * not used * update ramp rate/precision notes * cleanup * bump steering pressed torque to 0.8 Nm * add standstill * bump steer ratio * try increasing delay? * fix docs * add kuga car info * maybe fix tja toggle? * compensate for ford roll compensation?? * oops * better ui * block non-adaptive * add note on ui warning for hands on wheel * try only checking/toggling TJA every 2 seconds * add car test route * dashcam only again * send buttons to camera * add process replay segment * cleanup * bump panda * add extra FW Co-authored-by: Cameron Clough --- panda | 2 +- selfdrive/car/ford/carcontroller.py | 70 +++++++++++------- selfdrive/car/ford/carstate.py | 49 ++++++++++++- selfdrive/car/ford/fordcan.py | 98 ++++++++++++++++++------- selfdrive/car/ford/interface.py | 40 +++++----- selfdrive/car/ford/values.py | 56 ++++++++++++-- selfdrive/car/fw_versions.py | 2 +- selfdrive/car/tests/routes.py | 1 + selfdrive/car/torque_data/override.yaml | 1 + 9 files changed, 236 insertions(+), 83 deletions(-) diff --git a/panda b/panda index 0ca23b6778..8f13ca3f66 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 0ca23b67786d0fa2a3162371aadeca52d24a8958 +Subproject commit 8f13ca3f66bcc72e3ac9028df7ce04851e7e3a48 diff --git a/selfdrive/car/ford/carcontroller.py b/selfdrive/car/ford/carcontroller.py index 11d9bb3c79..592d8586ca 100644 --- a/selfdrive/car/ford/carcontroller.py +++ b/selfdrive/car/ford/carcontroller.py @@ -1,3 +1,4 @@ +import math from cereal import car from common.numpy_fast import clip, interp from opendbc.can.packer import CANPacker @@ -7,14 +8,19 @@ from selfdrive.car.ford.values import CarControllerParams VisualAlert = car.CarControl.HUDControl.VisualAlert -def apply_ford_steer_angle_limits(apply_steer, apply_steer_last, vEgo): +def apply_ford_steer_angle_limits(apply_angle, apply_angle_last, vEgo): # rate limit - steer_up = apply_steer * apply_steer_last > 0. and abs(apply_steer) > abs(apply_steer_last) - rate_limit = CarControllerParams.STEER_RATE_LIMIT_UP if steer_up else CarControllerParams.STEER_RATE_LIMIT_DOWN + steer_up = apply_angle_last * apply_angle > 0. and abs(apply_angle) > abs(apply_angle_last) + rate_limit = CarControllerParams.RATE_LIMIT_UP if steer_up else CarControllerParams.RATE_LIMIT_DOWN max_angle_diff = interp(vEgo, rate_limit.speed_points, rate_limit.max_angle_diff_points) - apply_steer = clip(apply_steer, (apply_steer_last - max_angle_diff), (apply_steer_last + max_angle_diff)) + apply_angle = clip(apply_angle, (apply_angle_last - max_angle_diff), (apply_angle_last + max_angle_diff)) - return apply_steer + # absolute limit (LatCtlPath_An_Actl) + apply_path_angle = math.radians(apply_angle) / CarControllerParams.STEER_RATIO + apply_path_angle = clip(apply_path_angle, -0.4995, 0.5240) + apply_angle = math.degrees(apply_path_angle) * CarControllerParams.STEER_RATIO + + return apply_angle class CarController: @@ -24,7 +30,7 @@ class CarController: self.packer = CANPacker(dbc_name) self.frame = 0 - self.apply_steer_last = 0 + self.apply_angle_last = 0 self.main_on_last = False self.lkas_enabled_last = False self.steer_alert_last = False @@ -38,52 +44,62 @@ class CarController: main_on = CS.out.cruiseState.available steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) + ### acc buttons ### if CC.cruiseControl.cancel: - # cancel stock ACC - can_sends.append(fordcan.spam_cancel_button(self.packer)) + can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, cancel=True)) + elif CC.cruiseControl.resume: + can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, resume=True)) + + # if stock lane centering is active or in standby, toggle it off + # the stock system checks for steering pressed, and eventually disengages cruise control + if (self.frame % 200) == 0 and CS.acc_tja_status_stock_values["Tja_D_Stat"] != 0: + can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, tja_toggle=True)) + - # apply rate limits - new_steer = actuators.steeringAngleDeg - apply_steer = apply_ford_steer_angle_limits(new_steer, self.apply_steer_last, CS.out.vEgo) + ### lateral control ### + if CC.latActive: + apply_angle = apply_ford_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgo) + else: + apply_angle = CS.out.steeringAngleDeg # send steering commands at 20Hz if (self.frame % CarControllerParams.LKAS_STEER_STEP) == 0: lca_rq = 1 if CC.latActive else 0 - # use LatCtlPath_An_Actl to actuate steering for now until curvature control is implemented - path_angle = apply_steer + # use LatCtlPath_An_Actl to actuate steering + # path angle is the car wheel angle, not the steering wheel angle + path_angle = math.radians(apply_angle) / CarControllerParams.STEER_RATIO - # convert steer angle to curvature - curvature = self.VM.calc_curvature(apply_steer, CS.out.vEgo, 0.0) + # ramp rate: 0=Slow, 1=Medium, 2=Fast, 3=Immediately + # TODO: try slower ramp speed when driver torque detected + ramp_type = 3 + precision = 1 # 0=Comfortable, 1=Precise (the stock system always uses comfortable) - # TODO: get other actuators - curvature_rate = 0 - path_offset = 0 + offset_roll_compensation_curvature = clip(self.VM.calc_curvature(0, CS.out.vEgo, -CS.yaw_data["VehYaw_W_Actl"]), -0.02, 0.02094) - ramp_type = 3 # 0=Slow, 1=Medium, 2=Fast, 3=Immediately - precision = 0 # 0=Comfortable, 1=Precise - - self.apply_steer_last = apply_steer - can_sends.append(fordcan.create_lkas_command(self.packer, apply_steer, curvature)) + self.apply_angle_last = apply_angle + can_sends.append(fordcan.create_lka_command(self.packer, apply_angle, 0)) can_sends.append(fordcan.create_tja_command(self.packer, lca_rq, ramp_type, precision, - path_offset, path_angle, curvature_rate, curvature)) + 0, path_angle, 0, offset_roll_compensation_curvature)) + + ### ui ### send_ui = (self.main_on_last != main_on) or (self.lkas_enabled_last != CC.latActive) or (self.steer_alert_last != steer_alert) # send lkas ui command at 1Hz or if ui state changes if (self.frame % CarControllerParams.LKAS_UI_STEP) == 0 or send_ui: - can_sends.append(fordcan.create_lkas_ui_command(self.packer, main_on, CC.latActive, steer_alert, CS.lkas_status_stock_values)) + can_sends.append(fordcan.create_lkas_ui_command(self.packer, main_on, CC.latActive, steer_alert, hud_control, CS.lkas_status_stock_values)) # send acc ui command at 20Hz or if ui state changes if (self.frame % CarControllerParams.ACC_UI_STEP) == 0 or send_ui: - can_sends.append(fordcan.create_acc_ui_command(self.packer, main_on, CC.latActive, CS.acc_tja_status_stock_values)) + can_sends.append(fordcan.create_acc_ui_command(self.packer, main_on, CC.latActive, hud_control, CS.acc_tja_status_stock_values)) self.main_on_last = main_on self.lkas_enabled_last = CC.latActive self.steer_alert_last = steer_alert new_actuators = actuators.copy() - new_actuators.steeringAngleDeg = apply_steer + new_actuators.steeringAngleDeg = apply_angle self.frame += 1 return new_actuators, can_sends diff --git a/selfdrive/car/ford/carstate.py b/selfdrive/car/ford/carstate.py index 3c9961e9e1..a7ea19effc 100644 --- a/selfdrive/car/ford/carstate.py +++ b/selfdrive/car/ford/carstate.py @@ -3,7 +3,7 @@ from common.conversions import Conversions as CV from opendbc.can.can_define import CANDefine from opendbc.can.parser import CANParser from selfdrive.car.interfaces import CarStateBase -from selfdrive.car.ford.values import CANBUS, DBC +from selfdrive.car.ford.values import CANBUS, DBC, CarControllerParams GearShifter = car.CarState.GearShifter TransmissionType = car.CarParams.TransmissionType @@ -22,7 +22,7 @@ class CarState(CarStateBase): # car speed ret.vEgoRaw = cp.vl["EngVehicleSpThrottle2"]["Veh_V_ActlEng"] * CV.KPH_TO_MS ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.yawRate = cp.vl["Yaw_Data_FD1"]["VehYaw_W_Actl"] * CV.RAD_TO_DEG + ret.yawRate = cp.vl["Yaw_Data_FD1"]["VehYaw_W_Actl"] ret.standstill = cp.vl["DesiredTorqBrk"]["VehStop_D_Stat"] == 1 # gas pedal @@ -37,7 +37,7 @@ class CarState(CarStateBase): # steering wheel ret.steeringAngleDeg = cp.vl["SteeringPinion_Data"]["StePinComp_An_Est"] ret.steeringTorque = cp.vl["EPAS_INFO"]["SteeringColumnTorque"] - ret.steeringPressed = cp.vl["Lane_Assist_Data3_FD1"]["LaHandsOff_B_Actl"] == 0 + ret.steeringPressed = abs(ret.steeringTorque) > CarControllerParams.STEER_DRIVER_ALLOWANCE ret.steerFaultTemporary = cp.vl["EPAS_INFO"]["EPAS_Failure"] == 1 ret.steerFaultPermanent = cp.vl["EPAS_INFO"]["EPAS_Failure"] in (2, 3) # ret.espDisabled = False # TODO: find traction control signal @@ -46,6 +46,8 @@ class CarState(CarStateBase): ret.cruiseState.speed = cp.vl["EngBrakeData"]["Veh_V_DsplyCcSet"] * CV.MPH_TO_MS ret.cruiseState.enabled = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (4, 5) ret.cruiseState.available = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (3, 4, 5) + ret.cruiseState.nonAdaptive = cp.vl["Cluster_Info1_FD1"]["AccEnbl_B_RqDrv"] == 0 + ret.cruiseState.standstill = cp.vl["EngBrakeData"]["AccStopMde_D_Rq"] == 3 # gear if self.CP.transmissionType == TransmissionType.automatic: @@ -65,6 +67,7 @@ class CarState(CarStateBase): # button presses ret.leftBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 1 ret.rightBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 2 + # TODO: block this going to the camera otherwise it will enable stock TJA ret.genericToggle = bool(cp.vl["Steering_Data_FD1"]["TjaButtnOnOffPress"]) # lock info @@ -77,9 +80,13 @@ class CarState(CarStateBase): ret.leftBlindspot = cp.vl["Side_Detect_L_Stat"]["SodDetctLeft_D_Stat"] != 0 ret.rightBlindspot = cp.vl["Side_Detect_R_Stat"]["SodDetctRight_D_Stat"] != 0 + # Stock steering buttons so that we can passthru blinkers etc. + self.buttons_stock_values = cp.vl["Steering_Data_FD1"] # Stock values from IPMA so that we can retain some stock functionality self.acc_tja_status_stock_values = cp_cam.vl["ACCDATA_3"] self.lkas_status_stock_values = cp_cam.vl["IPMA_Data"] + # Use stock sensor values + self.yaw_data = cp.vl["Yaw_Data_FD1"] return ret @@ -97,6 +104,8 @@ class CarState(CarStateBase): ("Veh_V_DsplyCcSet", "EngBrakeData"), # PCM ACC set speed (mph) # The units might change with IPC settings? ("CcStat_D_Actl", "EngBrakeData"), # PCM ACC status + ("AccStopMde_D_Rq", "EngBrakeData"), # PCM ACC standstill + ("AccEnbl_B_RqDrv", "Cluster_Info1_FD1"), # PCM ACC enable ("StePinComp_An_Est", "SteeringPinion_Data"), # PSCM estimated steering angle (deg) # Calculates steering angle (and offset) from pinion # angle and driving measurements. @@ -104,7 +113,6 @@ class CarState(CarStateBase): # to zero at the beginning of the drive. ("SteeringColumnTorque", "EPAS_INFO"), # PSCM steering column torque (Nm) ("EPAS_Failure", "EPAS_INFO"), # PSCM EPAS status - ("LaHandsOff_B_Actl", "Lane_Assist_Data3_FD1"), # PSCM LKAS hands off wheel ("TurnLghtSwtch_D_Stat", "Steering_Data_FD1"), # SCCM Turn signal switch ("TjaButtnOnOffPress", "Steering_Data_FD1"), # SCCM ACC button, lane-centering/traffic jam assist toggle ("DrStatDrv_B_Actl", "BodyInfo_3_FD1"), # BCM Door open, driver @@ -112,6 +120,38 @@ class CarState(CarStateBase): ("DrStatRl_B_Actl", "BodyInfo_3_FD1"), # BCM Door open, rear left ("DrStatRr_B_Actl", "BodyInfo_3_FD1"), # BCM Door open, rear right ("FirstRowBuckleDriver", "RCMStatusMessage2_FD1"), # RCM Seatbelt status, driver + ("HeadLghtHiFlash_D_Stat", "Steering_Data_FD1"), # SCCM Passthru the remaining buttons + ("WiprFront_D_Stat", "Steering_Data_FD1"), + ("LghtAmb_D_Sns", "Steering_Data_FD1"), + ("AccButtnGapDecPress", "Steering_Data_FD1"), + ("AccButtnGapIncPress", "Steering_Data_FD1"), + ("AslButtnOnOffCnclPress", "Steering_Data_FD1"), + ("AslButtnOnOffPress", "Steering_Data_FD1"), + ("CcAslButtnCnclPress", "Steering_Data_FD1"), + ("LaSwtchPos_D_Stat", "Steering_Data_FD1"), + ("CcAslButtnCnclResPress", "Steering_Data_FD1"), + ("CcAslButtnDeny_B_Actl", "Steering_Data_FD1"), + ("CcAslButtnIndxDecPress", "Steering_Data_FD1"), + ("CcAslButtnIndxIncPress", "Steering_Data_FD1"), + ("CcAslButtnOffCnclPress", "Steering_Data_FD1"), + ("CcAslButtnOnOffCncl", "Steering_Data_FD1"), + ("CcAslButtnOnPress", "Steering_Data_FD1"), + ("CcAslButtnResDecPress", "Steering_Data_FD1"), + ("CcAslButtnResIncPress", "Steering_Data_FD1"), + ("CcAslButtnSetDecPress", "Steering_Data_FD1"), + ("CcAslButtnSetIncPress", "Steering_Data_FD1"), + ("CcAslButtnSetPress", "Steering_Data_FD1"), + ("CcAsllButtnResPress", "Steering_Data_FD1"), + ("CcButtnOffPress", "Steering_Data_FD1"), + ("CcButtnOnOffCnclPress", "Steering_Data_FD1"), + ("CcButtnOnOffPress", "Steering_Data_FD1"), + ("CcButtnOnPress", "Steering_Data_FD1"), + ("HeadLghtHiFlash_D_Actl", "Steering_Data_FD1"), + ("HeadLghtHiOn_B_StatAhb", "Steering_Data_FD1"), + ("AhbStat_B_Dsply", "Steering_Data_FD1"), + ("AccButtnGapTogglePress", "Steering_Data_FD1"), + ("WiprFrontSwtch_D_Stat", "Steering_Data_FD1"), + ("HeadLghtHiCtrl_D_RqAhb", "Steering_Data_FD1"), ] checks = [ @@ -122,6 +162,7 @@ class CarState(CarStateBase): ("EngVehicleSpThrottle", 100), ("BrakeSnData_4", 50), ("EngBrakeData", 10), + ("Cluster_Info1_FD1", 10), ("SteeringPinion_Data", 100), ("EPAS_INFO", 50), ("Lane_Assist_Data3_FD1", 33), diff --git a/selfdrive/car/ford/fordcan.py b/selfdrive/car/ford/fordcan.py index bb104aaf3c..b42561df21 100644 --- a/selfdrive/car/ford/fordcan.py +++ b/selfdrive/car/ford/fordcan.py @@ -1,7 +1,10 @@ -from common.numpy_fast import clip +from cereal import car +from selfdrive.car.ford.values import CANBUS +HUDControl = car.CarControl.HUDControl -def create_lkas_command(packer, angle_deg: float, curvature: float): + +def create_lka_command(packer, angle_deg: float, curvature: float): """ Creates a CAN message for the Ford LKAS Command. @@ -20,7 +23,7 @@ def create_lkas_command(packer, angle_deg: float, curvature: float): "LdwActvStats_D_Req": 0, # LDW status [0|7] "LdwActvIntns_D_Req": 0, # LDW intensity [0|3], shake alert strength } - return packer.make_can_msg("Lane_Assist_Data1", 0, values) + return packer.make_can_msg("Lane_Assist_Data1", CANBUS.main, values) def create_tja_command(packer, lca_rq: int, ramp_type: int, precision: int, path_offset: float, path_angle: float, curvature_rate: float, curvature: float): @@ -38,20 +41,20 @@ def create_tja_command(packer, lca_rq: int, ramp_type: int, precision: int, path """ values = { - "LatCtlRng_L_Max": 0, # Unknown [0|126] meter - "HandsOffCnfm_B_Rq": 0, # Unknown: 0=Inactive, 1=Active [0|1] - "LatCtl_D_Rq": lca_rq, # Mode: 0=None, 1=ContinuousPathFollowing, 2=InterventionLeft, 3=InterventionRight, 4-7=NotUsed [0|7] - "LatCtlRampType_D_Rq": ramp_type, # Ramp speed: 0=Slow, 1=Medium, 2=Fast, 3=Immediate [0|3] - "LatCtlPrecision_D_Rq": precision, # Precision: 0=Comfortable, 1=Precise, 2/3=NotUsed [0|3] - "LatCtlPathOffst_L_Actl": clip(path_offset, -5.12, 5.11), # Path offset [-5.12|5.11] meter - "LatCtlPath_An_Actl": clip(path_angle, -0.5, 0.5235), # Path angle [-0.5|0.5235] radians - "LatCtlCurv_NoRate_Actl": clip(curvature_rate, -0.001024, 0.00102375), # Curvature rate [-0.001024|0.00102375] 1/meter^2 - "LatCtlCurv_No_Actl": clip(curvature, -0.02, 0.02094), # Curvature [-0.02|0.02094] 1/meter + "LatCtlRng_L_Max": 0, # Unknown [0|126] meter + "HandsOffCnfm_B_Rq": 0, # Unknown: 0=Inactive, 1=Active [0|1] + "LatCtl_D_Rq": lca_rq, # Mode: 0=None, 1=ContinuousPathFollowing, 2=InterventionLeft, 3=InterventionRight, 4-7=NotUsed [0|7] + "LatCtlRampType_D_Rq": ramp_type, # Ramp speed: 0=Slow, 1=Medium, 2=Fast, 3=Immediate [0|3] + "LatCtlPrecision_D_Rq": precision, # Precision: 0=Comfortable, 1=Precise, 2/3=NotUsed [0|3] + "LatCtlPathOffst_L_Actl": path_offset, # Path offset [-5.12|5.11] meter + "LatCtlPath_An_Actl": path_angle, # Path angle [-0.4995|0.5240] radians + "LatCtlCurv_NoRate_Actl": curvature_rate, # Curvature rate [-0.001024|0.00102375] 1/meter^2 + "LatCtlCurv_No_Actl": curvature, # Curvature [-0.02|0.02094] 1/meter } - return packer.make_can_msg("LateralMotionControl", 0, values) + return packer.make_can_msg("LateralMotionControl", CANBUS.main, values) -def create_lkas_ui_command(packer, main_on: bool, enabled: bool, steer_alert: bool, stock_values: dict): +def create_lkas_ui_command(packer, main_on: bool, enabled: bool, steer_alert: bool, hud_control, stock_values: dict): """ Creates a CAN message for the Ford IPC IPMA/LKAS status. @@ -63,23 +66,47 @@ def create_lkas_ui_command(packer, main_on: bool, enabled: bool, steer_alert: bo """ # LaActvStats_D_Dsply - # TODO: get LDW state from OP + # R Intvn Warn Supprs Avail No + # L + # Intvn 24 19 14 9 4 + # Warn 23 18 13 8 3 + # Supprs 22 17 12 7 2 + # Avail 21 16 11 6 1 + # No 20 15 10 5 0 + # + # TODO: test suppress state if enabled: - lines = 6 + lines = 0 # NoLeft_NoRight + if hud_control.leftLaneDepart: + lines += 4 + elif hud_control.leftLaneVisible: + lines += 1 + if hud_control.rightLaneDepart: + lines += 20 + elif hud_control.rightLaneVisible: + lines += 5 elif main_on: lines = 0 else: - lines = 30 + if hud_control.leftLaneDepart: + lines = 3 # WarnLeft_NoRight + elif hud_control.rightLaneDepart: + lines = 15 # NoLeft_WarnRight + else: + lines = 30 # LA_Off + + # TODO: use level 1 for no sound when less severe? + hands_on_wheel_dsply = 2 if steer_alert else 0 values = { **stock_values, "LaActvStats_D_Dsply": lines, # LKAS status (lines) [0|31] - "LaHandsOff_D_Dsply": 2 if steer_alert else 0, # 0=HandsOn, 1=Level1 (w/o chime), 2=Level2 (w/ chime), 3=Suppressed + "LaHandsOff_D_Dsply": hands_on_wheel_dsply, # 0=HandsOn, 1=Level1 (w/o chime), 2=Level2 (w/ chime), 3=Suppressed } - return packer.make_can_msg("IPMA_Data", 0, values) + return packer.make_can_msg("IPMA_Data", CANBUS.main, values) -def create_acc_ui_command(packer, main_on: bool, enabled: bool, stock_values: dict): +def create_acc_ui_command(packer, main_on: bool, enabled: bool, hud_control, stock_values: dict): """ Creates a CAN message for the Ford IPC adaptive cruise, forward collision warning and traffic jam assist status. @@ -89,14 +116,32 @@ def create_acc_ui_command(packer, main_on: bool, enabled: bool, stock_values: di Frequency is 20Hz. """ + # Tja_D_Stat + if enabled: + if hud_control.leftLaneDepart: + status = 3 # ActiveInterventionLeft + elif hud_control.rightLaneDepart: + status = 4 # ActiveInterventionRight + else: + status = 2 # Active + elif main_on: + if hud_control.leftLaneDepart: + status = 5 # ActiveWarningLeft + elif hud_control.rightLaneDepart: + status = 6 # ActiveWarningRight + else: + status = 1 # Standby + else: + status = 0 # Off + values = { **stock_values, - "Tja_D_Stat": 2 if enabled else (1 if main_on else 0), # TJA status: 0=Off, 1=Standby, 2=Active, 3=InterventionLeft, 4=InterventionRight, 5=WarningLeft, 6=WarningRight, 7=NotUsed [0|7] + "Tja_D_Stat": status, } - return packer.make_can_msg("ACCDATA_3", 0, values) + return packer.make_can_msg("ACCDATA_3", CANBUS.main, values) -def spam_cancel_button(packer, cancel=1): +def create_button_command(packer, stock_values: dict, cancel = False, resume = False, tja_toggle = False, bus = CANBUS.camera): """ Creates a CAN message for the Ford SCCM buttons/switches. @@ -104,6 +149,9 @@ def spam_cancel_button(packer, cancel=1): """ values = { - "CcAslButtnCnclPress": cancel, # CC cancel button + **stock_values, + "CcAslButtnCnclPress": 1 if cancel else 0, # CC cancel button + "CcAsllButtnResPress": 1 if resume else 0, # CC resume button + "TjaButtnOnOffPress": 1 if tja_toggle else 0, # TJA toggle button } - return packer.make_can_msg("Steering_Data_FD1", 0, values) + return packer.make_can_msg("Steering_Data_FD1", bus, values) diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py index 271b347148..7d4c9eb94c 100644 --- a/selfdrive/car/ford/interface.py +++ b/selfdrive/car/ford/interface.py @@ -1,8 +1,8 @@ #!/usr/bin/env python3 from cereal import car from common.conversions import Conversions as CV -from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint -from selfdrive.car.ford.values import CAR, TransmissionType, GearShifter +from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config +from selfdrive.car.ford.values import CAR, Ecu, TransmissionType, GearShifter from selfdrive.car.interfaces import CarInterfaceBase @@ -12,59 +12,59 @@ EventName = car.CarEvent.EventName class CarInterface(CarInterfaceBase): @staticmethod def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False): + if car_fw is None: + car_fw = [] + ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "ford" - #ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.ford)] ret.dashcamOnly = True + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.ford)] # Angle-based steering - # TODO: use curvature control when ready ret.steerControlType = car.CarParams.SteerControlType.angle - ret.steerActuatorDelay = 0.1 + ret.steerActuatorDelay = 0.4 ret.steerLimitTimer = 1.0 - - # TODO: detect stop-and-go vehicles - stop_and_go = False + tire_stiffness_factor = 1.0 if candidate == CAR.ESCAPE_MK4: ret.wheelbase = 2.71 ret.steerRatio = 14.3 # Copied from Focus - tire_stiffness_factor = 0.5328 # Copied from Focus ret.mass = 1750 + STD_CARGO_KG + elif candidate == CAR.EXPLORER_MK6: + ret.wheelbase = 3.025 + ret.steerRatio = 16.8 # learned + ret.mass = 2050 + STD_CARGO_KG + elif candidate == CAR.FOCUS_MK4: ret.wheelbase = 2.7 - ret.steerRatio = 14.3 - tire_stiffness_factor = 0.5328 + ret.steerRatio = 13.8 # learned ret.mass = 1350 + STD_CARGO_KG else: raise ValueError(f"Unsupported car: ${candidate}") - # Auto Transmission: Gear_Shift_by_Wire_FD1 - # TODO: detect transmission in car_fw? - if 0x5A in fingerprint[0]: + # Auto Transmission: 0x732 ECU or Gear_Shift_by_Wire_FD1 + found_ecus = [fw.ecu for fw in car_fw] + if Ecu.shiftByWire in found_ecus or 0x5A in fingerprint[0]: ret.transmissionType = TransmissionType.automatic else: ret.transmissionType = TransmissionType.manual + ret.minEnableSpeed = 20.0 * CV.MPH_TO_MS # BSM: Side_Detect_L_Stat, Side_Detect_R_Stat # TODO: detect bsm in car_fw? ret.enableBsm = 0x3A6 in fingerprint[0] and 0x3A7 in fingerprint[0] - # min speed to enable ACC. if car can do stop and go, then set enabling speed - # to a negative value, so it won't matter. - ret.minEnableSpeed = -1. if (stop_and_go) else 20. * CV.MPH_TO_MS # LCA can steer down to zero ret.minSteerSpeed = 0. - ret.centerToFront = ret.wheelbase * 0.44 - + ret.autoResumeSng = ret.minEnableSpeed == -1. ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) + ret.centerToFront = ret.wheelbase * 0.44 ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, tire_stiffness_factor=tire_stiffness_factor) - return ret def _update(self, c): diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index 2624fd2524..54ff043a33 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -1,9 +1,11 @@ from collections import namedtuple +from dataclasses import dataclass +from enum import Enum from typing import Dict, List, Union from cereal import car from selfdrive.car import dbc_dict -from selfdrive.car.docs_definitions import CarInfo +from selfdrive.car.docs_definitions import CarInfo, Harness Ecu = car.CarParams.Ecu TransmissionType = car.CarParams.TransmissionType @@ -20,8 +22,11 @@ class CarControllerParams: # Message: ACCDATA_3 ACC_UI_STEP = 5 - STEER_RATE_LIMIT_UP = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., .8, .15]) - STEER_RATE_LIMIT_DOWN = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., 3.5, 0.4]) + STEER_RATIO = 2.75 + STEER_DRIVER_ALLOWANCE = 0.8 + + RATE_LIMIT_UP = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., .8, .15]) + RATE_LIMIT_DOWN = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., 3.5, 0.4]) class RADAR: @@ -37,12 +42,23 @@ class CANBUS: class CAR: ESCAPE_MK4 = "FORD ESCAPE 4TH GEN" + EXPLORER_MK6 = "FORD EXPLORER 6TH GEN" FOCUS_MK4 = "FORD FOCUS 4TH GEN" +@dataclass +class FordCarInfo(CarInfo): + package: str = "Co-Pilot360 Assist+" + harness: Enum = Harness.ford_q3 + + CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { - CAR.ESCAPE_MK4: CarInfo("Ford Escape", "NA"), - CAR.FOCUS_MK4: CarInfo("Ford Focus", "NA"), + CAR.ESCAPE_MK4: [ + FordCarInfo("Ford Escape 2020"), + FordCarInfo("Ford Kuga EU", "Driver Assistance Pack"), + ], + CAR.EXPLORER_MK6: FordCarInfo("Ford Explorer 2020-21"), + CAR.FOCUS_MK4: FordCarInfo("Ford Focus EU 2019", "Driver Assistance Pack"), } @@ -63,6 +79,33 @@ FW_VERSIONS = { (Ecu.engine, 0x7E0, None): [ b'LX6A-14C204-ESG\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], + (Ecu.shiftByWire, 0x732, None): [ + ], + }, + CAR.EXPLORER_MK6: { + (Ecu.eps, 0x730, None): [ + b'L1MC-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'L1MC-2D053-BB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-BF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'LB5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LB5T-14F397-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7E0, None): [ + b'LB5A-14C204-EAC\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'MB5A-14C204-MD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.shiftByWire, 0x732, None): [ + b'L1MP-14G395-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MP-14G395-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], }, CAR.FOCUS_MK4: { (Ecu.eps, 0x730, None): [ @@ -80,11 +123,14 @@ FW_VERSIONS = { (Ecu.engine, 0x7E0, None): [ b'JX6A-14C204-BPL\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], + (Ecu.shiftByWire, 0x732, None): [ + ], }, } DBC = { CAR.ESCAPE_MK4: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR), + CAR.EXPLORER_MK6: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR), CAR.FOCUS_MK4: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR), } diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index e6faa0e950..376a743dfb 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -240,7 +240,7 @@ REQUESTS: List[Request] = [ [TESTER_PRESENT_REQUEST, FORD_VERSION_REQUEST], [TESTER_PRESENT_RESPONSE, FORD_VERSION_RESPONSE], bus=0, - whitelist_ecus=[Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera], + whitelist_ecus=[Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.shiftByWire], ), ] diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index b769cbe5f7..635f43cc8d 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -41,6 +41,7 @@ routes = [ CarTestRoute("221c253375af4ee9|2022-06-15--18-38-24", CHRYSLER.RAM_1500), CarTestRoute("8fb5eabf914632ae|2022-08-04--17-28-53", CHRYSLER.RAM_HD, segment=6), + CarTestRoute("62241b0c7fea4589|2022-09-01--15-32-49", FORD.EXPLORER_MK6), #TestRoute("f1b4c567731f4a1b|2018-04-30--10-15-35", FORD.FUSION), CarTestRoute("7cc2a8365b4dd8a9|2018-12-02--12-10-44", GM.ACADIA), diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index 14ee7e2239..fcc762c2b8 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -13,6 +13,7 @@ TESLA AP2 MODEL S: [.nan, 2.5, .nan] # Guess FORD ESCAPE 4TH GEN: [.nan, 1.5, .nan] +FORD EXPLORER 6TH GEN: [.nan, 1.5, .nan] FORD FOCUS 4TH GEN: [.nan, 1.5, .nan] ### From 69e9b285b3e125e319aedc9b587e4da44adb9913 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 9 Sep 2022 06:53:23 +0800 Subject: [PATCH 058/152] UI/map: remove redundant QString ctor (#25704) --- selfdrive/ui/qt/maps/map.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc index 046814d517..71706fd35e 100644 --- a/selfdrive/ui/qt/maps/map.cc +++ b/selfdrive/ui/qt/maps/map.cc @@ -486,9 +486,9 @@ void MapInstructions::updateInstructions(cereal::NavInstruction::Reader instruct // for rhd, reflect direction and then flip if (is_rhd) { if (fn.contains("left")) { - fn.replace(QString("left"), QString("right")); + fn.replace("left", "right"); } else if (fn.contains("right")) { - fn.replace(QString("right"), QString("left")); + fn.replace("right", "left"); } } From 9fb2c40cfdd5a4c05c65e90c7d91a2afd267e26b Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Thu, 8 Sep 2022 15:54:14 -0700 Subject: [PATCH 059/152] bump catch2 headers to v2.13.9 (#25678) --- third_party/catch2/include/catch2/catch.hpp | 705 +++++++++++------- .../catch2/catch_reporter_automake.hpp | 124 +-- .../catch2/catch_reporter_sonarqube.hpp | 360 ++++----- .../include/catch2/catch_reporter_tap.hpp | 508 ++++++------- .../catch2/catch_reporter_teamcity.hpp | 438 +++++------ 5 files changed, 1153 insertions(+), 982 deletions(-) diff --git a/third_party/catch2/include/catch2/catch.hpp b/third_party/catch2/include/catch2/catch.hpp index cf1fae15aa..d2a12427b2 100644 --- a/third_party/catch2/include/catch2/catch.hpp +++ b/third_party/catch2/include/catch2/catch.hpp @@ -1,9 +1,9 @@ /* - * Catch v2.13.0 - * Generated: 2020-07-12 20:07:49.015950 + * Catch v2.13.9 + * Generated: 2022-04-12 22:37:23.260201 * ---------------------------------------------------------- * This file has been merged from multiple headers. Please don't edit it directly - * Copyright (c) 2020 Two Blue Cubes Ltd. All rights reserved. + * Copyright (c) 2022 Two Blue Cubes Ltd. All rights reserved. * * Distributed under the Boost Software License, Version 1.0. (See accompanying * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) @@ -15,7 +15,7 @@ #define CATCH_VERSION_MAJOR 2 #define CATCH_VERSION_MINOR 13 -#define CATCH_VERSION_PATCH 0 +#define CATCH_VERSION_PATCH 9 #ifdef __clang__ # pragma clang system_header @@ -66,13 +66,16 @@ #if !defined(CATCH_CONFIG_IMPL_ONLY) // start catch_platform.h +// See e.g.: +// https://opensource.apple.com/source/CarbonHeaders/CarbonHeaders-18.1/TargetConditionals.h.auto.html #ifdef __APPLE__ -# include -# if TARGET_OS_OSX == 1 -# define CATCH_PLATFORM_MAC -# elif TARGET_OS_IPHONE == 1 -# define CATCH_PLATFORM_IPHONE -# endif +# include +# if (defined(TARGET_OS_OSX) && TARGET_OS_OSX == 1) || \ + (defined(TARGET_OS_MAC) && TARGET_OS_MAC == 1) +# define CATCH_PLATFORM_MAC +# elif (defined(TARGET_OS_IPHONE) && TARGET_OS_IPHONE == 1) +# define CATCH_PLATFORM_IPHONE +# endif #elif defined(linux) || defined(__linux) || defined(__linux__) # define CATCH_PLATFORM_LINUX @@ -132,13 +135,9 @@ namespace Catch { #endif -#if defined(__cpp_lib_uncaught_exceptions) -# define CATCH_INTERNAL_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS -#endif - -// We have to avoid both ICC and Clang, because they try to mask themselves -// as gcc, and we want only GCC in this block -#if defined(__GNUC__) && !defined(__clang__) && !defined(__ICC) +// Only GCC compiler should be used in this block, so other compilers trying to +// mask themselves as GCC should be ignored. +#if defined(__GNUC__) && !defined(__clang__) && !defined(__ICC) && !defined(__CUDACC__) && !defined(__LCC__) # define CATCH_INTERNAL_START_WARNINGS_SUPPRESSION _Pragma( "GCC diagnostic push" ) # define CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION _Pragma( "GCC diagnostic pop" ) @@ -162,7 +161,7 @@ namespace Catch { // ``` // // Therefore, `CATCH_INTERNAL_IGNORE_BUT_WARN` is not implemented. -# if !defined(__ibmxl__) +# if !defined(__ibmxl__) && !defined(__CUDACC__) # define CATCH_INTERNAL_IGNORE_BUT_WARN(...) (void)__builtin_constant_p(__VA_ARGS__) /* NOLINT(cppcoreguidelines-pro-type-vararg, hicpp-vararg) */ # endif @@ -241,13 +240,6 @@ namespace Catch { // Visual C++ #if defined(_MSC_VER) -# define CATCH_INTERNAL_START_WARNINGS_SUPPRESSION __pragma( warning(push) ) -# define CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION __pragma( warning(pop) ) - -# if _MSC_VER >= 1900 // Visual Studio 2015 or newer -# define CATCH_INTERNAL_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS -# endif - // Universal Windows platform does not support SEH // Or console colours (or console at all...) # if defined(WINAPI_FAMILY) && (WINAPI_FAMILY == WINAPI_FAMILY_APP) @@ -256,13 +248,18 @@ namespace Catch { # define CATCH_INTERNAL_CONFIG_WINDOWS_SEH # endif +# if !defined(__clang__) // Handle Clang masquerading for msvc + // MSVC traditional preprocessor needs some workaround for __VA_ARGS__ // _MSVC_TRADITIONAL == 0 means new conformant preprocessor // _MSVC_TRADITIONAL == 1 means old traditional non-conformant preprocessor -# if !defined(__clang__) // Handle Clang masquerading for msvc # if !defined(_MSVC_TRADITIONAL) || (defined(_MSVC_TRADITIONAL) && _MSVC_TRADITIONAL) # define CATCH_INTERNAL_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR # endif // MSVC_TRADITIONAL + +// Only do this if we're not using clang on Windows, which uses `diagnostic push` & `diagnostic pop` +# define CATCH_INTERNAL_START_WARNINGS_SUPPRESSION __pragma( warning(push) ) +# define CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION __pragma( warning(pop) ) # endif // __clang__ #endif // _MSC_VER @@ -330,7 +327,10 @@ namespace Catch { // Check if byte is available and usable # if __has_include() && defined(CATCH_CPP17_OR_GREATER) - # define CATCH_INTERNAL_CONFIG_CPP17_BYTE + # include + # if defined(__cpp_lib_byte) && (__cpp_lib_byte > 0) + # define CATCH_INTERNAL_CONFIG_CPP17_BYTE + # endif # endif // __has_include() && defined(CATCH_CPP17_OR_GREATER) // Check if variant is available and usable @@ -373,10 +373,6 @@ namespace Catch { # define CATCH_CONFIG_CPP17_OPTIONAL #endif -#if defined(CATCH_INTERNAL_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS) && !defined(CATCH_CONFIG_NO_CPP17_UNCAUGHT_EXCEPTIONS) && !defined(CATCH_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS) -# define CATCH_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS -#endif - #if defined(CATCH_INTERNAL_CONFIG_CPP17_STRING_VIEW) && !defined(CATCH_CONFIG_NO_CPP17_STRING_VIEW) && !defined(CATCH_CONFIG_CPP17_STRING_VIEW) # define CATCH_CONFIG_CPP17_STRING_VIEW #endif @@ -1016,34 +1012,34 @@ struct AutoReg : NonCopyable { #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION(Name, Tags, ...) \ - INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), Name, Tags, typename TestType, __VA_ARGS__ ) + INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, typename TestType, __VA_ARGS__ ) #else #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION(Name, Tags, ...) \ - INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), Name, Tags, typename TestType, __VA_ARGS__ ) ) + INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, typename TestType, __VA_ARGS__ ) ) #endif #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_SIG_NO_REGISTRATION(Name, Tags, Signature, ...) \ - INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), Name, Tags, Signature, __VA_ARGS__ ) + INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, Signature, __VA_ARGS__ ) #else #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_SIG_NO_REGISTRATION(Name, Tags, Signature, ...) \ - INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), Name, Tags, Signature, __VA_ARGS__ ) ) + INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, Signature, __VA_ARGS__ ) ) #endif #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION( ClassName, Name, Tags,... ) \ - INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____C_L_A_S_S____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ) , ClassName, Name, Tags, typename T, __VA_ARGS__ ) + INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, typename T, __VA_ARGS__ ) #else #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION( ClassName, Name, Tags,... ) \ - INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____C_L_A_S_S____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ) , ClassName, Name, Tags, typename T, __VA_ARGS__ ) ) + INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, typename T, __VA_ARGS__ ) ) #endif #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_SIG_NO_REGISTRATION( ClassName, Name, Tags, Signature, ... ) \ - INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____C_L_A_S_S____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ) , ClassName, Name, Tags, Signature, __VA_ARGS__ ) + INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, Signature, __VA_ARGS__ ) #else #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_SIG_NO_REGISTRATION( ClassName, Name, Tags, Signature, ... ) \ - INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____C_L_A_S_S____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ) , ClassName, Name, Tags, Signature, __VA_ARGS__ ) ) + INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, Signature, __VA_ARGS__ ) ) #endif #endif @@ -1056,7 +1052,7 @@ struct AutoReg : NonCopyable { CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION \ static void TestName() #define INTERNAL_CATCH_TESTCASE( ... ) \ - INTERNAL_CATCH_TESTCASE2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), __VA_ARGS__ ) + INTERNAL_CATCH_TESTCASE2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_S_T_ ), __VA_ARGS__ ) /////////////////////////////////////////////////////////////////////////////// #define INTERNAL_CATCH_METHOD_AS_TEST_CASE( QualifiedMethod, ... ) \ @@ -1078,7 +1074,7 @@ struct AutoReg : NonCopyable { CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION \ void TestName::test() #define INTERNAL_CATCH_TEST_CASE_METHOD( ClassName, ... ) \ - INTERNAL_CATCH_TEST_CASE_METHOD2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), ClassName, __VA_ARGS__ ) + INTERNAL_CATCH_TEST_CASE_METHOD2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_S_T_ ), ClassName, __VA_ARGS__ ) /////////////////////////////////////////////////////////////////////////////// #define INTERNAL_CATCH_REGISTER_TESTCASE( Function, ... ) \ @@ -1105,7 +1101,7 @@ struct AutoReg : NonCopyable { int index = 0; \ constexpr char const* tmpl_types[] = {CATCH_REC_LIST(INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS, __VA_ARGS__)};\ using expander = int[];\ - (void)expander{(reg_test(Types{}, Catch::NameAndTags{ Name " - " + std::string(tmpl_types[index]), Tags } ), index++, 0)... };/* NOLINT */ \ + (void)expander{(reg_test(Types{}, Catch::NameAndTags{ Name " - " + std::string(tmpl_types[index]), Tags } ), index++)... };/* NOLINT */ \ }\ };\ static int INTERNAL_CATCH_UNIQUE_NAME( globalRegistrar ) = [](){\ @@ -1119,18 +1115,18 @@ struct AutoReg : NonCopyable { #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR #define INTERNAL_CATCH_TEMPLATE_TEST_CASE(Name, Tags, ...) \ - INTERNAL_CATCH_TEMPLATE_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), Name, Tags, typename TestType, __VA_ARGS__ ) + INTERNAL_CATCH_TEMPLATE_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, typename TestType, __VA_ARGS__ ) #else #define INTERNAL_CATCH_TEMPLATE_TEST_CASE(Name, Tags, ...) \ - INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), Name, Tags, typename TestType, __VA_ARGS__ ) ) + INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, typename TestType, __VA_ARGS__ ) ) #endif #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_SIG(Name, Tags, Signature, ...) \ - INTERNAL_CATCH_TEMPLATE_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), Name, Tags, Signature, __VA_ARGS__ ) + INTERNAL_CATCH_TEMPLATE_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, Signature, __VA_ARGS__ ) #else #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_SIG(Name, Tags, Signature, ...) \ - INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), Name, Tags, Signature, __VA_ARGS__ ) ) + INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, Signature, __VA_ARGS__ ) ) #endif #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE2(TestName, TestFuncName, Name, Tags, Signature, TmplTypes, TypesList) \ @@ -1151,7 +1147,7 @@ struct AutoReg : NonCopyable { constexpr char const* tmpl_types[] = {CATCH_REC_LIST(INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS, INTERNAL_CATCH_REMOVE_PARENS(TmplTypes))};\ constexpr char const* types_list[] = {CATCH_REC_LIST(INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS, INTERNAL_CATCH_REMOVE_PARENS(TypesList))};\ constexpr auto num_types = sizeof(types_list) / sizeof(types_list[0]);\ - (void)expander{(Catch::AutoReg( Catch::makeTestInvoker( &TestFuncName ), CATCH_INTERNAL_LINEINFO, Catch::StringRef(), Catch::NameAndTags{ Name " - " + std::string(tmpl_types[index / num_types]) + "<" + std::string(types_list[index % num_types]) + ">", Tags } ), index++, 0)... };/* NOLINT */\ + (void)expander{(Catch::AutoReg( Catch::makeTestInvoker( &TestFuncName ), CATCH_INTERNAL_LINEINFO, Catch::StringRef(), Catch::NameAndTags{ Name " - " + std::string(tmpl_types[index / num_types]) + "<" + std::string(types_list[index % num_types]) + ">", Tags } ), index++)... };/* NOLINT */\ } \ }; \ static int INTERNAL_CATCH_UNIQUE_NAME( globalRegistrar ) = [](){ \ @@ -1168,18 +1164,18 @@ struct AutoReg : NonCopyable { #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE(Name, Tags, ...)\ - INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE2(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), Name, Tags, typename T,__VA_ARGS__) + INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE2(INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, typename T,__VA_ARGS__) #else #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE(Name, Tags, ...)\ - INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), Name, Tags, typename T, __VA_ARGS__ ) ) + INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, typename T, __VA_ARGS__ ) ) #endif #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_SIG(Name, Tags, Signature, ...)\ - INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE2(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), Name, Tags, Signature, __VA_ARGS__) + INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE2(INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, Signature, __VA_ARGS__) #else #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_SIG(Name, Tags, Signature, ...)\ - INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), Name, Tags, Signature, __VA_ARGS__ ) ) + INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, Signature, __VA_ARGS__ ) ) #endif #define INTERNAL_CATCH_TEMPLATE_LIST_TEST_CASE_2(TestName, TestFunc, Name, Tags, TmplList)\ @@ -1195,7 +1191,7 @@ struct AutoReg : NonCopyable { void reg_tests() { \ int index = 0; \ using expander = int[]; \ - (void)expander{(Catch::AutoReg( Catch::makeTestInvoker( &TestFunc ), CATCH_INTERNAL_LINEINFO, Catch::StringRef(), Catch::NameAndTags{ Name " - " + std::string(INTERNAL_CATCH_STRINGIZE(TmplList)) + " - " + std::to_string(index), Tags } ), index++, 0)... };/* NOLINT */\ + (void)expander{(Catch::AutoReg( Catch::makeTestInvoker( &TestFunc ), CATCH_INTERNAL_LINEINFO, Catch::StringRef(), Catch::NameAndTags{ Name " - " + std::string(INTERNAL_CATCH_STRINGIZE(TmplList)) + " - " + std::to_string(index), Tags } ), index++)... };/* NOLINT */\ } \ };\ static int INTERNAL_CATCH_UNIQUE_NAME( globalRegistrar ) = [](){ \ @@ -1210,7 +1206,7 @@ struct AutoReg : NonCopyable { static void TestFunc() #define INTERNAL_CATCH_TEMPLATE_LIST_TEST_CASE(Name, Tags, TmplList) \ - INTERNAL_CATCH_TEMPLATE_LIST_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), Name, Tags, TmplList ) + INTERNAL_CATCH_TEMPLATE_LIST_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, TmplList ) #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( TestNameClass, TestName, ClassName, Name, Tags, Signature, ... ) \ CATCH_INTERNAL_START_WARNINGS_SUPPRESSION \ @@ -1229,7 +1225,7 @@ struct AutoReg : NonCopyable { int index = 0; \ constexpr char const* tmpl_types[] = {CATCH_REC_LIST(INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS, __VA_ARGS__)};\ using expander = int[];\ - (void)expander{(reg_test(Types{}, #ClassName, Catch::NameAndTags{ Name " - " + std::string(tmpl_types[index]), Tags } ), index++, 0)... };/* NOLINT */ \ + (void)expander{(reg_test(Types{}, #ClassName, Catch::NameAndTags{ Name " - " + std::string(tmpl_types[index]), Tags } ), index++)... };/* NOLINT */ \ }\ };\ static int INTERNAL_CATCH_UNIQUE_NAME( globalRegistrar ) = [](){\ @@ -1243,18 +1239,18 @@ struct AutoReg : NonCopyable { #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD( ClassName, Name, Tags,... ) \ - INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____C_L_A_S_S____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ) , ClassName, Name, Tags, typename T, __VA_ARGS__ ) + INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, typename T, __VA_ARGS__ ) #else #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD( ClassName, Name, Tags,... ) \ - INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____C_L_A_S_S____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ) , ClassName, Name, Tags, typename T, __VA_ARGS__ ) ) + INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, typename T, __VA_ARGS__ ) ) #endif #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_SIG( ClassName, Name, Tags, Signature, ... ) \ - INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____C_L_A_S_S____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ) , ClassName, Name, Tags, Signature, __VA_ARGS__ ) + INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, Signature, __VA_ARGS__ ) #else #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_SIG( ClassName, Name, Tags, Signature, ... ) \ - INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____C_L_A_S_S____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ) , ClassName, Name, Tags, Signature, __VA_ARGS__ ) ) + INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, Signature, __VA_ARGS__ ) ) #endif #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_2(TestNameClass, TestName, ClassName, Name, Tags, Signature, TmplTypes, TypesList)\ @@ -1278,7 +1274,7 @@ struct AutoReg : NonCopyable { constexpr char const* tmpl_types[] = {CATCH_REC_LIST(INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS, INTERNAL_CATCH_REMOVE_PARENS(TmplTypes))};\ constexpr char const* types_list[] = {CATCH_REC_LIST(INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS, INTERNAL_CATCH_REMOVE_PARENS(TypesList))};\ constexpr auto num_types = sizeof(types_list) / sizeof(types_list[0]);\ - (void)expander{(Catch::AutoReg( Catch::makeTestInvoker( &TestName::test ), CATCH_INTERNAL_LINEINFO, #ClassName, Catch::NameAndTags{ Name " - " + std::string(tmpl_types[index / num_types]) + "<" + std::string(types_list[index % num_types]) + ">", Tags } ), index++, 0)... };/* NOLINT */ \ + (void)expander{(Catch::AutoReg( Catch::makeTestInvoker( &TestName::test ), CATCH_INTERNAL_LINEINFO, #ClassName, Catch::NameAndTags{ Name " - " + std::string(tmpl_types[index / num_types]) + "<" + std::string(types_list[index % num_types]) + ">", Tags } ), index++)... };/* NOLINT */ \ }\ };\ static int INTERNAL_CATCH_UNIQUE_NAME( globalRegistrar ) = [](){\ @@ -1295,18 +1291,18 @@ struct AutoReg : NonCopyable { #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD( ClassName, Name, Tags, ... )\ - INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), ClassName, Name, Tags, typename T, __VA_ARGS__ ) + INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), ClassName, Name, Tags, typename T, __VA_ARGS__ ) #else #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD( ClassName, Name, Tags, ... )\ - INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), ClassName, Name, Tags, typename T,__VA_ARGS__ ) ) + INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), ClassName, Name, Tags, typename T,__VA_ARGS__ ) ) #endif #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_SIG( ClassName, Name, Tags, Signature, ... )\ - INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), ClassName, Name, Tags, Signature, __VA_ARGS__ ) + INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), ClassName, Name, Tags, Signature, __VA_ARGS__ ) #else #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_SIG( ClassName, Name, Tags, Signature, ... )\ - INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), ClassName, Name, Tags, Signature,__VA_ARGS__ ) ) + INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), ClassName, Name, Tags, Signature,__VA_ARGS__ ) ) #endif #define INTERNAL_CATCH_TEMPLATE_LIST_TEST_CASE_METHOD_2( TestNameClass, TestName, ClassName, Name, Tags, TmplList) \ @@ -1325,7 +1321,7 @@ struct AutoReg : NonCopyable { void reg_tests(){\ int index = 0;\ using expander = int[];\ - (void)expander{(Catch::AutoReg( Catch::makeTestInvoker( &TestName::test ), CATCH_INTERNAL_LINEINFO, #ClassName, Catch::NameAndTags{ Name " - " + std::string(INTERNAL_CATCH_STRINGIZE(TmplList)) + " - " + std::to_string(index), Tags } ), index++, 0)... };/* NOLINT */ \ + (void)expander{(Catch::AutoReg( Catch::makeTestInvoker( &TestName::test ), CATCH_INTERNAL_LINEINFO, #ClassName, Catch::NameAndTags{ Name " - " + std::string(INTERNAL_CATCH_STRINGIZE(TmplList)) + " - " + std::to_string(index), Tags } ), index++)... };/* NOLINT */ \ }\ };\ static int INTERNAL_CATCH_UNIQUE_NAME( globalRegistrar ) = [](){\ @@ -1340,7 +1336,7 @@ struct AutoReg : NonCopyable { void TestName::test() #define INTERNAL_CATCH_TEMPLATE_LIST_TEST_CASE_METHOD(ClassName, Name, Tags, TmplList) \ - INTERNAL_CATCH_TEMPLATE_LIST_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), ClassName, Name, Tags, TmplList ) + INTERNAL_CATCH_TEMPLATE_LIST_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), ClassName, Name, Tags, TmplList ) // end catch_test_registry.h // start catch_capture.hpp @@ -1829,8 +1825,8 @@ namespace Catch { #endif namespace Detail { - template - std::string rangeToString(InputIterator first, InputIterator last) { + template + std::string rangeToString(InputIterator first, Sentinel last) { ReusableStringStream rss; rss << "{ "; if (first != last) { @@ -3097,7 +3093,7 @@ namespace Detail { Approx operator-() const; template ::value>::type> - Approx operator()( T const& value ) { + Approx operator()( T const& value ) const { Approx approx( static_cast(value) ); approx.m_epsilon = m_epsilon; approx.m_margin = m_margin; @@ -4169,7 +4165,7 @@ namespace Generators { if (!m_predicate(m_generator.get())) { // It might happen that there are no values that pass the // filter. In that case we throw an exception. - auto has_initial_value = next(); + auto has_initial_value = nextImpl(); if (!has_initial_value) { Catch::throw_exception(GeneratorException("No valid value found in filtered generator")); } @@ -4181,6 +4177,11 @@ namespace Generators { } bool next() override { + return nextImpl(); + } + + private: + bool nextImpl() { bool success = m_generator.next(); if (!success) { return false; @@ -5464,6 +5465,8 @@ namespace Catch { } // namespace Catch // end catch_outlier_classification.hpp + +#include #endif // CATCH_CONFIG_ENABLE_BENCHMARKING #include @@ -6348,9 +6351,10 @@ namespace Catch { void writeTestCase(TestCaseNode const& testCaseNode); - void writeSection(std::string const& className, - std::string const& rootName, - SectionNode const& sectionNode); + void writeSection( std::string const& className, + std::string const& rootName, + SectionNode const& sectionNode, + bool testOkToFail ); void writeAssertions(SectionNode const& sectionNode); void writeAssertion(AssertionStats const& stats); @@ -6885,7 +6889,7 @@ namespace Catch { } iters *= 2; } - throw optimized_away_error{}; + Catch::throw_exception(optimized_away_error{}); } } // namespace Detail } // namespace Benchmark @@ -6893,6 +6897,7 @@ namespace Catch { // end catch_run_for_at_least.hpp #include +#include namespace Catch { namespace Benchmark { @@ -7063,8 +7068,8 @@ namespace Catch { double b2 = bias - z1; double a1 = a(b1); double a2 = a(b2); - auto lo = std::max(cumn(a1), 0); - auto hi = std::min(cumn(a2), n - 1); + auto lo = (std::max)(cumn(a1), 0); + auto hi = (std::min)(cumn(a2), n - 1); return { point, resample[lo], resample[hi], confidence_level }; } @@ -7133,7 +7138,9 @@ namespace Catch { } template EnvironmentEstimate> estimate_clock_cost(FloatDuration resolution) { - auto time_limit = std::min(resolution * clock_cost_estimation_tick_limit, FloatDuration(clock_cost_estimation_time_limit)); + auto time_limit = (std::min)( + resolution * clock_cost_estimation_tick_limit, + FloatDuration(clock_cost_estimation_time_limit)); auto time_clock = [](int k) { return Detail::measure([k] { for (int i = 0; i < k; ++i) { @@ -7611,6 +7618,10 @@ namespace TestCaseTracking { void addInitialFilters( std::vector const& filters ); void addNextFilters( std::vector const& filters ); + //! Returns filters active in this tracker + std::vector const& getFilters() const; + //! Returns whitespace-trimmed name of the tracked section + std::string const& trimmedName() const; }; } // namespace TestCaseTracking @@ -7776,7 +7787,7 @@ namespace Catch { double sb = stddev.point; double mn = mean.point / n; double mg_min = mn / 2.; - double sg = std::min(mg_min / 4., sb / std::sqrt(n)); + double sg = (std::min)(mg_min / 4., sb / std::sqrt(n)); double sg2 = sg * sg; double sb2 = sb * sb; @@ -7795,7 +7806,7 @@ namespace Catch { return (nc / n) * (sb2 - nc * sg2); }; - return std::min(var_out(1), var_out(std::min(c_max(0.), c_max(mg_min)))) / sb2; + return (std::min)(var_out(1), var_out((std::min)(c_max(0.), c_max(mg_min)))) / sb2; } bootstrap_analysis analyse_samples(double confidence_level, int n_resamples, std::vector::iterator first, std::vector::iterator last) { @@ -7985,86 +7996,58 @@ namespace Catch { // start catch_fatal_condition.h -// start catch_windows_h_proxy.h - - -#if defined(CATCH_PLATFORM_WINDOWS) - -#if !defined(NOMINMAX) && !defined(CATCH_CONFIG_NO_NOMINMAX) -# define CATCH_DEFINED_NOMINMAX -# define NOMINMAX -#endif -#if !defined(WIN32_LEAN_AND_MEAN) && !defined(CATCH_CONFIG_NO_WIN32_LEAN_AND_MEAN) -# define CATCH_DEFINED_WIN32_LEAN_AND_MEAN -# define WIN32_LEAN_AND_MEAN -#endif - -#ifdef __AFXDLL -#include -#else -#include -#endif - -#ifdef CATCH_DEFINED_NOMINMAX -# undef NOMINMAX -#endif -#ifdef CATCH_DEFINED_WIN32_LEAN_AND_MEAN -# undef WIN32_LEAN_AND_MEAN -#endif - -#endif // defined(CATCH_PLATFORM_WINDOWS) - -// end catch_windows_h_proxy.h -#if defined( CATCH_CONFIG_WINDOWS_SEH ) +#include namespace Catch { - struct FatalConditionHandler { - - static LONG CALLBACK handleVectoredException(PEXCEPTION_POINTERS ExceptionInfo); + // Wrapper for platform-specific fatal error (signals/SEH) handlers + // + // Tries to be cooperative with other handlers, and not step over + // other handlers. This means that unknown structured exceptions + // are passed on, previous signal handlers are called, and so on. + // + // Can only be instantiated once, and assumes that once a signal + // is caught, the binary will end up terminating. Thus, there + class FatalConditionHandler { + bool m_started = false; + + // Install/disengage implementation for specific platform. + // Should be if-defed to work on current platform, can assume + // engage-disengage 1:1 pairing. + void engage_platform(); + void disengage_platform(); + public: + // Should also have platform-specific implementations as needed FatalConditionHandler(); - static void reset(); ~FatalConditionHandler(); - private: - static bool isSet; - static ULONG guaranteeSize; - static PVOID exceptionHandlerHandle; - }; - -} // namespace Catch - -#elif defined ( CATCH_CONFIG_POSIX_SIGNALS ) - -#include - -namespace Catch { - - struct FatalConditionHandler { - - static bool isSet; - static struct sigaction oldSigActions[]; - static stack_t oldSigStack; - static char altStackMem[]; - - static void handleSignal( int sig ); + void engage() { + assert(!m_started && "Handler cannot be installed twice."); + m_started = true; + engage_platform(); + } - FatalConditionHandler(); - ~FatalConditionHandler(); - static void reset(); + void disengage() { + assert(m_started && "Handler cannot be uninstalled without being installed first"); + m_started = false; + disengage_platform(); + } }; -} // namespace Catch - -#else - -namespace Catch { - struct FatalConditionHandler { - void reset(); + //! Simple RAII guard for (dis)engaging the FatalConditionHandler + class FatalConditionHandlerGuard { + FatalConditionHandler* m_handler; + public: + FatalConditionHandlerGuard(FatalConditionHandler* handler): + m_handler(handler) { + m_handler->engage(); + } + ~FatalConditionHandlerGuard() { + m_handler->disengage(); + } }; -} -#endif +} // end namespace Catch // end catch_fatal_condition.h #include @@ -8190,6 +8173,7 @@ namespace Catch { std::vector m_unfinishedSections; std::vector m_activeSections; TrackerContext m_trackerContext; + FatalConditionHandler m_fatalConditionhandler; bool m_lastAssertionPassed = false; bool m_shouldReportUnexpected = true; bool m_includeSuccessfulResults; @@ -10062,6 +10046,36 @@ namespace Catch { } // end catch_errno_guard.h +// start catch_windows_h_proxy.h + + +#if defined(CATCH_PLATFORM_WINDOWS) + +#if !defined(NOMINMAX) && !defined(CATCH_CONFIG_NO_NOMINMAX) +# define CATCH_DEFINED_NOMINMAX +# define NOMINMAX +#endif +#if !defined(WIN32_LEAN_AND_MEAN) && !defined(CATCH_CONFIG_NO_WIN32_LEAN_AND_MEAN) +# define CATCH_DEFINED_WIN32_LEAN_AND_MEAN +# define WIN32_LEAN_AND_MEAN +#endif + +#ifdef __AFXDLL +#include +#else +#include +#endif + +#ifdef CATCH_DEFINED_NOMINMAX +# undef NOMINMAX +#endif +#ifdef CATCH_DEFINED_WIN32_LEAN_AND_MEAN +# undef WIN32_LEAN_AND_MEAN +#endif + +#endif // defined(CATCH_PLATFORM_WINDOWS) + +// end catch_windows_h_proxy.h #include namespace Catch { @@ -10578,7 +10592,7 @@ namespace Catch { // Extracts the actual name part of an enum instance // In other words, it returns the Blue part of Bikeshed::Colour::Blue StringRef extractInstanceName(StringRef enumInstance) { - // Find last occurence of ":" + // Find last occurrence of ":" size_t name_start = enumInstance.size(); while (name_start > 0 && enumInstance[name_start - 1] != ':') { --name_start; @@ -10740,25 +10754,47 @@ namespace Catch { // end catch_exception_translator_registry.cpp // start catch_fatal_condition.cpp -#if defined(__GNUC__) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wmissing-field-initializers" -#endif +#include + +#if !defined( CATCH_CONFIG_WINDOWS_SEH ) && !defined( CATCH_CONFIG_POSIX_SIGNALS ) + +namespace Catch { + + // If neither SEH nor signal handling is required, the handler impls + // do not have to do anything, and can be empty. + void FatalConditionHandler::engage_platform() {} + void FatalConditionHandler::disengage_platform() {} + FatalConditionHandler::FatalConditionHandler() = default; + FatalConditionHandler::~FatalConditionHandler() = default; + +} // end namespace Catch + +#endif // !CATCH_CONFIG_WINDOWS_SEH && !CATCH_CONFIG_POSIX_SIGNALS + +#if defined( CATCH_CONFIG_WINDOWS_SEH ) && defined( CATCH_CONFIG_POSIX_SIGNALS ) +#error "Inconsistent configuration: Windows' SEH handling and POSIX signals cannot be enabled at the same time" +#endif // CATCH_CONFIG_WINDOWS_SEH && CATCH_CONFIG_POSIX_SIGNALS #if defined( CATCH_CONFIG_WINDOWS_SEH ) || defined( CATCH_CONFIG_POSIX_SIGNALS ) namespace { - // Report the error condition + //! Signals fatal error message to the run context void reportFatal( char const * const message ) { Catch::getCurrentContext().getResultCapture()->handleFatalErrorCondition( message ); } -} -#endif // signals/SEH handling + //! Minimal size Catch2 needs for its own fatal error handling. + //! Picked anecdotally, so it might not be sufficient on all + //! platforms, and for all configurations. + constexpr std::size_t minStackSizeForErrors = 32 * 1024; +} // end unnamed namespace + +#endif // CATCH_CONFIG_WINDOWS_SEH || CATCH_CONFIG_POSIX_SIGNALS #if defined( CATCH_CONFIG_WINDOWS_SEH ) namespace Catch { + struct SignalDefs { DWORD id; const char* name; }; // There is no 1-1 mapping between signals and windows exceptions. @@ -10771,7 +10807,7 @@ namespace Catch { { static_cast(EXCEPTION_INT_DIVIDE_BY_ZERO), "Divide by zero error" }, }; - LONG CALLBACK FatalConditionHandler::handleVectoredException(PEXCEPTION_POINTERS ExceptionInfo) { + static LONG CALLBACK handleVectoredException(PEXCEPTION_POINTERS ExceptionInfo) { for (auto const& def : signalDefs) { if (ExceptionInfo->ExceptionRecord->ExceptionCode == def.id) { reportFatal(def.name); @@ -10782,38 +10818,50 @@ namespace Catch { return EXCEPTION_CONTINUE_SEARCH; } + // Since we do not support multiple instantiations, we put these + // into global variables and rely on cleaning them up in outlined + // constructors/destructors + static PVOID exceptionHandlerHandle = nullptr; + + // For MSVC, we reserve part of the stack memory for handling + // memory overflow structured exception. FatalConditionHandler::FatalConditionHandler() { - isSet = true; - // 32k seems enough for Catch to handle stack overflow, - // but the value was found experimentally, so there is no strong guarantee - guaranteeSize = 32 * 1024; - exceptionHandlerHandle = nullptr; + ULONG guaranteeSize = static_cast(minStackSizeForErrors); + if (!SetThreadStackGuarantee(&guaranteeSize)) { + // We do not want to fully error out, because needing + // the stack reserve should be rare enough anyway. + Catch::cerr() + << "Failed to reserve piece of stack." + << " Stack overflows will not be reported successfully."; + } + } + + // We do not attempt to unset the stack guarantee, because + // Windows does not support lowering the stack size guarantee. + FatalConditionHandler::~FatalConditionHandler() = default; + + void FatalConditionHandler::engage_platform() { // Register as first handler in current chain exceptionHandlerHandle = AddVectoredExceptionHandler(1, handleVectoredException); - // Pass in guarantee size to be filled - SetThreadStackGuarantee(&guaranteeSize); + if (!exceptionHandlerHandle) { + CATCH_RUNTIME_ERROR("Could not register vectored exception handler"); + } } - void FatalConditionHandler::reset() { - if (isSet) { - RemoveVectoredExceptionHandler(exceptionHandlerHandle); - SetThreadStackGuarantee(&guaranteeSize); - exceptionHandlerHandle = nullptr; - isSet = false; + void FatalConditionHandler::disengage_platform() { + if (!RemoveVectoredExceptionHandler(exceptionHandlerHandle)) { + CATCH_RUNTIME_ERROR("Could not unregister vectored exception handler"); } + exceptionHandlerHandle = nullptr; } - FatalConditionHandler::~FatalConditionHandler() { - reset(); - } +} // end namespace Catch -bool FatalConditionHandler::isSet = false; -ULONG FatalConditionHandler::guaranteeSize = 0; -PVOID FatalConditionHandler::exceptionHandlerHandle = nullptr; +#endif // CATCH_CONFIG_WINDOWS_SEH -} // namespace Catch +#if defined( CATCH_CONFIG_POSIX_SIGNALS ) -#elif defined( CATCH_CONFIG_POSIX_SIGNALS ) +#include namespace Catch { @@ -10822,10 +10870,6 @@ namespace Catch { const char* name; }; - // 32kb for the alternate stack seems to be sufficient. However, this value - // is experimentally determined, so that's not guaranteed. - static constexpr std::size_t sigStackSize = 32768 >= MINSIGSTKSZ ? 32768 : MINSIGSTKSZ; - static SignalDefs signalDefs[] = { { SIGINT, "SIGINT - Terminal interrupt signal" }, { SIGILL, "SIGILL - Illegal instruction signal" }, @@ -10835,7 +10879,32 @@ namespace Catch { { SIGABRT, "SIGABRT - Abort (abnormal termination) signal" } }; - void FatalConditionHandler::handleSignal( int sig ) { +// Older GCCs trigger -Wmissing-field-initializers for T foo = {} +// which is zero initialization, but not explicit. We want to avoid +// that. +#if defined(__GNUC__) +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wmissing-field-initializers" +#endif + + static char* altStackMem = nullptr; + static std::size_t altStackSize = 0; + static stack_t oldSigStack{}; + static struct sigaction oldSigActions[sizeof(signalDefs) / sizeof(SignalDefs)]{}; + + static void restorePreviousSignalHandlers() { + // We set signal handlers back to the previous ones. Hopefully + // nobody overwrote them in the meantime, and doesn't expect + // their signal handlers to live past ours given that they + // installed them after ours.. + for (std::size_t i = 0; i < sizeof(signalDefs) / sizeof(SignalDefs); ++i) { + sigaction(signalDefs[i].id, &oldSigActions[i], nullptr); + } + // Return the old stack + sigaltstack(&oldSigStack, nullptr); + } + + static void handleSignal( int sig ) { char const * name = ""; for (auto const& def : signalDefs) { if (sig == def.id) { @@ -10843,16 +10912,33 @@ namespace Catch { break; } } - reset(); - reportFatal(name); + // We need to restore previous signal handlers and let them do + // their thing, so that the users can have the debugger break + // when a signal is raised, and so on. + restorePreviousSignalHandlers(); + reportFatal( name ); raise( sig ); } FatalConditionHandler::FatalConditionHandler() { - isSet = true; + assert(!altStackMem && "Cannot initialize POSIX signal handler when one already exists"); + if (altStackSize == 0) { + altStackSize = std::max(static_cast(SIGSTKSZ), minStackSizeForErrors); + } + altStackMem = new char[altStackSize](); + } + + FatalConditionHandler::~FatalConditionHandler() { + delete[] altStackMem; + // We signal that another instance can be constructed by zeroing + // out the pointer. + altStackMem = nullptr; + } + + void FatalConditionHandler::engage_platform() { stack_t sigStack; sigStack.ss_sp = altStackMem; - sigStack.ss_size = sigStackSize; + sigStack.ss_size = altStackSize; sigStack.ss_flags = 0; sigaltstack(&sigStack, &oldSigStack); struct sigaction sa = { }; @@ -10864,40 +10950,17 @@ namespace Catch { } } - FatalConditionHandler::~FatalConditionHandler() { - reset(); - } +#if defined(__GNUC__) +# pragma GCC diagnostic pop +#endif - void FatalConditionHandler::reset() { - if( isSet ) { - // Set signals back to previous values -- hopefully nobody overwrote them in the meantime - for( std::size_t i = 0; i < sizeof(signalDefs)/sizeof(SignalDefs); ++i ) { - sigaction(signalDefs[i].id, &oldSigActions[i], nullptr); - } - // Return the old stack - sigaltstack(&oldSigStack, nullptr); - isSet = false; - } + void FatalConditionHandler::disengage_platform() { + restorePreviousSignalHandlers(); } - bool FatalConditionHandler::isSet = false; - struct sigaction FatalConditionHandler::oldSigActions[sizeof(signalDefs)/sizeof(SignalDefs)] = {}; - stack_t FatalConditionHandler::oldSigStack = {}; - char FatalConditionHandler::altStackMem[sigStackSize] = {}; - -} // namespace Catch - -#else - -namespace Catch { - void FatalConditionHandler::reset() {} -} - -#endif // signals/SEH handling +} // end namespace Catch -#if defined(__GNUC__) -# pragma GCC diagnostic pop -#endif +#endif // CATCH_CONFIG_POSIX_SIGNALS // end catch_fatal_condition.cpp // start catch_generators.cpp @@ -11452,7 +11515,8 @@ namespace { return lhs == rhs; } - auto ulpDiff = std::abs(lc - rc); + // static cast as a workaround for IBM XLC + auto ulpDiff = std::abs(static_cast(lc - rc)); return static_cast(ulpDiff) <= maxUlpDiff; } @@ -11626,7 +11690,6 @@ Floating::WithinRelMatcher WithinRel(float target) { } // namespace Matchers } // namespace Catch - // end catch_matchers_floating.cpp // start catch_matchers_generic.cpp @@ -12042,7 +12105,7 @@ namespace Catch { if (tmpnam_s(m_buffer)) { CATCH_RUNTIME_ERROR("Could not get a temp filename"); } - if (fopen_s(&m_file, m_buffer, "w")) { + if (fopen_s(&m_file, m_buffer, "w+")) { char buffer[100]; if (strerror_s(buffer, errno)) { CATCH_RUNTIME_ERROR("Could not translate errno to a string"); @@ -12580,13 +12643,53 @@ namespace Catch { // `SECTION`s. // **The check for m_children.empty cannot be removed**. // doing so would break `GENERATE` _not_ followed by `SECTION`s. - const bool should_wait_for_child = - !m_children.empty() && - std::find_if( m_children.begin(), - m_children.end(), - []( TestCaseTracking::ITrackerPtr tracker ) { - return tracker->hasStarted(); - } ) == m_children.end(); + const bool should_wait_for_child = [&]() { + // No children -> nobody to wait for + if ( m_children.empty() ) { + return false; + } + // If at least one child started executing, don't wait + if ( std::find_if( + m_children.begin(), + m_children.end(), + []( TestCaseTracking::ITrackerPtr tracker ) { + return tracker->hasStarted(); + } ) != m_children.end() ) { + return false; + } + + // No children have started. We need to check if they _can_ + // start, and thus we should wait for them, or they cannot + // start (due to filters), and we shouldn't wait for them + auto* parent = m_parent; + // This is safe: there is always at least one section + // tracker in a test case tracking tree + while ( !parent->isSectionTracker() ) { + parent = &( parent->parent() ); + } + assert( parent && + "Missing root (test case) level section" ); + + auto const& parentSection = + static_cast( *parent ); + auto const& filters = parentSection.getFilters(); + // No filters -> no restrictions on running sections + if ( filters.empty() ) { + return true; + } + + for ( auto const& child : m_children ) { + if ( child->isSectionTracker() && + std::find( filters.begin(), + filters.end(), + static_cast( *child ) + .trimmedName() ) != + filters.end() ) { + return true; + } + } + return false; + }(); // This check is a bit tricky, because m_generator->next() // has a side-effect, where it consumes generator's current @@ -12920,9 +13023,8 @@ namespace Catch { } void RunContext::invokeActiveTestCase() { - FatalConditionHandler fatalConditionHandler; // Handle signals + FatalConditionHandlerGuard _(&m_fatalConditionhandler); m_activeTestCase->invoke(); - fatalConditionHandler.reset(); } void RunContext::handleUnfinishedSections() { @@ -13290,6 +13392,10 @@ namespace Catch { filename.erase(0, lastSlash); filename[0] = '#'; } + else + { + filename.insert(0, "#"); + } auto lastDot = filename.find_last_of('.'); if (lastDot != std::string::npos) { @@ -14091,24 +14197,28 @@ namespace Catch { namespace { struct TestHasher { - explicit TestHasher(Catch::SimplePcg32& rng) { - basis = rng(); - basis <<= 32; - basis |= rng(); - } + using hash_t = uint64_t; - uint64_t basis; + explicit TestHasher( hash_t hashSuffix ): + m_hashSuffix{ hashSuffix } {} - uint64_t operator()(TestCase const& t) const { - // Modified FNV-1a hash - static constexpr uint64_t prime = 1099511628211; - uint64_t hash = basis; - for (const char c : t.name) { + uint32_t operator()( TestCase const& t ) const { + // FNV-1a hash with multiplication fold. + const hash_t prime = 1099511628211u; + hash_t hash = 14695981039346656037u; + for ( const char c : t.name ) { hash ^= c; hash *= prime; } - return hash; + hash ^= m_hashSuffix; + hash *= prime; + const uint32_t low{ static_cast( hash ) }; + const uint32_t high{ static_cast( hash >> 32 ) }; + return low * high; } + + private: + hash_t m_hashSuffix; }; } // end unnamed namespace @@ -14126,9 +14236,9 @@ namespace Catch { case RunTests::InRandomOrder: { seedRng( config ); - TestHasher h( rng() ); + TestHasher h{ config.rngSeed() }; - using hashedTest = std::pair; + using hashedTest = std::pair; std::vector indexed_tests; indexed_tests.reserve( unsortedTestCases.size() ); @@ -14458,6 +14568,14 @@ namespace TestCaseTracking { m_filters.insert( m_filters.end(), filters.begin()+1, filters.end() ); } + std::vector const& SectionTracker::getFilters() const { + return m_filters; + } + + std::string const& SectionTracker::trimmedName() const { + return m_trimmed_name; + } + } // namespace TestCaseTracking using TestCaseTracking::ITracker; @@ -15192,6 +15310,41 @@ namespace Catch { // end catch_totals.cpp // start catch_uncaught_exceptions.cpp +// start catch_config_uncaught_exceptions.hpp + +// Copyright Catch2 Authors +// Distributed under the Boost Software License, Version 1.0. +// (See accompanying file LICENSE_1_0.txt or copy at +// https://www.boost.org/LICENSE_1_0.txt) + +// SPDX-License-Identifier: BSL-1.0 + +#ifndef CATCH_CONFIG_UNCAUGHT_EXCEPTIONS_HPP +#define CATCH_CONFIG_UNCAUGHT_EXCEPTIONS_HPP + +#if defined(_MSC_VER) +# if _MSC_VER >= 1900 // Visual Studio 2015 or newer +# define CATCH_INTERNAL_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS +# endif +#endif + +#include + +#if defined(__cpp_lib_uncaught_exceptions) \ + && !defined(CATCH_INTERNAL_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS) + +# define CATCH_INTERNAL_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS +#endif // __cpp_lib_uncaught_exceptions + +#if defined(CATCH_INTERNAL_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS) \ + && !defined(CATCH_CONFIG_NO_CPP17_UNCAUGHT_EXCEPTIONS) \ + && !defined(CATCH_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS) + +# define CATCH_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS +#endif + +#endif // CATCH_CONFIG_UNCAUGHT_EXCEPTIONS_HPP +// end catch_config_uncaught_exceptions.hpp #include namespace Catch { @@ -15238,7 +15391,7 @@ namespace Catch { } Version const& libraryVersion() { - static Version version( 2, 13, 0, "", 0 ); + static Version version( 2, 13, 9, "", 0 ); return version; } @@ -16651,6 +16804,7 @@ CATCH_REGISTER_REPORTER("console", ConsoleReporter) #include #include #include +#include namespace Catch { @@ -16678,7 +16832,7 @@ namespace Catch { #else std::strftime(timeStamp, timeStampSize, fmt, timeInfo); #endif - return std::string(timeStamp); + return std::string(timeStamp, timeStampSize-1); } std::string fileNameTag(const std::vector &tags) { @@ -16689,6 +16843,17 @@ namespace Catch { return it->substr(1); return std::string(); } + + // Formats the duration in seconds to 3 decimal places. + // This is done because some genius defined Maven Surefire schema + // in a way that only accepts 3 decimal places, and tools like + // Jenkins use that schema for validation JUnit reporter output. + std::string formatDuration( double seconds ) { + ReusableStringStream rss; + rss << std::fixed << std::setprecision( 3 ) << seconds; + return rss.str(); + } + } // anonymous namespace JunitReporter::JunitReporter( ReporterConfig const& _config ) @@ -16758,7 +16923,7 @@ namespace Catch { if( m_config->showDurations() == ShowDurations::Never ) xml.writeAttribute( "time", "" ); else - xml.writeAttribute( "time", suiteTime ); + xml.writeAttribute( "time", formatDuration( suiteTime ) ); xml.writeAttribute( "timestamp", getCurrentTimestamp() ); // Write properties if there are any @@ -16803,12 +16968,13 @@ namespace Catch { if ( !m_config->name().empty() ) className = m_config->name() + "." + className; - writeSection( className, "", rootSection ); + writeSection( className, "", rootSection, stats.testInfo.okToFail() ); } - void JunitReporter::writeSection( std::string const& className, - std::string const& rootName, - SectionNode const& sectionNode ) { + void JunitReporter::writeSection( std::string const& className, + std::string const& rootName, + SectionNode const& sectionNode, + bool testOkToFail) { std::string name = trim( sectionNode.stats.sectionInfo.name ); if( !rootName.empty() ) name = rootName + '/' + name; @@ -16825,13 +16991,18 @@ namespace Catch { xml.writeAttribute( "classname", className ); xml.writeAttribute( "name", name ); } - xml.writeAttribute( "time", ::Catch::Detail::stringify( sectionNode.stats.durationInSeconds ) ); + xml.writeAttribute( "time", formatDuration( sectionNode.stats.durationInSeconds ) ); // This is not ideal, but it should be enough to mimic gtest's // junit output. // Ideally the JUnit reporter would also handle `skipTest` // events and write those out appropriately. xml.writeAttribute( "status", "run" ); + if (sectionNode.stats.assertions.failedButOk) { + xml.scopedElement("skipped") + .writeAttribute("message", "TEST_CASE tagged with !mayfail"); + } + writeAssertions( sectionNode ); if( !sectionNode.stdOut.empty() ) @@ -16841,9 +17012,9 @@ namespace Catch { } for( auto const& childNode : sectionNode.childSections ) if( className.empty() ) - writeSection( name, "", *childNode ); + writeSection( name, "", *childNode, testOkToFail ); else - writeSection( className, name, *childNode ); + writeSection( className, name, *childNode, testOkToFail ); } void JunitReporter::writeAssertions( SectionNode const& sectionNode ) { @@ -17488,9 +17659,9 @@ int main (int argc, char * const argv[]) { #if defined(CATCH_CONFIG_ENABLE_BENCHMARKING) #define CATCH_BENCHMARK(...) \ - INTERNAL_CATCH_BENCHMARK(INTERNAL_CATCH_UNIQUE_NAME(____C_A_T_C_H____B_E_N_C_H____), INTERNAL_CATCH_GET_1_ARG(__VA_ARGS__,,), INTERNAL_CATCH_GET_2_ARG(__VA_ARGS__,,)) + INTERNAL_CATCH_BENCHMARK(INTERNAL_CATCH_UNIQUE_NAME(C_A_T_C_H_B_E_N_C_H_), INTERNAL_CATCH_GET_1_ARG(__VA_ARGS__,,), INTERNAL_CATCH_GET_2_ARG(__VA_ARGS__,,)) #define CATCH_BENCHMARK_ADVANCED(name) \ - INTERNAL_CATCH_BENCHMARK_ADVANCED(INTERNAL_CATCH_UNIQUE_NAME(____C_A_T_C_H____B_E_N_C_H____), name) + INTERNAL_CATCH_BENCHMARK_ADVANCED(INTERNAL_CATCH_UNIQUE_NAME(C_A_T_C_H_B_E_N_C_H_), name) #endif // CATCH_CONFIG_ENABLE_BENCHMARKING // If CATCH_CONFIG_PREFIX_ALL is not defined then the CATCH_ prefix is not required @@ -17592,9 +17763,9 @@ int main (int argc, char * const argv[]) { #if defined(CATCH_CONFIG_ENABLE_BENCHMARKING) #define BENCHMARK(...) \ - INTERNAL_CATCH_BENCHMARK(INTERNAL_CATCH_UNIQUE_NAME(____C_A_T_C_H____B_E_N_C_H____), INTERNAL_CATCH_GET_1_ARG(__VA_ARGS__,,), INTERNAL_CATCH_GET_2_ARG(__VA_ARGS__,,)) + INTERNAL_CATCH_BENCHMARK(INTERNAL_CATCH_UNIQUE_NAME(C_A_T_C_H_B_E_N_C_H_), INTERNAL_CATCH_GET_1_ARG(__VA_ARGS__,,), INTERNAL_CATCH_GET_2_ARG(__VA_ARGS__,,)) #define BENCHMARK_ADVANCED(name) \ - INTERNAL_CATCH_BENCHMARK_ADVANCED(INTERNAL_CATCH_UNIQUE_NAME(____C_A_T_C_H____B_E_N_C_H____), name) + INTERNAL_CATCH_BENCHMARK_ADVANCED(INTERNAL_CATCH_UNIQUE_NAME(C_A_T_C_H_B_E_N_C_H_), name) #endif // CATCH_CONFIG_ENABLE_BENCHMARKING using Catch::Detail::Approx; @@ -17641,8 +17812,8 @@ using Catch::Detail::Approx; #define CATCH_WARN( msg ) (void)(0) #define CATCH_CAPTURE( msg ) (void)(0) -#define CATCH_TEST_CASE( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ )) -#define CATCH_TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ )) +#define CATCH_TEST_CASE( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_S_T_ )) +#define CATCH_TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_S_T_ )) #define CATCH_METHOD_AS_TEST_CASE( method, ... ) #define CATCH_REGISTER_TEST_CASE( Function, ... ) (void)(0) #define CATCH_SECTION( ... ) @@ -17651,7 +17822,7 @@ using Catch::Detail::Approx; #define CATCH_FAIL_CHECK( ... ) (void)(0) #define CATCH_SUCCEED( ... ) (void)(0) -#define CATCH_ANON_TEST_CASE() INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ )) +#define CATCH_ANON_TEST_CASE() INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_S_T_ )) #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR #define CATCH_TEMPLATE_TEST_CASE( ... ) INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION(__VA_ARGS__) @@ -17674,8 +17845,8 @@ using Catch::Detail::Approx; #endif // "BDD-style" convenience wrappers -#define CATCH_SCENARIO( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ )) -#define CATCH_SCENARIO_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_METHOD_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), className ) +#define CATCH_SCENARIO( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_S_T_ )) +#define CATCH_SCENARIO_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_METHOD_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_S_T_ ), className ) #define CATCH_GIVEN( desc ) #define CATCH_AND_GIVEN( desc ) #define CATCH_WHEN( desc ) @@ -17723,10 +17894,10 @@ using Catch::Detail::Approx; #define INFO( msg ) (void)(0) #define UNSCOPED_INFO( msg ) (void)(0) #define WARN( msg ) (void)(0) -#define CAPTURE( msg ) (void)(0) +#define CAPTURE( ... ) (void)(0) -#define TEST_CASE( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ )) -#define TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ )) +#define TEST_CASE( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_S_T_ )) +#define TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_S_T_ )) #define METHOD_AS_TEST_CASE( method, ... ) #define REGISTER_TEST_CASE( Function, ... ) (void)(0) #define SECTION( ... ) @@ -17734,7 +17905,7 @@ using Catch::Detail::Approx; #define FAIL( ... ) (void)(0) #define FAIL_CHECK( ... ) (void)(0) #define SUCCEED( ... ) (void)(0) -#define ANON_TEST_CASE() INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ )) +#define ANON_TEST_CASE() INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_S_T_ )) #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR #define TEMPLATE_TEST_CASE( ... ) INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION(__VA_ARGS__) @@ -17764,8 +17935,8 @@ using Catch::Detail::Approx; #define CATCH_TRANSLATE_EXCEPTION( signature ) INTERNAL_CATCH_TRANSLATE_EXCEPTION_NO_REG( INTERNAL_CATCH_UNIQUE_NAME( catch_internal_ExceptionTranslator ), signature ) // "BDD-style" convenience wrappers -#define SCENARIO( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ) ) -#define SCENARIO_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_METHOD_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), className ) +#define SCENARIO( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_S_T_ ) ) +#define SCENARIO_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_METHOD_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_S_T_ ), className ) #define GIVEN( desc ) #define AND_GIVEN( desc ) diff --git a/third_party/catch2/include/catch2/catch_reporter_automake.hpp b/third_party/catch2/include/catch2/catch_reporter_automake.hpp index dbebe97516..ba6f67f310 100644 --- a/third_party/catch2/include/catch2/catch_reporter_automake.hpp +++ b/third_party/catch2/include/catch2/catch_reporter_automake.hpp @@ -1,62 +1,62 @@ -/* - * Created by Justin R. Wilson on 2/19/2017. - * Copyright 2017 Justin R. Wilson. All rights reserved. - * - * Distributed under the Boost Software License, Version 1.0. (See accompanying - * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) - */ -#ifndef TWOBLUECUBES_CATCH_REPORTER_AUTOMAKE_HPP_INCLUDED -#define TWOBLUECUBES_CATCH_REPORTER_AUTOMAKE_HPP_INCLUDED - -// Don't #include any Catch headers here - we can assume they are already -// included before this header. -// This is not good practice in general but is necessary in this case so this -// file can be distributed as a single header that works with the main -// Catch single header. - -namespace Catch { - - struct AutomakeReporter : StreamingReporterBase { - AutomakeReporter( ReporterConfig const& _config ) - : StreamingReporterBase( _config ) - {} - - ~AutomakeReporter() override; - - static std::string getDescription() { - return "Reports test results in the format of Automake .trs files"; - } - - void assertionStarting( AssertionInfo const& ) override {} - - bool assertionEnded( AssertionStats const& /*_assertionStats*/ ) override { return true; } - - void testCaseEnded( TestCaseStats const& _testCaseStats ) override { - // Possible values to emit are PASS, XFAIL, SKIP, FAIL, XPASS and ERROR. - stream << ":test-result: "; - if (_testCaseStats.totals.assertions.allPassed()) { - stream << "PASS"; - } else if (_testCaseStats.totals.assertions.allOk()) { - stream << "XFAIL"; - } else { - stream << "FAIL"; - } - stream << ' ' << _testCaseStats.testInfo.name << '\n'; - StreamingReporterBase::testCaseEnded( _testCaseStats ); - } - - void skipTest( TestCaseInfo const& testInfo ) override { - stream << ":test-result: SKIP " << testInfo.name << '\n'; - } - - }; - -#ifdef CATCH_IMPL - AutomakeReporter::~AutomakeReporter() {} -#endif - - CATCH_REGISTER_REPORTER( "automake", AutomakeReporter) - -} // end namespace Catch - -#endif // TWOBLUECUBES_CATCH_REPORTER_AUTOMAKE_HPP_INCLUDED +/* + * Created by Justin R. Wilson on 2/19/2017. + * Copyright 2017 Justin R. Wilson. All rights reserved. + * + * Distributed under the Boost Software License, Version 1.0. (See accompanying + * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) + */ +#ifndef TWOBLUECUBES_CATCH_REPORTER_AUTOMAKE_HPP_INCLUDED +#define TWOBLUECUBES_CATCH_REPORTER_AUTOMAKE_HPP_INCLUDED + +// Don't #include any Catch headers here - we can assume they are already +// included before this header. +// This is not good practice in general but is necessary in this case so this +// file can be distributed as a single header that works with the main +// Catch single header. + +namespace Catch { + + struct AutomakeReporter : StreamingReporterBase { + AutomakeReporter( ReporterConfig const& _config ) + : StreamingReporterBase( _config ) + {} + + ~AutomakeReporter() override; + + static std::string getDescription() { + return "Reports test results in the format of Automake .trs files"; + } + + void assertionStarting( AssertionInfo const& ) override {} + + bool assertionEnded( AssertionStats const& /*_assertionStats*/ ) override { return true; } + + void testCaseEnded( TestCaseStats const& _testCaseStats ) override { + // Possible values to emit are PASS, XFAIL, SKIP, FAIL, XPASS and ERROR. + stream << ":test-result: "; + if (_testCaseStats.totals.assertions.allPassed()) { + stream << "PASS"; + } else if (_testCaseStats.totals.assertions.allOk()) { + stream << "XFAIL"; + } else { + stream << "FAIL"; + } + stream << ' ' << _testCaseStats.testInfo.name << '\n'; + StreamingReporterBase::testCaseEnded( _testCaseStats ); + } + + void skipTest( TestCaseInfo const& testInfo ) override { + stream << ":test-result: SKIP " << testInfo.name << '\n'; + } + + }; + +#ifdef CATCH_IMPL + AutomakeReporter::~AutomakeReporter() {} +#endif + + CATCH_REGISTER_REPORTER( "automake", AutomakeReporter) + +} // end namespace Catch + +#endif // TWOBLUECUBES_CATCH_REPORTER_AUTOMAKE_HPP_INCLUDED diff --git a/third_party/catch2/include/catch2/catch_reporter_sonarqube.hpp b/third_party/catch2/include/catch2/catch_reporter_sonarqube.hpp index bf7d9299a5..06056f154f 100644 --- a/third_party/catch2/include/catch2/catch_reporter_sonarqube.hpp +++ b/third_party/catch2/include/catch2/catch_reporter_sonarqube.hpp @@ -1,181 +1,181 @@ -/* - * Created by Daniel Garcia on 2018-12-04. - * Copyright Social Point SL. All rights reserved. - * - * Distributed under the Boost Software License, Version 1.0. (See accompanying - * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) - */ -#ifndef CATCH_REPORTER_SONARQUBE_HPP_INCLUDED -#define CATCH_REPORTER_SONARQUBE_HPP_INCLUDED - - -// Don't #include any Catch headers here - we can assume they are already -// included before this header. -// This is not good practice in general but is necessary in this case so this -// file can be distributed as a single header that works with the main -// Catch single header. - -#include - -namespace Catch { - - struct SonarQubeReporter : CumulativeReporterBase { - - SonarQubeReporter(ReporterConfig const& config) - : CumulativeReporterBase(config) - , xml(config.stream()) { - m_reporterPrefs.shouldRedirectStdOut = true; - m_reporterPrefs.shouldReportAllAssertions = true; - } - - ~SonarQubeReporter() override; - - static std::string getDescription() { - return "Reports test results in the Generic Test Data SonarQube XML format"; - } - - static std::set getSupportedVerbosities() { - return { Verbosity::Normal }; - } - - void noMatchingTestCases(std::string const& /*spec*/) override {} - - void testRunStarting(TestRunInfo const& testRunInfo) override { - CumulativeReporterBase::testRunStarting(testRunInfo); - xml.startElement("testExecutions"); - xml.writeAttribute("version", "1"); - } - - void testGroupEnded(TestGroupStats const& testGroupStats) override { - CumulativeReporterBase::testGroupEnded(testGroupStats); - writeGroup(*m_testGroups.back()); - } - - void testRunEndedCumulative() override { - xml.endElement(); - } - - void writeGroup(TestGroupNode const& groupNode) { - std::map testsPerFile; - for(auto const& child : groupNode.children) - testsPerFile[child->value.testInfo.lineInfo.file].push_back(child); - - for(auto const& kv : testsPerFile) - writeTestFile(kv.first.c_str(), kv.second); - } - - void writeTestFile(const char* filename, TestGroupNode::ChildNodes const& testCaseNodes) { - XmlWriter::ScopedElement e = xml.scopedElement("file"); - xml.writeAttribute("path", filename); - - for(auto const& child : testCaseNodes) - writeTestCase(*child); - } - - void writeTestCase(TestCaseNode const& testCaseNode) { - // All test cases have exactly one section - which represents the - // test case itself. That section may have 0-n nested sections - assert(testCaseNode.children.size() == 1); - SectionNode const& rootSection = *testCaseNode.children.front(); - writeSection("", rootSection, testCaseNode.value.testInfo.okToFail()); - } - - void writeSection(std::string const& rootName, SectionNode const& sectionNode, bool okToFail) { - std::string name = trim(sectionNode.stats.sectionInfo.name); - if(!rootName.empty()) - name = rootName + '/' + name; - - if(!sectionNode.assertions.empty() || !sectionNode.stdOut.empty() || !sectionNode.stdErr.empty()) { - XmlWriter::ScopedElement e = xml.scopedElement("testCase"); - xml.writeAttribute("name", name); - xml.writeAttribute("duration", static_cast(sectionNode.stats.durationInSeconds * 1000)); - - writeAssertions(sectionNode, okToFail); - } - - for(auto const& childNode : sectionNode.childSections) - writeSection(name, *childNode, okToFail); - } - - void writeAssertions(SectionNode const& sectionNode, bool okToFail) { - for(auto const& assertion : sectionNode.assertions) - writeAssertion( assertion, okToFail); - } - - void writeAssertion(AssertionStats const& stats, bool okToFail) { - AssertionResult const& result = stats.assertionResult; - if(!result.isOk()) { - std::string elementName; - if(okToFail) { - elementName = "skipped"; - } - else { - switch(result.getResultType()) { - case ResultWas::ThrewException: - case ResultWas::FatalErrorCondition: - elementName = "error"; - break; - case ResultWas::ExplicitFailure: - elementName = "failure"; - break; - case ResultWas::ExpressionFailed: - elementName = "failure"; - break; - case ResultWas::DidntThrowException: - elementName = "failure"; - break; - - // We should never see these here: - case ResultWas::Info: - case ResultWas::Warning: - case ResultWas::Ok: - case ResultWas::Unknown: - case ResultWas::FailureBit: - case ResultWas::Exception: - elementName = "internalError"; - break; - } - } - - XmlWriter::ScopedElement e = xml.scopedElement(elementName); - - ReusableStringStream messageRss; - messageRss << result.getTestMacroName() << "(" << result.getExpression() << ")"; - xml.writeAttribute("message", messageRss.str()); - - ReusableStringStream textRss; - if (stats.totals.assertions.total() > 0) { - textRss << "FAILED:\n"; - if (result.hasExpression()) { - textRss << "\t" << result.getExpressionInMacro() << "\n"; - } - if (result.hasExpandedExpression()) { - textRss << "with expansion:\n\t" << result.getExpandedExpression() << "\n"; - } - } - - if(!result.getMessage().empty()) - textRss << result.getMessage() << "\n"; - - for(auto const& msg : stats.infoMessages) - if(msg.type == ResultWas::Info) - textRss << msg.message << "\n"; - - textRss << "at " << result.getSourceInfo(); - xml.writeText(textRss.str(), XmlFormatting::Newline); - } - } - - private: - XmlWriter xml; - }; - -#ifdef CATCH_IMPL - SonarQubeReporter::~SonarQubeReporter() {} -#endif - - CATCH_REGISTER_REPORTER( "sonarqube", SonarQubeReporter ) - -} // end namespace Catch - +/* + * Created by Daniel Garcia on 2018-12-04. + * Copyright Social Point SL. All rights reserved. + * + * Distributed under the Boost Software License, Version 1.0. (See accompanying + * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) + */ +#ifndef CATCH_REPORTER_SONARQUBE_HPP_INCLUDED +#define CATCH_REPORTER_SONARQUBE_HPP_INCLUDED + + +// Don't #include any Catch headers here - we can assume they are already +// included before this header. +// This is not good practice in general but is necessary in this case so this +// file can be distributed as a single header that works with the main +// Catch single header. + +#include + +namespace Catch { + + struct SonarQubeReporter : CumulativeReporterBase { + + SonarQubeReporter(ReporterConfig const& config) + : CumulativeReporterBase(config) + , xml(config.stream()) { + m_reporterPrefs.shouldRedirectStdOut = true; + m_reporterPrefs.shouldReportAllAssertions = true; + } + + ~SonarQubeReporter() override; + + static std::string getDescription() { + return "Reports test results in the Generic Test Data SonarQube XML format"; + } + + static std::set getSupportedVerbosities() { + return { Verbosity::Normal }; + } + + void noMatchingTestCases(std::string const& /*spec*/) override {} + + void testRunStarting(TestRunInfo const& testRunInfo) override { + CumulativeReporterBase::testRunStarting(testRunInfo); + xml.startElement("testExecutions"); + xml.writeAttribute("version", "1"); + } + + void testGroupEnded(TestGroupStats const& testGroupStats) override { + CumulativeReporterBase::testGroupEnded(testGroupStats); + writeGroup(*m_testGroups.back()); + } + + void testRunEndedCumulative() override { + xml.endElement(); + } + + void writeGroup(TestGroupNode const& groupNode) { + std::map testsPerFile; + for(auto const& child : groupNode.children) + testsPerFile[child->value.testInfo.lineInfo.file].push_back(child); + + for(auto const& kv : testsPerFile) + writeTestFile(kv.first.c_str(), kv.second); + } + + void writeTestFile(const char* filename, TestGroupNode::ChildNodes const& testCaseNodes) { + XmlWriter::ScopedElement e = xml.scopedElement("file"); + xml.writeAttribute("path", filename); + + for(auto const& child : testCaseNodes) + writeTestCase(*child); + } + + void writeTestCase(TestCaseNode const& testCaseNode) { + // All test cases have exactly one section - which represents the + // test case itself. That section may have 0-n nested sections + assert(testCaseNode.children.size() == 1); + SectionNode const& rootSection = *testCaseNode.children.front(); + writeSection("", rootSection, testCaseNode.value.testInfo.okToFail()); + } + + void writeSection(std::string const& rootName, SectionNode const& sectionNode, bool okToFail) { + std::string name = trim(sectionNode.stats.sectionInfo.name); + if(!rootName.empty()) + name = rootName + '/' + name; + + if(!sectionNode.assertions.empty() || !sectionNode.stdOut.empty() || !sectionNode.stdErr.empty()) { + XmlWriter::ScopedElement e = xml.scopedElement("testCase"); + xml.writeAttribute("name", name); + xml.writeAttribute("duration", static_cast(sectionNode.stats.durationInSeconds * 1000)); + + writeAssertions(sectionNode, okToFail); + } + + for(auto const& childNode : sectionNode.childSections) + writeSection(name, *childNode, okToFail); + } + + void writeAssertions(SectionNode const& sectionNode, bool okToFail) { + for(auto const& assertion : sectionNode.assertions) + writeAssertion( assertion, okToFail); + } + + void writeAssertion(AssertionStats const& stats, bool okToFail) { + AssertionResult const& result = stats.assertionResult; + if(!result.isOk()) { + std::string elementName; + if(okToFail) { + elementName = "skipped"; + } + else { + switch(result.getResultType()) { + case ResultWas::ThrewException: + case ResultWas::FatalErrorCondition: + elementName = "error"; + break; + case ResultWas::ExplicitFailure: + elementName = "failure"; + break; + case ResultWas::ExpressionFailed: + elementName = "failure"; + break; + case ResultWas::DidntThrowException: + elementName = "failure"; + break; + + // We should never see these here: + case ResultWas::Info: + case ResultWas::Warning: + case ResultWas::Ok: + case ResultWas::Unknown: + case ResultWas::FailureBit: + case ResultWas::Exception: + elementName = "internalError"; + break; + } + } + + XmlWriter::ScopedElement e = xml.scopedElement(elementName); + + ReusableStringStream messageRss; + messageRss << result.getTestMacroName() << "(" << result.getExpression() << ")"; + xml.writeAttribute("message", messageRss.str()); + + ReusableStringStream textRss; + if (stats.totals.assertions.total() > 0) { + textRss << "FAILED:\n"; + if (result.hasExpression()) { + textRss << "\t" << result.getExpressionInMacro() << "\n"; + } + if (result.hasExpandedExpression()) { + textRss << "with expansion:\n\t" << result.getExpandedExpression() << "\n"; + } + } + + if(!result.getMessage().empty()) + textRss << result.getMessage() << "\n"; + + for(auto const& msg : stats.infoMessages) + if(msg.type == ResultWas::Info) + textRss << msg.message << "\n"; + + textRss << "at " << result.getSourceInfo(); + xml.writeText(textRss.str(), XmlFormatting::Newline); + } + } + + private: + XmlWriter xml; + }; + +#ifdef CATCH_IMPL + SonarQubeReporter::~SonarQubeReporter() {} +#endif + + CATCH_REGISTER_REPORTER( "sonarqube", SonarQubeReporter ) + +} // end namespace Catch + #endif // CATCH_REPORTER_SONARQUBE_HPP_INCLUDED \ No newline at end of file diff --git a/third_party/catch2/include/catch2/catch_reporter_tap.hpp b/third_party/catch2/include/catch2/catch_reporter_tap.hpp index 5ac8524ce7..3acab5f39d 100644 --- a/third_party/catch2/include/catch2/catch_reporter_tap.hpp +++ b/third_party/catch2/include/catch2/catch_reporter_tap.hpp @@ -1,254 +1,254 @@ -/* - * Created by Colton Wolkins on 2015-08-15. - * Copyright 2015 Martin Moene. All rights reserved. - * - * Distributed under the Boost Software License, Version 1.0. (See accompanying - * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) - */ -#ifndef TWOBLUECUBES_CATCH_REPORTER_TAP_HPP_INCLUDED -#define TWOBLUECUBES_CATCH_REPORTER_TAP_HPP_INCLUDED - - -// Don't #include any Catch headers here - we can assume they are already -// included before this header. -// This is not good practice in general but is necessary in this case so this -// file can be distributed as a single header that works with the main -// Catch single header. - -#include - -namespace Catch { - - struct TAPReporter : StreamingReporterBase { - - using StreamingReporterBase::StreamingReporterBase; - - TAPReporter( ReporterConfig const& config ): - StreamingReporterBase( config ) { - m_reporterPrefs.shouldReportAllAssertions = true; - } - - ~TAPReporter() override; - - static std::string getDescription() { - return "Reports test results in TAP format, suitable for test harnesses"; - } - - void noMatchingTestCases( std::string const& spec ) override { - stream << "# No test cases matched '" << spec << "'" << std::endl; - } - - void assertionStarting( AssertionInfo const& ) override {} - - bool assertionEnded( AssertionStats const& _assertionStats ) override { - ++counter; - - stream << "# " << currentTestCaseInfo->name << std::endl; - AssertionPrinter printer( stream, _assertionStats, counter ); - printer.print(); - - stream << std::endl; - return true; - } - - void testRunEnded( TestRunStats const& _testRunStats ) override { - printTotals( _testRunStats.totals ); - stream << "\n" << std::endl; - StreamingReporterBase::testRunEnded( _testRunStats ); - } - - private: - std::size_t counter = 0; - class AssertionPrinter { - public: - AssertionPrinter& operator= ( AssertionPrinter const& ) = delete; - AssertionPrinter( AssertionPrinter const& ) = delete; - AssertionPrinter( std::ostream& _stream, AssertionStats const& _stats, std::size_t _counter ) - : stream( _stream ) - , result( _stats.assertionResult ) - , messages( _stats.infoMessages ) - , itMessage( _stats.infoMessages.begin() ) - , printInfoMessages( true ) - , counter(_counter) - {} - - void print() { - itMessage = messages.begin(); - - switch( result.getResultType() ) { - case ResultWas::Ok: - printResultType( passedString() ); - printOriginalExpression(); - printReconstructedExpression(); - if ( ! result.hasExpression() ) - printRemainingMessages( Colour::None ); - else - printRemainingMessages(); - break; - case ResultWas::ExpressionFailed: - if (result.isOk()) { - printResultType(passedString()); - } else { - printResultType(failedString()); - } - printOriginalExpression(); - printReconstructedExpression(); - if (result.isOk()) { - printIssue(" # TODO"); - } - printRemainingMessages(); - break; - case ResultWas::ThrewException: - printResultType( failedString() ); - printIssue( "unexpected exception with message:" ); - printMessage(); - printExpressionWas(); - printRemainingMessages(); - break; - case ResultWas::FatalErrorCondition: - printResultType( failedString() ); - printIssue( "fatal error condition with message:" ); - printMessage(); - printExpressionWas(); - printRemainingMessages(); - break; - case ResultWas::DidntThrowException: - printResultType( failedString() ); - printIssue( "expected exception, got none" ); - printExpressionWas(); - printRemainingMessages(); - break; - case ResultWas::Info: - printResultType( "info" ); - printMessage(); - printRemainingMessages(); - break; - case ResultWas::Warning: - printResultType( "warning" ); - printMessage(); - printRemainingMessages(); - break; - case ResultWas::ExplicitFailure: - printResultType( failedString() ); - printIssue( "explicitly" ); - printRemainingMessages( Colour::None ); - break; - // These cases are here to prevent compiler warnings - case ResultWas::Unknown: - case ResultWas::FailureBit: - case ResultWas::Exception: - printResultType( "** internal error **" ); - break; - } - } - - private: - static Colour::Code dimColour() { return Colour::FileName; } - - static const char* failedString() { return "not ok"; } - static const char* passedString() { return "ok"; } - - void printSourceInfo() const { - Colour colourGuard( dimColour() ); - stream << result.getSourceInfo() << ":"; - } - - void printResultType( std::string const& passOrFail ) const { - if( !passOrFail.empty() ) { - stream << passOrFail << ' ' << counter << " -"; - } - } - - void printIssue( std::string const& issue ) const { - stream << " " << issue; - } - - void printExpressionWas() { - if( result.hasExpression() ) { - stream << ";"; - { - Colour colour( dimColour() ); - stream << " expression was:"; - } - printOriginalExpression(); - } - } - - void printOriginalExpression() const { - if( result.hasExpression() ) { - stream << " " << result.getExpression(); - } - } - - void printReconstructedExpression() const { - if( result.hasExpandedExpression() ) { - { - Colour colour( dimColour() ); - stream << " for: "; - } - std::string expr = result.getExpandedExpression(); - std::replace( expr.begin(), expr.end(), '\n', ' '); - stream << expr; - } - } - - void printMessage() { - if ( itMessage != messages.end() ) { - stream << " '" << itMessage->message << "'"; - ++itMessage; - } - } - - void printRemainingMessages( Colour::Code colour = dimColour() ) { - if (itMessage == messages.end()) { - return; - } - - const auto itEnd = messages.cend(); - const auto N = static_cast( std::distance( itMessage, itEnd ) ); - - { - Colour colourGuard( colour ); - stream << " with " << pluralise( N, "message" ) << ":"; - } - - while( itMessage != itEnd ) { - // If this assertion is a warning ignore any INFO messages - if( printInfoMessages || itMessage->type != ResultWas::Info ) { - stream << " '" << itMessage->message << "'"; - if ( ++itMessage != itEnd ) { - Colour colourGuard( dimColour() ); - stream << " and"; - } - continue; - } - ++itMessage; - } - } - - private: - std::ostream& stream; - AssertionResult const& result; - std::vector messages; - std::vector::const_iterator itMessage; - bool printInfoMessages; - std::size_t counter; - }; - - void printTotals( const Totals& totals ) const { - stream << "1.." << totals.assertions.total(); - if( totals.testCases.total() == 0 ) { - stream << " # Skipped: No tests ran."; - } - } - }; - -#ifdef CATCH_IMPL - TAPReporter::~TAPReporter() {} -#endif - - CATCH_REGISTER_REPORTER( "tap", TAPReporter ) - -} // end namespace Catch - -#endif // TWOBLUECUBES_CATCH_REPORTER_TAP_HPP_INCLUDED +/* + * Created by Colton Wolkins on 2015-08-15. + * Copyright 2015 Martin Moene. All rights reserved. + * + * Distributed under the Boost Software License, Version 1.0. (See accompanying + * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) + */ +#ifndef TWOBLUECUBES_CATCH_REPORTER_TAP_HPP_INCLUDED +#define TWOBLUECUBES_CATCH_REPORTER_TAP_HPP_INCLUDED + + +// Don't #include any Catch headers here - we can assume they are already +// included before this header. +// This is not good practice in general but is necessary in this case so this +// file can be distributed as a single header that works with the main +// Catch single header. + +#include + +namespace Catch { + + struct TAPReporter : StreamingReporterBase { + + using StreamingReporterBase::StreamingReporterBase; + + TAPReporter( ReporterConfig const& config ): + StreamingReporterBase( config ) { + m_reporterPrefs.shouldReportAllAssertions = true; + } + + ~TAPReporter() override; + + static std::string getDescription() { + return "Reports test results in TAP format, suitable for test harnesses"; + } + + void noMatchingTestCases( std::string const& spec ) override { + stream << "# No test cases matched '" << spec << "'" << std::endl; + } + + void assertionStarting( AssertionInfo const& ) override {} + + bool assertionEnded( AssertionStats const& _assertionStats ) override { + ++counter; + + stream << "# " << currentTestCaseInfo->name << std::endl; + AssertionPrinter printer( stream, _assertionStats, counter ); + printer.print(); + + stream << std::endl; + return true; + } + + void testRunEnded( TestRunStats const& _testRunStats ) override { + printTotals( _testRunStats.totals ); + stream << "\n" << std::endl; + StreamingReporterBase::testRunEnded( _testRunStats ); + } + + private: + std::size_t counter = 0; + class AssertionPrinter { + public: + AssertionPrinter& operator= ( AssertionPrinter const& ) = delete; + AssertionPrinter( AssertionPrinter const& ) = delete; + AssertionPrinter( std::ostream& _stream, AssertionStats const& _stats, std::size_t _counter ) + : stream( _stream ) + , result( _stats.assertionResult ) + , messages( _stats.infoMessages ) + , itMessage( _stats.infoMessages.begin() ) + , printInfoMessages( true ) + , counter(_counter) + {} + + void print() { + itMessage = messages.begin(); + + switch( result.getResultType() ) { + case ResultWas::Ok: + printResultType( passedString() ); + printOriginalExpression(); + printReconstructedExpression(); + if ( ! result.hasExpression() ) + printRemainingMessages( Colour::None ); + else + printRemainingMessages(); + break; + case ResultWas::ExpressionFailed: + if (result.isOk()) { + printResultType(passedString()); + } else { + printResultType(failedString()); + } + printOriginalExpression(); + printReconstructedExpression(); + if (result.isOk()) { + printIssue(" # TODO"); + } + printRemainingMessages(); + break; + case ResultWas::ThrewException: + printResultType( failedString() ); + printIssue( "unexpected exception with message:" ); + printMessage(); + printExpressionWas(); + printRemainingMessages(); + break; + case ResultWas::FatalErrorCondition: + printResultType( failedString() ); + printIssue( "fatal error condition with message:" ); + printMessage(); + printExpressionWas(); + printRemainingMessages(); + break; + case ResultWas::DidntThrowException: + printResultType( failedString() ); + printIssue( "expected exception, got none" ); + printExpressionWas(); + printRemainingMessages(); + break; + case ResultWas::Info: + printResultType( "info" ); + printMessage(); + printRemainingMessages(); + break; + case ResultWas::Warning: + printResultType( "warning" ); + printMessage(); + printRemainingMessages(); + break; + case ResultWas::ExplicitFailure: + printResultType( failedString() ); + printIssue( "explicitly" ); + printRemainingMessages( Colour::None ); + break; + // These cases are here to prevent compiler warnings + case ResultWas::Unknown: + case ResultWas::FailureBit: + case ResultWas::Exception: + printResultType( "** internal error **" ); + break; + } + } + + private: + static Colour::Code dimColour() { return Colour::FileName; } + + static const char* failedString() { return "not ok"; } + static const char* passedString() { return "ok"; } + + void printSourceInfo() const { + Colour colourGuard( dimColour() ); + stream << result.getSourceInfo() << ":"; + } + + void printResultType( std::string const& passOrFail ) const { + if( !passOrFail.empty() ) { + stream << passOrFail << ' ' << counter << " -"; + } + } + + void printIssue( std::string const& issue ) const { + stream << " " << issue; + } + + void printExpressionWas() { + if( result.hasExpression() ) { + stream << ";"; + { + Colour colour( dimColour() ); + stream << " expression was:"; + } + printOriginalExpression(); + } + } + + void printOriginalExpression() const { + if( result.hasExpression() ) { + stream << " " << result.getExpression(); + } + } + + void printReconstructedExpression() const { + if( result.hasExpandedExpression() ) { + { + Colour colour( dimColour() ); + stream << " for: "; + } + std::string expr = result.getExpandedExpression(); + std::replace( expr.begin(), expr.end(), '\n', ' '); + stream << expr; + } + } + + void printMessage() { + if ( itMessage != messages.end() ) { + stream << " '" << itMessage->message << "'"; + ++itMessage; + } + } + + void printRemainingMessages( Colour::Code colour = dimColour() ) { + if (itMessage == messages.end()) { + return; + } + + const auto itEnd = messages.cend(); + const auto N = static_cast( std::distance( itMessage, itEnd ) ); + + { + Colour colourGuard( colour ); + stream << " with " << pluralise( N, "message" ) << ":"; + } + + while( itMessage != itEnd ) { + // If this assertion is a warning ignore any INFO messages + if( printInfoMessages || itMessage->type != ResultWas::Info ) { + stream << " '" << itMessage->message << "'"; + if ( ++itMessage != itEnd ) { + Colour colourGuard( dimColour() ); + stream << " and"; + } + continue; + } + ++itMessage; + } + } + + private: + std::ostream& stream; + AssertionResult const& result; + std::vector messages; + std::vector::const_iterator itMessage; + bool printInfoMessages; + std::size_t counter; + }; + + void printTotals( const Totals& totals ) const { + stream << "1.." << totals.assertions.total(); + if( totals.testCases.total() == 0 ) { + stream << " # Skipped: No tests ran."; + } + } + }; + +#ifdef CATCH_IMPL + TAPReporter::~TAPReporter() {} +#endif + + CATCH_REGISTER_REPORTER( "tap", TAPReporter ) + +} // end namespace Catch + +#endif // TWOBLUECUBES_CATCH_REPORTER_TAP_HPP_INCLUDED diff --git a/third_party/catch2/include/catch2/catch_reporter_teamcity.hpp b/third_party/catch2/include/catch2/catch_reporter_teamcity.hpp index 47b7e4aac3..5c985d2cc1 100644 --- a/third_party/catch2/include/catch2/catch_reporter_teamcity.hpp +++ b/third_party/catch2/include/catch2/catch_reporter_teamcity.hpp @@ -1,219 +1,219 @@ -/* - * Created by Phil Nash on 19th December 2014 - * Copyright 2014 Two Blue Cubes Ltd. All rights reserved. - * - * Distributed under the Boost Software License, Version 1.0. (See accompanying - * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) - */ -#ifndef TWOBLUECUBES_CATCH_REPORTER_TEAMCITY_HPP_INCLUDED -#define TWOBLUECUBES_CATCH_REPORTER_TEAMCITY_HPP_INCLUDED - -// Don't #include any Catch headers here - we can assume they are already -// included before this header. -// This is not good practice in general but is necessary in this case so this -// file can be distributed as a single header that works with the main -// Catch single header. - -#include - -#ifdef __clang__ -# pragma clang diagnostic push -# pragma clang diagnostic ignored "-Wpadded" -#endif - -namespace Catch { - - struct TeamCityReporter : StreamingReporterBase { - TeamCityReporter( ReporterConfig const& _config ) - : StreamingReporterBase( _config ) - { - m_reporterPrefs.shouldRedirectStdOut = true; - } - - static std::string escape( std::string const& str ) { - std::string escaped = str; - replaceInPlace( escaped, "|", "||" ); - replaceInPlace( escaped, "'", "|'" ); - replaceInPlace( escaped, "\n", "|n" ); - replaceInPlace( escaped, "\r", "|r" ); - replaceInPlace( escaped, "[", "|[" ); - replaceInPlace( escaped, "]", "|]" ); - return escaped; - } - ~TeamCityReporter() override; - - static std::string getDescription() { - return "Reports test results as TeamCity service messages"; - } - - void skipTest( TestCaseInfo const& /* testInfo */ ) override { - } - - void noMatchingTestCases( std::string const& /* spec */ ) override {} - - void testGroupStarting( GroupInfo const& groupInfo ) override { - StreamingReporterBase::testGroupStarting( groupInfo ); - stream << "##teamcity[testSuiteStarted name='" - << escape( groupInfo.name ) << "']\n"; - } - void testGroupEnded( TestGroupStats const& testGroupStats ) override { - StreamingReporterBase::testGroupEnded( testGroupStats ); - stream << "##teamcity[testSuiteFinished name='" - << escape( testGroupStats.groupInfo.name ) << "']\n"; - } - - - void assertionStarting( AssertionInfo const& ) override {} - - bool assertionEnded( AssertionStats const& assertionStats ) override { - AssertionResult const& result = assertionStats.assertionResult; - if( !result.isOk() ) { - - ReusableStringStream msg; - if( !m_headerPrintedForThisSection ) - printSectionHeader( msg.get() ); - m_headerPrintedForThisSection = true; - - msg << result.getSourceInfo() << "\n"; - - switch( result.getResultType() ) { - case ResultWas::ExpressionFailed: - msg << "expression failed"; - break; - case ResultWas::ThrewException: - msg << "unexpected exception"; - break; - case ResultWas::FatalErrorCondition: - msg << "fatal error condition"; - break; - case ResultWas::DidntThrowException: - msg << "no exception was thrown where one was expected"; - break; - case ResultWas::ExplicitFailure: - msg << "explicit failure"; - break; - - // We shouldn't get here because of the isOk() test - case ResultWas::Ok: - case ResultWas::Info: - case ResultWas::Warning: - CATCH_ERROR( "Internal error in TeamCity reporter" ); - // These cases are here to prevent compiler warnings - case ResultWas::Unknown: - case ResultWas::FailureBit: - case ResultWas::Exception: - CATCH_ERROR( "Not implemented" ); - } - if( assertionStats.infoMessages.size() == 1 ) - msg << " with message:"; - if( assertionStats.infoMessages.size() > 1 ) - msg << " with messages:"; - for( auto const& messageInfo : assertionStats.infoMessages ) - msg << "\n \"" << messageInfo.message << "\""; - - - if( result.hasExpression() ) { - msg << - "\n " << result.getExpressionInMacro() << "\n" - "with expansion:\n" << - " " << result.getExpandedExpression() << "\n"; - } - - if( currentTestCaseInfo->okToFail() ) { - msg << "- failure ignore as test marked as 'ok to fail'\n"; - stream << "##teamcity[testIgnored" - << " name='" << escape( currentTestCaseInfo->name )<< "'" - << " message='" << escape( msg.str() ) << "'" - << "]\n"; - } - else { - stream << "##teamcity[testFailed" - << " name='" << escape( currentTestCaseInfo->name )<< "'" - << " message='" << escape( msg.str() ) << "'" - << "]\n"; - } - } - stream.flush(); - return true; - } - - void sectionStarting( SectionInfo const& sectionInfo ) override { - m_headerPrintedForThisSection = false; - StreamingReporterBase::sectionStarting( sectionInfo ); - } - - void testCaseStarting( TestCaseInfo const& testInfo ) override { - m_testTimer.start(); - StreamingReporterBase::testCaseStarting( testInfo ); - stream << "##teamcity[testStarted name='" - << escape( testInfo.name ) << "']\n"; - stream.flush(); - } - - void testCaseEnded( TestCaseStats const& testCaseStats ) override { - StreamingReporterBase::testCaseEnded( testCaseStats ); - if( !testCaseStats.stdOut.empty() ) - stream << "##teamcity[testStdOut name='" - << escape( testCaseStats.testInfo.name ) - << "' out='" << escape( testCaseStats.stdOut ) << "']\n"; - if( !testCaseStats.stdErr.empty() ) - stream << "##teamcity[testStdErr name='" - << escape( testCaseStats.testInfo.name ) - << "' out='" << escape( testCaseStats.stdErr ) << "']\n"; - stream << "##teamcity[testFinished name='" - << escape( testCaseStats.testInfo.name ) << "' duration='" - << m_testTimer.getElapsedMilliseconds() << "']\n"; - stream.flush(); - } - - private: - void printSectionHeader( std::ostream& os ) { - assert( !m_sectionStack.empty() ); - - if( m_sectionStack.size() > 1 ) { - os << getLineOfChars<'-'>() << "\n"; - - std::vector::const_iterator - it = m_sectionStack.begin()+1, // Skip first section (test case) - itEnd = m_sectionStack.end(); - for( ; it != itEnd; ++it ) - printHeaderString( os, it->name ); - os << getLineOfChars<'-'>() << "\n"; - } - - SourceLineInfo lineInfo = m_sectionStack.front().lineInfo; - - os << lineInfo << "\n"; - os << getLineOfChars<'.'>() << "\n\n"; - } - - // if string has a : in first line will set indent to follow it on - // subsequent lines - static void printHeaderString( std::ostream& os, std::string const& _string, std::size_t indent = 0 ) { - std::size_t i = _string.find( ": " ); - if( i != std::string::npos ) - i+=2; - else - i = 0; - os << Column( _string ) - .indent( indent+i) - .initialIndent( indent ) << "\n"; - } - private: - bool m_headerPrintedForThisSection = false; - Timer m_testTimer; - }; - -#ifdef CATCH_IMPL - TeamCityReporter::~TeamCityReporter() {} -#endif - - CATCH_REGISTER_REPORTER( "teamcity", TeamCityReporter ) - -} // end namespace Catch - -#ifdef __clang__ -# pragma clang diagnostic pop -#endif - -#endif // TWOBLUECUBES_CATCH_REPORTER_TEAMCITY_HPP_INCLUDED +/* + * Created by Phil Nash on 19th December 2014 + * Copyright 2014 Two Blue Cubes Ltd. All rights reserved. + * + * Distributed under the Boost Software License, Version 1.0. (See accompanying + * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) + */ +#ifndef TWOBLUECUBES_CATCH_REPORTER_TEAMCITY_HPP_INCLUDED +#define TWOBLUECUBES_CATCH_REPORTER_TEAMCITY_HPP_INCLUDED + +// Don't #include any Catch headers here - we can assume they are already +// included before this header. +// This is not good practice in general but is necessary in this case so this +// file can be distributed as a single header that works with the main +// Catch single header. + +#include + +#ifdef __clang__ +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wpadded" +#endif + +namespace Catch { + + struct TeamCityReporter : StreamingReporterBase { + TeamCityReporter( ReporterConfig const& _config ) + : StreamingReporterBase( _config ) + { + m_reporterPrefs.shouldRedirectStdOut = true; + } + + static std::string escape( std::string const& str ) { + std::string escaped = str; + replaceInPlace( escaped, "|", "||" ); + replaceInPlace( escaped, "'", "|'" ); + replaceInPlace( escaped, "\n", "|n" ); + replaceInPlace( escaped, "\r", "|r" ); + replaceInPlace( escaped, "[", "|[" ); + replaceInPlace( escaped, "]", "|]" ); + return escaped; + } + ~TeamCityReporter() override; + + static std::string getDescription() { + return "Reports test results as TeamCity service messages"; + } + + void skipTest( TestCaseInfo const& /* testInfo */ ) override { + } + + void noMatchingTestCases( std::string const& /* spec */ ) override {} + + void testGroupStarting( GroupInfo const& groupInfo ) override { + StreamingReporterBase::testGroupStarting( groupInfo ); + stream << "##teamcity[testSuiteStarted name='" + << escape( groupInfo.name ) << "']\n"; + } + void testGroupEnded( TestGroupStats const& testGroupStats ) override { + StreamingReporterBase::testGroupEnded( testGroupStats ); + stream << "##teamcity[testSuiteFinished name='" + << escape( testGroupStats.groupInfo.name ) << "']\n"; + } + + + void assertionStarting( AssertionInfo const& ) override {} + + bool assertionEnded( AssertionStats const& assertionStats ) override { + AssertionResult const& result = assertionStats.assertionResult; + if( !result.isOk() ) { + + ReusableStringStream msg; + if( !m_headerPrintedForThisSection ) + printSectionHeader( msg.get() ); + m_headerPrintedForThisSection = true; + + msg << result.getSourceInfo() << "\n"; + + switch( result.getResultType() ) { + case ResultWas::ExpressionFailed: + msg << "expression failed"; + break; + case ResultWas::ThrewException: + msg << "unexpected exception"; + break; + case ResultWas::FatalErrorCondition: + msg << "fatal error condition"; + break; + case ResultWas::DidntThrowException: + msg << "no exception was thrown where one was expected"; + break; + case ResultWas::ExplicitFailure: + msg << "explicit failure"; + break; + + // We shouldn't get here because of the isOk() test + case ResultWas::Ok: + case ResultWas::Info: + case ResultWas::Warning: + CATCH_ERROR( "Internal error in TeamCity reporter" ); + // These cases are here to prevent compiler warnings + case ResultWas::Unknown: + case ResultWas::FailureBit: + case ResultWas::Exception: + CATCH_ERROR( "Not implemented" ); + } + if( assertionStats.infoMessages.size() == 1 ) + msg << " with message:"; + if( assertionStats.infoMessages.size() > 1 ) + msg << " with messages:"; + for( auto const& messageInfo : assertionStats.infoMessages ) + msg << "\n \"" << messageInfo.message << "\""; + + + if( result.hasExpression() ) { + msg << + "\n " << result.getExpressionInMacro() << "\n" + "with expansion:\n" << + " " << result.getExpandedExpression() << "\n"; + } + + if( currentTestCaseInfo->okToFail() ) { + msg << "- failure ignore as test marked as 'ok to fail'\n"; + stream << "##teamcity[testIgnored" + << " name='" << escape( currentTestCaseInfo->name )<< "'" + << " message='" << escape( msg.str() ) << "'" + << "]\n"; + } + else { + stream << "##teamcity[testFailed" + << " name='" << escape( currentTestCaseInfo->name )<< "'" + << " message='" << escape( msg.str() ) << "'" + << "]\n"; + } + } + stream.flush(); + return true; + } + + void sectionStarting( SectionInfo const& sectionInfo ) override { + m_headerPrintedForThisSection = false; + StreamingReporterBase::sectionStarting( sectionInfo ); + } + + void testCaseStarting( TestCaseInfo const& testInfo ) override { + m_testTimer.start(); + StreamingReporterBase::testCaseStarting( testInfo ); + stream << "##teamcity[testStarted name='" + << escape( testInfo.name ) << "']\n"; + stream.flush(); + } + + void testCaseEnded( TestCaseStats const& testCaseStats ) override { + StreamingReporterBase::testCaseEnded( testCaseStats ); + if( !testCaseStats.stdOut.empty() ) + stream << "##teamcity[testStdOut name='" + << escape( testCaseStats.testInfo.name ) + << "' out='" << escape( testCaseStats.stdOut ) << "']\n"; + if( !testCaseStats.stdErr.empty() ) + stream << "##teamcity[testStdErr name='" + << escape( testCaseStats.testInfo.name ) + << "' out='" << escape( testCaseStats.stdErr ) << "']\n"; + stream << "##teamcity[testFinished name='" + << escape( testCaseStats.testInfo.name ) << "' duration='" + << m_testTimer.getElapsedMilliseconds() << "']\n"; + stream.flush(); + } + + private: + void printSectionHeader( std::ostream& os ) { + assert( !m_sectionStack.empty() ); + + if( m_sectionStack.size() > 1 ) { + os << getLineOfChars<'-'>() << "\n"; + + std::vector::const_iterator + it = m_sectionStack.begin()+1, // Skip first section (test case) + itEnd = m_sectionStack.end(); + for( ; it != itEnd; ++it ) + printHeaderString( os, it->name ); + os << getLineOfChars<'-'>() << "\n"; + } + + SourceLineInfo lineInfo = m_sectionStack.front().lineInfo; + + os << lineInfo << "\n"; + os << getLineOfChars<'.'>() << "\n\n"; + } + + // if string has a : in first line will set indent to follow it on + // subsequent lines + static void printHeaderString( std::ostream& os, std::string const& _string, std::size_t indent = 0 ) { + std::size_t i = _string.find( ": " ); + if( i != std::string::npos ) + i+=2; + else + i = 0; + os << Column( _string ) + .indent( indent+i) + .initialIndent( indent ) << "\n"; + } + private: + bool m_headerPrintedForThisSection = false; + Timer m_testTimer; + }; + +#ifdef CATCH_IMPL + TeamCityReporter::~TeamCityReporter() {} +#endif + + CATCH_REGISTER_REPORTER( "teamcity", TeamCityReporter ) + +} // end namespace Catch + +#ifdef __clang__ +# pragma clang diagnostic pop +#endif + +#endif // TWOBLUECUBES_CATCH_REPORTER_TEAMCITY_HPP_INCLUDED From 0028e062b8f80ff6762f1517191d0a39e3457ed2 Mon Sep 17 00:00:00 2001 From: Ochi Yuma <44621609+Chizuchizu@users.noreply.github.com> Date: Fri, 9 Sep 2022 08:00:00 +0900 Subject: [PATCH 060/152] third party: add -Wno-unqualified-std-cast-call to fix json11 build (#25686) only for json11 Co-authored-by: Adeeb Shihadeh --- third_party/SConscript | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/third_party/SConscript b/third_party/SConscript index 5a7a62ae5a..e5bbfaa07a 100644 --- a/third_party/SConscript +++ b/third_party/SConscript @@ -1,6 +1,6 @@ Import('env') -env.Library('json11', ['json11/json11.cpp']) +env.Library('json11', ['json11/json11.cpp'], CCFLAGS=env['CCFLAGS'] + ['-Wno-unqualified-std-cast-call']) env.Append(CPPPATH=[Dir('json11')]) env.Library('kaitai', ['kaitai/kaitaistream.cpp'], CPPDEFINES=['KS_STR_ENCODING_NONE']) From 4974ca03a8ec1919075cd41da0a80eb1f32f53dd Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 9 Sep 2022 07:46:52 +0800 Subject: [PATCH 061/152] ui: stop timer if PairingQRWidget is hidden (#25671) --- selfdrive/ui/qt/widgets/prime.cc | 16 +++++++++------- selfdrive/ui/qt/widgets/prime.h | 2 ++ 2 files changed, 11 insertions(+), 7 deletions(-) diff --git a/selfdrive/ui/qt/widgets/prime.cc b/selfdrive/ui/qt/widgets/prime.cc index 5419475262..a8ceee4ca9 100644 --- a/selfdrive/ui/qt/widgets/prime.cc +++ b/selfdrive/ui/qt/widgets/prime.cc @@ -18,21 +18,23 @@ using qrcodegen::QrCode; PairingQRWidget::PairingQRWidget(QWidget* parent) : QWidget(parent) { - QTimer* timer = new QTimer(this); - timer->start(5 * 60 * 1000); + timer = new QTimer(this); connect(timer, &QTimer::timeout, this, &PairingQRWidget::refresh); } void PairingQRWidget::showEvent(QShowEvent *event) { refresh(); + timer->start(5 * 60 * 1000); +} + +void PairingQRWidget::hideEvent(QHideEvent *event) { + timer->stop(); } void PairingQRWidget::refresh() { - if (isVisible()) { - QString pairToken = CommaApi::create_jwt({{"pair", true}}); - QString qrString = "https://connect.comma.ai/?pair=" + pairToken; - this->updateQrCode(qrString); - } + QString pairToken = CommaApi::create_jwt({{"pair", true}}); + QString qrString = "https://connect.comma.ai/?pair=" + pairToken; + this->updateQrCode(qrString); } void PairingQRWidget::updateQrCode(const QString &text) { diff --git a/selfdrive/ui/qt/widgets/prime.h b/selfdrive/ui/qt/widgets/prime.h index ce4baecfa2..0a1d93250d 100644 --- a/selfdrive/ui/qt/widgets/prime.h +++ b/selfdrive/ui/qt/widgets/prime.h @@ -25,8 +25,10 @@ public: private: QPixmap img; + QTimer *timer; void updateQrCode(const QString &text); void showEvent(QShowEvent *event) override; + void hideEvent(QHideEvent *event) override; private slots: void refresh(); From 056b2ec2edb40ce48871975bdbf19d9652c867f3 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 8 Sep 2022 21:43:04 -0700 Subject: [PATCH 062/152] Longcontrol: fix possible reference before assignment (#25715) fix possible reference before assignment --- selfdrive/controls/lib/longcontrol.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index 082e7725d7..f72995d414 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -92,6 +92,7 @@ class LongControl: v_target_1sec = interp(self.CP.longitudinalActuatorDelayUpperBound + t_since_plan + 1.0, T_IDXS[:CONTROL_N], speeds) else: v_target = 0.0 + v_target_now = 0.0 v_target_1sec = 0.0 a_target = 0.0 @@ -132,7 +133,6 @@ class LongControl: feedforward=a_target, freeze_integrator=freeze_integrator) - self.last_output_accel = clip(output_accel, accel_limits[0], accel_limits[1]) return self.last_output_accel From fc3bdef89143721172230bcf413a08a0091bca32 Mon Sep 17 00:00:00 2001 From: calledit <1573053+calledit@users.noreply.github.com> Date: Fri, 9 Sep 2022 20:20:59 +0200 Subject: [PATCH 063/152] VW MQB: Added support for APA racks to EPS configuration tool (#25556) * Added support for APA racks APA steering racks use a different bit to represent whether the ECU should enable steering assist. This change supports those APA steering racks. * Static analysis fix * Static analysis fix2 * Code cleanup * Update selfdrive/debug/vw_mqb_config.py * Apply suggestions from code review Co-authored-by: Jason Young <46612682+jyoung8607@users.noreply.github.com> Co-authored-by: Adeeb Shihadeh Co-authored-by: Jason Young <46612682+jyoung8607@users.noreply.github.com> --- selfdrive/debug/vw_mqb_config.py | 32 +++++++++++++++++++++----------- 1 file changed, 21 insertions(+), 11 deletions(-) diff --git a/selfdrive/debug/vw_mqb_config.py b/selfdrive/debug/vw_mqb_config.py index c55a058159..c1068bf067 100755 --- a/selfdrive/debug/vw_mqb_config.py +++ b/selfdrive/debug/vw_mqb_config.py @@ -67,20 +67,30 @@ if __name__ == "__main__": print("Timeout fetching data from EPS") quit() - coding_variant, current_coding_array = None, None + coding_variant, current_coding_array, coding_byte, coding_bit = None, None, 0, 0 + coding_length = len(current_coding) + # EV_SteerAssisMQB covers the majority of MQB racks (EPS_MQB_ZFLS) - # APA racks (MQB_PP_APA) have a different coding layout, which should - # be easy to support once we identify the specific config bit if odx_file == "EV_SteerAssisMQB\x00": coding_variant = "ZF" - current_coding_array = struct.unpack("!4B", current_coding) - hca_enabled = (current_coding_array[0] & (1 << 4) != 0) - hca_text = ("DISABLED", "ENABLED")[hca_enabled] - print(f" Lane Assist: {hca_text}") + coding_byte = 0 + coding_bit = 4 + + # APA racks (MQB_PP_APA) have a different coding layout + elif odx_file == "EV_SteerAssisVWBSMQBA\x00\x00\x00\x00": + coding_variant = "APA" + coding_byte = 3 + coding_bit = 0 + else: print("Configuration changes not yet supported on this EPS!") quit() + current_coding_array = struct.unpack(f"!{coding_length}B", current_coding) + hca_enabled = (current_coding_array[coding_byte] & (1 << coding_bit) != 0) + hca_text = ("DISABLED", "ENABLED")[hca_enabled] + print(f" Lane Assist: {hca_text}") + try: params = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION).decode("utf-8") param_version_system_params = params[1:3] @@ -101,14 +111,14 @@ if __name__ == "__main__": if args.action in ["enable", "disable"]: print("\nAttempting configuration update") - assert(coding_variant == "ZF") # revisit when we have the APA rack coding bit + assert(coding_variant in ("ZF", "APA")) # ZF EPS config coding length can be anywhere from 1 to 4 bytes, but the # bit we care about is always in the same place in the first byte if args.action == "enable": - new_byte_0 = current_coding_array[0] | (1 << 4) + new_byte = current_coding_array[coding_byte] | (1 << coding_bit) else: - new_byte_0 = current_coding_array[0] & ~(1 << 4) - new_coding = new_byte_0.to_bytes(1, "little") + current_coding[1:] + new_byte = current_coding_array[coding_byte] & ~(1 << coding_bit) + new_coding = current_coding[0:coding_byte] + new_byte.to_bytes(1, "little") + current_coding[coding_byte+1:] try: seed = uds_client.security_access(ACCESS_TYPE_LEVEL_1.REQUEST_SEED) # type: ignore From 0ef6bb48df63fa07609c170b61584a1d3ef8c320 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 9 Sep 2022 16:24:29 -0700 Subject: [PATCH 064/152] FPv2: move car-specific configuration into interfaces (#25711) * Add VMCU address for EV6 * Rename vmcu * add to tests add to tests * rename to more generic name * more explicit * remove print * Like this much better, removes subtle fingerprinting problems * clean up * add test and clean up * remove hyundai stuffs * global * Fpv2Config class * fix missing fw versions from import order * unused * revert for now * test for fpv2 configs with subtests * subtests don't work that way * do toyota as an example * revert revert * do chrysler * do rest * stash * much smaller of a diff than the alternative * remove unused test * fix tests * remove brand from Request * Make StandardQueries class * add missing_ecus clean up * rename file * unused * test implemented * add comment and rename add comment and rename add comment and rename * should be impossible now * this is a fixme * rename to fw_query * rename this too * and this * move vin queries to class * order * can use p16! * formatting * whoops, this wasn't gated on not len(found_versions) * make this clear * Standardize manufacturer software version query --- release/files_common | 1 + selfdrive/car/body/values.py | 15 ++ selfdrive/car/chrysler/values.py | 36 +++ selfdrive/car/ford/values.py | 16 ++ selfdrive/car/fw_query_definitions.py | 66 +++++ selfdrive/car/fw_versions.py | 281 ++------------------- selfdrive/car/honda/values.py | 9 + selfdrive/car/hyundai/values.py | 23 ++ selfdrive/car/mazda/values.py | 16 +- selfdrive/car/nissan/values.py | 32 ++- selfdrive/car/subaru/values.py | 17 +- selfdrive/car/tests/test_fw_fingerprint.py | 19 +- selfdrive/car/toyota/values.py | 30 +++ selfdrive/car/vin.py | 11 +- selfdrive/car/volkswagen/values.py | 26 ++ 15 files changed, 326 insertions(+), 272 deletions(-) create mode 100755 selfdrive/car/fw_query_definitions.py diff --git a/release/files_common b/release/files_common index ad99af752f..be0a4f0f03 100644 --- a/release/files_common +++ b/release/files_common @@ -101,6 +101,7 @@ selfdrive/car/interfaces.py selfdrive/car/vin.py selfdrive/car/disable_ecu.py selfdrive/car/fw_versions.py +selfdrive/car/fw_query_definitions.py selfdrive/car/ecu_addrs.py selfdrive/car/isotp_parallel_query.py selfdrive/car/tests/__init__.py diff --git a/selfdrive/car/body/values.py b/selfdrive/car/body/values.py index 61b72d5ade..66f1b947a8 100644 --- a/selfdrive/car/body/values.py +++ b/selfdrive/car/body/values.py @@ -3,10 +3,13 @@ from typing import Dict from cereal import car from selfdrive.car import dbc_dict from selfdrive.car.docs_definitions import CarInfo +from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + Ecu = car.CarParams.Ecu SPEED_FROM_RPM = 0.008587 + class CarControllerParams: ANGLE_DELTA_BP = [0., 5., 15.] ANGLE_DELTA_V = [5., .8, .15] # windup limit @@ -14,13 +17,25 @@ class CarControllerParams: LKAS_MAX_TORQUE = 1 # A value of 1 is easy to overpower STEER_THRESHOLD = 1.0 + class CAR: BODY = "COMMA BODY" + CAR_INFO: Dict[str, CarInfo] = { CAR.BODY: CarInfo("comma body", package="All"), } +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], + bus=0, + ), + ], +) + FW_VERSIONS = { CAR.BODY: { (Ecu.engine, 0x720, None): [ diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index f495d06a10..3b3fc6e558 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -3,8 +3,11 @@ from enum import Enum from typing import Dict, List, Optional, Union from cereal import car +from panda.python import uds from selfdrive.car import dbc_dict from selfdrive.car.docs_definitions import CarInfo, Harness +from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, p16 + Ecu = car.CarParams.Ecu @@ -129,6 +132,39 @@ FINGERPRINTS = { }], } +CHRYSLER_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xf132) +CHRYSLER_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(0xf132) + +CHRYSLER_SOFTWARE_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) +CHRYSLER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) + +CHRYSLER_RX_OFFSET = -0x280 + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [CHRYSLER_VERSION_REQUEST], + [CHRYSLER_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.srs, Ecu.gateway, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter], + rx_offset=CHRYSLER_RX_OFFSET, + ), + Request( + [CHRYSLER_VERSION_REQUEST], + [CHRYSLER_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.hcp, Ecu.engine, Ecu.transmission], + ), + Request( + [CHRYSLER_SOFTWARE_VERSION_REQUEST], + [CHRYSLER_SOFTWARE_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.transmission], + ), + ], +) + FW_VERSIONS = { CAR.PACIFICA_2019_HYBRID: { (Ecu.hcp, 0x7e2, None): [], diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index 54ff043a33..5820b5c9fd 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -6,6 +6,7 @@ from typing import Dict, List, Union from cereal import car from selfdrive.car import dbc_dict from selfdrive.car.docs_definitions import CarInfo, Harness +from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries Ecu = car.CarParams.Ecu TransmissionType = car.CarParams.TransmissionType @@ -61,6 +62,21 @@ CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { CAR.FOCUS_MK4: FordCarInfo("Ford Focus EU 2019", "Driver Assistance Pack"), } +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine], + ), + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], + bus=0, + whitelist_ecus=[Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.shiftByWire], + ), + ], +) FW_VERSIONS = { CAR.ESCAPE_MK4: { diff --git a/selfdrive/car/fw_query_definitions.py b/selfdrive/car/fw_query_definitions.py new file mode 100755 index 0000000000..c3b74da920 --- /dev/null +++ b/selfdrive/car/fw_query_definitions.py @@ -0,0 +1,66 @@ +#!/usr/bin/env python3 +import capnp +from dataclasses import dataclass, field +import struct +from typing import Dict, List + +import panda.python.uds as uds + + +def p16(val): + return struct.pack("!H", val) + + +class StdQueries: + # FW queries + TESTER_PRESENT_REQUEST = bytes([uds.SERVICE_TYPE.TESTER_PRESENT, 0x0]) + TESTER_PRESENT_RESPONSE = bytes([uds.SERVICE_TYPE.TESTER_PRESENT + 0x40, 0x0]) + + SHORT_TESTER_PRESENT_REQUEST = bytes([uds.SERVICE_TYPE.TESTER_PRESENT]) + SHORT_TESTER_PRESENT_RESPONSE = bytes([uds.SERVICE_TYPE.TESTER_PRESENT + 0x40]) + + DEFAULT_DIAGNOSTIC_REQUEST = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, + uds.SESSION_TYPE.DEFAULT]) + DEFAULT_DIAGNOSTIC_RESPONSE = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, + uds.SESSION_TYPE.DEFAULT, 0x0, 0x32, 0x1, 0xf4]) + + EXTENDED_DIAGNOSTIC_REQUEST = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, + uds.SESSION_TYPE.EXTENDED_DIAGNOSTIC]) + EXTENDED_DIAGNOSTIC_RESPONSE = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, + uds.SESSION_TYPE.EXTENDED_DIAGNOSTIC, 0x0, 0x32, 0x1, 0xf4]) + + MANUFACTURER_SOFTWARE_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER) + MANUFACTURER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER) + + UDS_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) + UDS_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) + + OBD_VERSION_REQUEST = b'\x09\x04' + OBD_VERSION_RESPONSE = b'\x49\x04' + + # VIN queries + OBD_VIN_REQUEST = b'\x09\x02' + OBD_VIN_RESPONSE = b'\x49\x02\x01' + + UDS_VIN_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + p16(uds.DATA_IDENTIFIER_TYPE.VIN) + UDS_VIN_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + p16(uds.DATA_IDENTIFIER_TYPE.VIN) + + +@dataclass +class Request: + request: List[bytes] + response: List[bytes] + whitelist_ecus: List[int] = field(default_factory=list) + rx_offset: int = 0x8 + bus: int = 1 + + +@dataclass +class FwQueryConfig: + requests: List[Request] + # Overrides and removes from essential ecus for specific models and ecus (exact matching) + non_essential_ecus: Dict[capnp.lib.capnp._EnumModule, List[str]] = field(default_factory=dict) diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 376a743dfb..9c0c406f14 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -1,9 +1,7 @@ #!/usr/bin/env python3 -import struct import traceback from collections import defaultdict -from dataclasses import dataclass, field -from typing import Any, List, Optional, Set, Tuple +from typing import Any, Optional, Set, Tuple from tqdm import tqdm import panda.python.uds as uds @@ -12,237 +10,16 @@ from selfdrive.car.ecu_addrs import get_ecu_addrs from selfdrive.car.interfaces import get_interface_attr from selfdrive.car.fingerprints import FW_VERSIONS from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery -from selfdrive.car.toyota.values import CAR as TOYOTA from system.swaglog import cloudlog Ecu = car.CarParams.Ecu ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa] +FW_QUERY_CONFIGS = get_interface_attr('FW_QUERY_CONFIG', ignore_none=True) +VERSIONS = get_interface_attr('FW_VERSIONS', ignore_none=True) -def p16(val): - return struct.pack("!H", val) - - -TESTER_PRESENT_REQUEST = bytes([uds.SERVICE_TYPE.TESTER_PRESENT, 0x0]) -TESTER_PRESENT_RESPONSE = bytes([uds.SERVICE_TYPE.TESTER_PRESENT + 0x40, 0x0]) - -SHORT_TESTER_PRESENT_REQUEST = bytes([uds.SERVICE_TYPE.TESTER_PRESENT]) -SHORT_TESTER_PRESENT_RESPONSE = bytes([uds.SERVICE_TYPE.TESTER_PRESENT + 0x40]) - -DEFAULT_DIAGNOSTIC_REQUEST = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, - uds.SESSION_TYPE.DEFAULT]) -DEFAULT_DIAGNOSTIC_RESPONSE = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, - uds.SESSION_TYPE.DEFAULT, 0x0, 0x32, 0x1, 0xf4]) - -EXTENDED_DIAGNOSTIC_REQUEST = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, - uds.SESSION_TYPE.EXTENDED_DIAGNOSTIC]) -EXTENDED_DIAGNOSTIC_RESPONSE = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, - uds.SESSION_TYPE.EXTENDED_DIAGNOSTIC, 0x0, 0x32, 0x1, 0xf4]) - -UDS_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) -UDS_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) - - -HYUNDAI_VERSION_REQUEST_LONG = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf100) # Long description -HYUNDAI_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) + \ - p16(0xf100) -HYUNDAI_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) - - -TOYOTA_VERSION_REQUEST = b'\x1a\x88\x01' -TOYOTA_VERSION_RESPONSE = b'\x5a\x88\x01' - -VOLKSWAGEN_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_VERSION_NUMBER) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) -VOLKSWAGEN_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) - -OBD_VERSION_REQUEST = b'\x09\x04' -OBD_VERSION_RESPONSE = b'\x49\x04' - -DEFAULT_RX_OFFSET = 0x8 -VOLKSWAGEN_RX_OFFSET = 0x6a - -MAZDA_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER) -MAZDA_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER) - -NISSAN_DIAGNOSTIC_REQUEST_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0xc0]) -NISSAN_DIAGNOSTIC_RESPONSE_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0xc0]) - -NISSAN_VERSION_REQUEST_KWP = b'\x21\x83' -NISSAN_VERSION_RESPONSE_KWP = b'\x61\x83' - -NISSAN_VERSION_REQUEST_STANDARD = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER) -NISSAN_VERSION_RESPONSE_STANDARD = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER) - -NISSAN_RX_OFFSET = 0x20 - -SUBARU_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) -SUBARU_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) - -CHRYSLER_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf132) -CHRYSLER_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(0xf132) - -CHRYSLER_SOFTWARE_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) -CHRYSLER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) - -CHRYSLER_RX_OFFSET = -0x280 - -FORD_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER) -FORD_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER) - - -@dataclass -class Request: - brand: str - request: List[bytes] - response: List[bytes] - whitelist_ecus: List[int] = field(default_factory=list) - rx_offset: int = DEFAULT_RX_OFFSET - bus: int = 1 - - -REQUESTS: List[Request] = [ - # Subaru - Request( - "subaru", - [TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], - [TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], - ), - # Hyundai - Request( - "hyundai", - [HYUNDAI_VERSION_REQUEST_LONG], - [HYUNDAI_VERSION_RESPONSE], - ), - Request( - "hyundai", - [HYUNDAI_VERSION_REQUEST_MULTI], - [HYUNDAI_VERSION_RESPONSE], - ), - # Honda - Request( - "honda", - [UDS_VERSION_REQUEST], - [UDS_VERSION_RESPONSE], - ), - # Toyota - Request( - "toyota", - [SHORT_TESTER_PRESENT_REQUEST, TOYOTA_VERSION_REQUEST], - [SHORT_TESTER_PRESENT_RESPONSE, TOYOTA_VERSION_RESPONSE], - bus=0, - ), - Request( - "toyota", - [SHORT_TESTER_PRESENT_REQUEST, OBD_VERSION_REQUEST], - [SHORT_TESTER_PRESENT_RESPONSE, OBD_VERSION_RESPONSE], - bus=0, - ), - Request( - "toyota", - [TESTER_PRESENT_REQUEST, DEFAULT_DIAGNOSTIC_REQUEST, EXTENDED_DIAGNOSTIC_REQUEST, UDS_VERSION_REQUEST], - [TESTER_PRESENT_RESPONSE, DEFAULT_DIAGNOSTIC_RESPONSE, EXTENDED_DIAGNOSTIC_RESPONSE, UDS_VERSION_RESPONSE], - bus=0, - ), - # Volkswagen - Request( - "volkswagen", - [VOLKSWAGEN_VERSION_REQUEST_MULTI], - [VOLKSWAGEN_VERSION_RESPONSE], - whitelist_ecus=[Ecu.srs, Ecu.eps, Ecu.fwdRadar], - rx_offset=VOLKSWAGEN_RX_OFFSET, - ), - Request( - "volkswagen", - [VOLKSWAGEN_VERSION_REQUEST_MULTI], - [VOLKSWAGEN_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine, Ecu.transmission], - ), - # Mazda - Request( - "mazda", - [MAZDA_VERSION_REQUEST], - [MAZDA_VERSION_RESPONSE], - ), - # Nissan - Request( - "nissan", - [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], - [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], - ), - Request( - "nissan", - [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], - [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], - rx_offset=NISSAN_RX_OFFSET, - ), - Request( - "nissan", - [NISSAN_VERSION_REQUEST_STANDARD], - [NISSAN_VERSION_RESPONSE_STANDARD], - rx_offset=NISSAN_RX_OFFSET, - ), - # Body - Request( - "body", - [TESTER_PRESENT_REQUEST, UDS_VERSION_REQUEST], - [TESTER_PRESENT_RESPONSE, UDS_VERSION_RESPONSE], - bus=0, - ), - # Chrysler / FCA / Stellantis - Request( - "chrysler", - [CHRYSLER_VERSION_REQUEST], - [CHRYSLER_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.srs, Ecu.gateway, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter], - rx_offset=CHRYSLER_RX_OFFSET, - ), - Request( - "chrysler", - [CHRYSLER_VERSION_REQUEST], - [CHRYSLER_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.hcp, Ecu.engine, Ecu.transmission], - ), - Request( - "chrysler", - [CHRYSLER_SOFTWARE_VERSION_REQUEST], - [CHRYSLER_SOFTWARE_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine, Ecu.transmission], - ), - # Ford - Request( - "ford", - [TESTER_PRESENT_REQUEST, FORD_VERSION_REQUEST], - [TESTER_PRESENT_RESPONSE, FORD_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine], - ), - Request( - "ford", - [TESTER_PRESENT_REQUEST, FORD_VERSION_REQUEST], - [TESTER_PRESENT_RESPONSE, FORD_VERSION_RESPONSE], - bus=0, - whitelist_ecus=[Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.shiftByWire], - ), -] +MODEL_TO_BRAND = {c: b for b, e in VERSIONS.items() for c in e} +REQUESTS = [(brand, r) for brand, config in FW_QUERY_CONFIGS.items() for r in config.requests] def chunks(l, n=128): @@ -261,9 +38,8 @@ def build_fw_dict(fw_versions, filter_brand=None): def get_brand_addrs(): - versions = get_interface_attr('FW_VERSIONS', ignore_none=True) brand_addrs = defaultdict(set) - for brand, cars in versions.items(): + for brand, cars in VERSIONS.items(): for fw in cars.values(): brand_addrs[brand] |= {(addr, sub_addr) for _, addr, sub_addr in fw.keys()} return brand_addrs @@ -325,19 +101,19 @@ def match_fw_to_car_exact(fw_versions_dict): for candidate, fws in candidates.items(): for ecu, expected_versions in fws.items(): + config = FW_QUERY_CONFIGS[MODEL_TO_BRAND[candidate]] ecu_type = ecu[0] addr = ecu[1:] - found_versions = fw_versions_dict.get(addr, set()) - if ecu_type == Ecu.abs and candidate in (TOYOTA.RAV4, TOYOTA.COROLLA, TOYOTA.HIGHLANDER, TOYOTA.SIENNA, TOYOTA.LEXUS_IS) and not len(found_versions): - continue - # On some Toyota models, the engine can show on two different addresses - if ecu_type == Ecu.engine and candidate in (TOYOTA.CAMRY, TOYOTA.COROLLA_TSS2, TOYOTA.CHR, TOYOTA.LEXUS_IS) and not len(found_versions): - continue + found_versions = fw_versions_dict.get(addr, set()) + if not len(found_versions): + # Some models can sometimes miss an ecu, or show on two different addresses + if candidate in config.non_essential_ecus.get(ecu_type, []): + continue - # Ignore non essential ecus - if ecu_type not in ESSENTIAL_ECUS and not len(found_versions): - continue + # Ignore non essential ecus + if ecu_type not in ESSENTIAL_ECUS: + continue # Virtual debug ecu doesn't need to match the database if ecu_type == Ecu.debug: @@ -358,11 +134,10 @@ def match_fw_to_car(fw_versions, allow_exact=True, allow_fuzzy=True): if allow_fuzzy: exact_matches.append((False, match_fw_to_car_fuzzy)) - brands = get_interface_attr('FW_VERSIONS', ignore_none=True).keys() for exact_match, match_func in exact_matches: # For each brand, attempt to fingerprint using all FW returned from its queries matches = set() - for brand in brands: + for brand in VERSIONS.keys(): fw_versions_dict = build_fw_dict(fw_versions, filter_brand=brand) matches |= match_func(fw_versions_dict) @@ -376,13 +151,9 @@ def get_present_ecus(logcan, sendcan): queries = list() parallel_queries = list() responses = set() - versions = get_interface_attr('FW_VERSIONS', ignore_none=True) - - for r in REQUESTS: - if r.brand not in versions: - continue - for brand_versions in versions[r.brand].values(): + for brand, r in REQUESTS: + for brand_versions in VERSIONS[brand].values(): for ecu_type, addr, sub_addr in brand_versions: # Only query ecus in whitelist if whitelist is not empty if len(r.whitelist_ecus) == 0 or ecu_type in r.whitelist_ecus: @@ -411,9 +182,9 @@ def get_brand_ecu_matches(ecu_rx_addrs): """Returns dictionary of brands and matches with ECUs in their FW versions""" brand_addrs = get_brand_addrs() - brand_matches = {r.brand: set() for r in REQUESTS} + brand_matches = {brand: set() for brand, _ in REQUESTS} - brand_rx_offsets = set((r.brand, r.rx_offset) for r in REQUESTS) + brand_rx_offsets = set((brand, r.rx_offset) for brand, r in REQUESTS) for addr, sub_addr, _ in ecu_rx_addrs: # Since we can't know what request an ecu responded to, add matches for all possible rx offsets for brand, rx_offset in brand_rx_offsets: @@ -442,7 +213,7 @@ def get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs, timeout=0.1, debug=Fa def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1, debug=False, progress=False): - versions = get_interface_attr('FW_VERSIONS', ignore_none=True) + versions = VERSIONS.copy() if query_brand is not None: versions = {query_brand: versions[query_brand]} @@ -473,12 +244,12 @@ def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1, # Get versions and build capnp list to put into CarParams car_fw = [] - requests = [r for r in REQUESTS if query_brand is None or r.brand == query_brand] + requests = [(brand, r) for brand, r in REQUESTS if query_brand is None or brand == query_brand] for addr in tqdm(addrs, disable=not progress): for addr_chunk in chunks(addr): - for r in requests: + for brand, r in requests: try: - addrs = [(a, s) for (b, a, s) in addr_chunk if b in (r.brand, 'any') and + addrs = [(a, s) for (b, a, s) in addr_chunk if b in (brand, 'any') and (len(r.whitelist_ecus) == 0 or ecu_types[(b, a, s)] in r.whitelist_ecus)] if addrs: @@ -486,12 +257,12 @@ def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1, for (addr, rx_addr), version in query.get_data(timeout).items(): f = car.CarParams.CarFw.new_message() - f.ecu = ecu_types.get((r.brand, addr[0], addr[1]), Ecu.unknown) + f.ecu = ecu_types.get((brand, addr[0], addr[1]), Ecu.unknown) f.fwVersion = version f.address = addr[0] f.responseAddress = rx_addr f.request = r.request - f.brand = r.brand + f.brand = brand f.bus = r.bus if addr[1] is not None: diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index ad4f73c011..43c3c77369 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -6,6 +6,7 @@ from cereal import car from common.conversions import Conversions as CV from selfdrive.car import dbc_dict from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness +from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries Ecu = car.CarParams.Ecu VisualAlert = car.CarControl.HUDControl.VisualAlert @@ -142,6 +143,14 @@ CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = { CAR.HONDA_E: HondaCarInfo("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), } +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [StdQueries.UDS_VERSION_REQUEST], + [StdQueries.UDS_VERSION_RESPONSE], + ), + ], +) FW_VERSIONS = { CAR.ACCORD: { diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index e2374a1c09..4225826c1d 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -3,9 +3,12 @@ from dataclasses import dataclass from typing import Dict, List, Optional, Union from cereal import car +from panda.python import uds from common.conversions import Conversions as CV from selfdrive.car import dbc_dict from selfdrive.car.docs_definitions import CarInfo, Harness +from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, p16 + Ecu = car.CarParams.Ecu @@ -272,6 +275,26 @@ FINGERPRINTS = { }], } +HYUNDAI_VERSION_REQUEST_LONG = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xf100) # Long description +HYUNDAI_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \ + p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) + \ + p16(0xf100) +HYUNDAI_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [HYUNDAI_VERSION_REQUEST_LONG], + [HYUNDAI_VERSION_RESPONSE], + ), + Request( + [HYUNDAI_VERSION_REQUEST_MULTI], + [HYUNDAI_VERSION_RESPONSE], + ), + ], +) FW_VERSIONS = { CAR.IONIQ: { diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 95f140422e..9befad4d0b 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -2,9 +2,11 @@ from dataclasses import dataclass from enum import Enum from typing import Dict, List, Union +from cereal import car from selfdrive.car import dbc_dict from selfdrive.car.docs_definitions import CarInfo, Harness -from cereal import car +from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + Ecu = car.CarParams.Ecu @@ -50,6 +52,7 @@ class LKAS_LIMITS: DISABLE_SPEED = 45 # kph ENABLE_SPEED = 52 # kph + class Buttons: NONE = 0 SET_PLUS = 1 @@ -58,8 +61,17 @@ class Buttons: CANCEL = 4 +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], + [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], + ), + ], +) + FW_VERSIONS = { - CAR.CX5_2022 : { + CAR.CX5_2022: { (Ecu.eps, 0x730, None): [ b'KSD5-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index 440c682490..09bd7ca838 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -2,9 +2,12 @@ from dataclasses import dataclass from typing import Dict, List, Optional, Union from enum import Enum +from cereal import car +from panda.python import uds from selfdrive.car import dbc_dict from selfdrive.car.docs_definitions import CarInfo, Harness -from cereal import car +from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + Ecu = car.CarParams.Ecu @@ -75,6 +78,33 @@ FINGERPRINTS = { ] } +NISSAN_DIAGNOSTIC_REQUEST_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0xc0]) +NISSAN_DIAGNOSTIC_RESPONSE_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0xc0]) + +NISSAN_VERSION_REQUEST_KWP = b'\x21\x83' +NISSAN_VERSION_RESPONSE_KWP = b'\x61\x83' + +NISSAN_RX_OFFSET = 0x20 + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], + [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], + ), + Request( + [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], + [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], + rx_offset=NISSAN_RX_OFFSET, + ), + Request( + [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], + [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], + rx_offset=NISSAN_RX_OFFSET, + ), + ], +) + FW_VERSIONS = { CAR.ALTIMA: { (Ecu.fwdCamera, 0x707, None): [ diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 53dd4a763f..58fe111fbd 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -2,9 +2,11 @@ from dataclasses import dataclass from enum import Enum from typing import Dict, List, Union +from cereal import car +from panda.python import uds from selfdrive.car import dbc_dict from selfdrive.car.docs_definitions import CarInfo, Harness -from cereal import car +from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 Ecu = car.CarParams.Ecu @@ -71,6 +73,19 @@ CAR_INFO: Dict[str, Union[SubaruCarInfo, List[SubaruCarInfo]]] = { CAR.OUTBACK_PREGLOBAL_2018: SubaruCarInfo("Subaru Outback 2018-19"), } +SUBARU_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) +SUBARU_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], + ), + ], +) FW_VERSIONS = { CAR.ASCENT: { diff --git a/selfdrive/car/tests/test_fw_fingerprint.py b/selfdrive/car/tests/test_fw_fingerprint.py index 2a47c60bf3..f0d2744a98 100755 --- a/selfdrive/car/tests/test_fw_fingerprint.py +++ b/selfdrive/car/tests/test_fw_fingerprint.py @@ -6,7 +6,7 @@ from parameterized import parameterized from cereal import car from selfdrive.car.car_helpers import get_interface_attr, interfaces from selfdrive.car.fingerprints import FW_VERSIONS -from selfdrive.car.fw_versions import REQUESTS, match_fw_to_car +from selfdrive.car.fw_versions import FW_QUERY_CONFIGS, match_fw_to_car CarFw = car.CarParams.CarFw Ecu = car.CarParams.Ecu @@ -59,14 +59,25 @@ class TestFwFingerprint(unittest.TestCase): for ecu in ecus.keys(): self.assertNotEqual(ecu[0], Ecu.transmission, f"{car_model}: Blacklisted ecu: (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])})") + def test_missing_versions_and_configs(self): + brand_versions = set(VERSIONS.keys()) + brand_configs = set(FW_QUERY_CONFIGS.keys()) + if len(brand_configs - brand_versions): + with self.subTest(): + self.fail(f"Brands do not implement FW_VERSIONS: {brand_configs - brand_versions}") + + if len(brand_versions - brand_configs): + with self.subTest(): + self.fail(f"Brands do not implement FW_QUERY_CONFIG: {brand_versions - brand_configs}") + def test_fw_request_ecu_whitelist(self): - for brand in set(r.brand for r in REQUESTS): + for brand, config in FW_QUERY_CONFIGS.items(): with self.subTest(brand=brand): - whitelisted_ecus = [ecu for r in REQUESTS for ecu in r.whitelist_ecus if r.brand == brand] + whitelisted_ecus = set([ecu for r in config.requests for ecu in r.whitelist_ecus]) brand_ecus = set([fw[0] for car_fw in VERSIONS[brand].values() for fw in car_fw]) # each ecu in brand's fw versions needs to be whitelisted at least once - ecus_not_whitelisted = set(brand_ecus) - set(whitelisted_ecus) + ecus_not_whitelisted = brand_ecus - whitelisted_ecus ecu_strings = ", ".join([f'Ecu.{ECU_NAME[ecu]}' for ecu in ecus_not_whitelisted]) self.assertFalse(len(whitelisted_ecus) and len(ecus_not_whitelisted), diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index af2fc9f56e..94fbdc8bf2 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -7,6 +7,7 @@ from cereal import car from common.conversions import Conversions as CV from selfdrive.car import dbc_dict from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness +from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries Ecu = car.CarParams.Ecu MIN_ACC_SPEED = 19. * CV.MPH_TO_MS @@ -198,6 +199,35 @@ STATIC_DSU_MSGS = [ (0x4CB, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), 0, 100, b'\x0c\x00\x00\x00\x00\x00\x00\x00'), ] +TOYOTA_VERSION_REQUEST = b'\x1a\x88\x01' +TOYOTA_VERSION_RESPONSE = b'\x5a\x88\x01' + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [StdQueries.SHORT_TESTER_PRESENT_REQUEST, TOYOTA_VERSION_REQUEST], + [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, TOYOTA_VERSION_RESPONSE], + bus=0, + ), + Request( + [StdQueries.SHORT_TESTER_PRESENT_REQUEST, StdQueries.OBD_VERSION_REQUEST], + [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, StdQueries.OBD_VERSION_RESPONSE], + bus=0, + ), + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.DEFAULT_DIAGNOSTIC_REQUEST, StdQueries.EXTENDED_DIAGNOSTIC_REQUEST, StdQueries.UDS_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.DEFAULT_DIAGNOSTIC_RESPONSE, StdQueries.EXTENDED_DIAGNOSTIC_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], + bus=0, + ), + ], + non_essential_ecus={ + # FIXME: On some models, abs can sometimes be missing + Ecu.abs: [CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_IS], + # On some models, the engine can show on two different addresses + Ecu.engine: [CAR.CAMRY, CAR.COROLLA_TSS2, CAR.CHR, CAR.LEXUS_IS], + } +) + FW_VERSIONS = { CAR.AVALON: { (Ecu.abs, 0x7b0, None): [ diff --git a/selfdrive/car/vin.py b/selfdrive/car/vin.py index ae3aa675c7..fba0c54eba 100755 --- a/selfdrive/car/vin.py +++ b/selfdrive/car/vin.py @@ -1,19 +1,12 @@ #!/usr/bin/env python3 import re -import struct import traceback import cereal.messaging as messaging -import panda.python.uds as uds from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery +from selfdrive.car.fw_query_definitions import StdQueries from system.swaglog import cloudlog -OBD_VIN_REQUEST = b'\x09\x02' -OBD_VIN_RESPONSE = b'\x49\x02\x01' - -UDS_VIN_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + struct.pack("!H", uds.DATA_IDENTIFIER_TYPE.VIN) -UDS_VIN_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + struct.pack("!H", uds.DATA_IDENTIFIER_TYPE.VIN) - VIN_UNKNOWN = "0" * 17 VIN_RE = "[A-HJ-NPR-Z0-9]{17}" @@ -25,7 +18,7 @@ def is_valid_vin(vin: str): def get_vin(logcan, sendcan, bus, timeout=0.1, retry=5, debug=False): addrs = [0x7e0, 0x7e2, 0x18da10f1, 0x18da0ef1] # engine, VMCU, 29-bit engine, PGM-FI for i in range(retry): - for request, response in ((UDS_VIN_REQUEST, UDS_VIN_RESPONSE), (OBD_VIN_REQUEST, OBD_VIN_RESPONSE)): + for request, response in ((StdQueries.UDS_VIN_REQUEST, StdQueries.UDS_VIN_RESPONSE), (StdQueries.OBD_VIN_REQUEST, StdQueries.OBD_VIN_RESPONSE)): try: query = IsoTpParallelQuery(sendcan, logcan, bus, addrs, [request, ], [response, ], debug=debug) for (addr, rx_addr), vin in query.get_data(timeout).items(): diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 62d6dcddaf..eaf6c042de 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -4,9 +4,11 @@ from enum import Enum from typing import Dict, List, Union from cereal import car +from panda.python import uds from opendbc.can.can_define import CANDefine from selfdrive.car import dbc_dict from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness +from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, p16 Ecu = car.CarParams.Ecu NetworkLocation = car.CarParams.NetworkLocation @@ -243,6 +245,30 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = { # ECU SW part numbers are invalid for vehicle ID and compatibility checks. Try to have # them repaired by the tuner before including them in openpilot. +VOLKSWAGEN_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \ + p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_VERSION_NUMBER) + \ + p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) +VOLKSWAGEN_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + +VOLKSWAGEN_RX_OFFSET = 0x6a + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [VOLKSWAGEN_VERSION_REQUEST_MULTI], + [VOLKSWAGEN_VERSION_RESPONSE], + whitelist_ecus=[Ecu.srs, Ecu.eps, Ecu.fwdRadar], + rx_offset=VOLKSWAGEN_RX_OFFSET, + ), + Request( + [VOLKSWAGEN_VERSION_REQUEST_MULTI], + [VOLKSWAGEN_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.transmission], + ), + ], +) + FW_VERSIONS = { CAR.ARTEON_MK1: { (Ecu.engine, 0x7e0, None): [ From aea1a0d5e684daf7682703174233390b0cf79c83 Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Fri, 9 Sep 2022 22:38:00 -0700 Subject: [PATCH 065/152] port OX03C10 (#25161) * start porting OS04C10 * something * is the pll why this doesn't work * understand plls, still doesn't work * work * weee something * working? * timing * encoderd works with less cameras * 1928 * flip image * color balance * adjust black level * extra height maybe * cleanups * clean up sensor i2c * sensors * approx 20fps * remove mirror * 50ms, no fsin yet * remove imx390 support * some attempt at AE * linearize the response * OX changes (#25697) * organize * wb * best effort but probably messed up by artifacts * multicam sync Co-authored-by: Comma Device * clean up * more * fix multiexposure * start porting OS04C10 * something * is the pll why this doesn't work * understand plls, still doesn't work * work * weee something * working? * timing * encoderd works with less cameras * 1928 * flip image * color balance * adjust black level * extra height maybe * cleanups * clean up sensor i2c * sensors * approx 20fps * remove mirror * 50ms, no fsin yet * remove imx390 support * some attempt at AE * linearize the response * OX changes (#25697) * organize * wb * best effort but probably messed up by artifacts * multicam sync Co-authored-by: Comma Device * clean up * more * fix multiexposure * unbroken AE * oops * sort of good AE * both should work 1 * open then init * fix debayer * rename * fix test build Co-authored-by: Comma Device Co-authored-by: ZwX1616 Co-authored-by: Adeeb Shihadeh --- selfdrive/loggerd/encoderd.cc | 28 +- system/camerad/cameras/camera_common.cc | 6 +- system/camerad/cameras/camera_common.h | 2 +- system/camerad/cameras/camera_qcom2.cc | 251 +++++--- system/camerad/cameras/camera_qcom2.h | 22 +- system/camerad/cameras/real_debayer.cl | 35 ++ system/camerad/cameras/sensor2_i2c.h | 772 +++++++++++++++++++++++- system/camerad/test/camera_test.h | 2 + 8 files changed, 989 insertions(+), 129 deletions(-) diff --git a/selfdrive/loggerd/encoderd.cc b/selfdrive/loggerd/encoderd.cc index 9bd8e2f1d4..db5f4b61ab 100644 --- a/selfdrive/loggerd/encoderd.cc +++ b/selfdrive/loggerd/encoderd.cc @@ -52,17 +52,23 @@ void encoder_thread(EncoderdState *s, const LogCameraInfo &cam_info) { VisionBuf buf_info = vipc_client.buffers[0]; LOGW("encoder %s init %dx%d", cam_info.filename, buf_info.width, buf_info.height); - // main encoder - encoders.push_back(new Encoder(cam_info.filename, cam_info.type, buf_info.width, buf_info.height, - cam_info.fps, cam_info.bitrate, - cam_info.is_h265 ? cereal::EncodeIndex::Type::FULL_H_E_V_C : cereal::EncodeIndex::Type::QCAMERA_H264, - buf_info.width, buf_info.height, false)); - // qcamera encoder - if (cam_info.has_qcamera) { - encoders.push_back(new Encoder(qcam_info.filename, cam_info.type, buf_info.width, buf_info.height, - qcam_info.fps, qcam_info.bitrate, - qcam_info.is_h265 ? cereal::EncodeIndex::Type::FULL_H_E_V_C : cereal::EncodeIndex::Type::QCAMERA_H264, - qcam_info.frame_width, qcam_info.frame_height, false)); + if (buf_info.width > 0 && buf_info.height > 0) { + // main encoder + encoders.push_back(new Encoder(cam_info.filename, cam_info.type, buf_info.width, buf_info.height, + cam_info.fps, cam_info.bitrate, + cam_info.is_h265 ? cereal::EncodeIndex::Type::FULL_H_E_V_C : cereal::EncodeIndex::Type::QCAMERA_H264, + buf_info.width, buf_info.height, false)); + // qcamera encoder + if (cam_info.has_qcamera) { + encoders.push_back(new Encoder(qcam_info.filename, cam_info.type, buf_info.width, buf_info.height, + qcam_info.fps, qcam_info.bitrate, + qcam_info.is_h265 ? cereal::EncodeIndex::Type::FULL_H_E_V_C : cereal::EncodeIndex::Type::QCAMERA_H264, + qcam_info.frame_width, qcam_info.frame_height, false)); + } + } else { + LOGE("not initting empty encoder"); + s->max_waiting--; + break; } } diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index 1d4ecd526a..313af00b5a 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -36,10 +36,10 @@ public: "-cl-fast-relaxed-math -cl-denorms-are-zero " "-DFRAME_WIDTH=%d -DFRAME_HEIGHT=%d -DFRAME_STRIDE=%d -DFRAME_OFFSET=%d " "-DRGB_WIDTH=%d -DRGB_HEIGHT=%d -DRGB_STRIDE=%d -DYUV_STRIDE=%d -DUV_OFFSET=%d " - "-DCAM_NUM=%d%s", + "-DIS_OX=%d -DCAM_NUM=%d%s", ci->frame_width, ci->frame_height, ci->frame_stride, ci->frame_offset, b->rgb_width, b->rgb_height, b->rgb_stride, buf_width, uv_offset, - s->camera_num, s->camera_num==1 ? " -DVIGNETTING" : ""); + s->camera_id==CAMERA_ID_OX03C10 ? 1 : 0, s->camera_num, s->camera_num==1 ? " -DVIGNETTING" : ""); const char *cl_file = "cameras/real_debayer.cl"; cl_program prg_debayer = cl_program_from_file(context, device_id, cl_file, args); krnl_ = CL_CHECK_ERR(clCreateKernel(prg_debayer, "debayer10", &err)); @@ -348,8 +348,8 @@ void camerad_thread() { MultiCameraState cameras = {}; VisionIpcServer vipc_server("camerad", device_id, context); - cameras_init(&vipc_server, &cameras, device_id, context); cameras_open(&cameras); + cameras_init(&vipc_server, &cameras, device_id, context); vipc_server.start_listener(); diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index e87eaf4b91..7bbb13c75f 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -23,7 +23,7 @@ #define CAMERA_ID_LGC920 6 #define CAMERA_ID_LGC615 7 #define CAMERA_ID_AR0231 8 -#define CAMERA_ID_IMX390 9 +#define CAMERA_ID_OX03C10 9 #define CAMERA_ID_MAX 10 const int YUV_BUFFER_COUNT = 40; diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index a86218c06e..3d0cc3a70f 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -32,7 +32,8 @@ const size_t FRAME_HEIGHT = 1208; const size_t FRAME_STRIDE = 2896; // for 12 bit output. 1928 * 12 / 8 + 4 (alignment) const size_t AR0231_REGISTERS_HEIGHT = 2; -const size_t AR0231_STATS_HEIGHT = 2; +// TODO: this extra height is universal and doesn't apply per camera +const size_t AR0231_STATS_HEIGHT = 2+8; const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py @@ -47,26 +48,60 @@ CameraInfo cameras_supported[CAMERA_ID_MAX] = { .frame_offset = AR0231_REGISTERS_HEIGHT, .stats_offset = AR0231_REGISTERS_HEIGHT + FRAME_HEIGHT, }, - [CAMERA_ID_IMX390] = { + [CAMERA_ID_OX03C10] = { .frame_width = FRAME_WIDTH, .frame_height = FRAME_HEIGHT, - .frame_stride = FRAME_STRIDE, + .frame_stride = FRAME_STRIDE, // (0xa80*12//8) + .extra_height = 16, // this right? }, }; -const float DC_GAIN = 2.5; -const float sensor_analog_gains[] = { +const float DC_GAIN_AR0231 = 2.5; +const float DC_GAIN_OX03C10 = 7.32; + +const float DC_GAIN_ON_GREY_AR0231= 0.2; +const float DC_GAIN_OFF_GREY_AR0231 = 0.3; +const float DC_GAIN_ON_GREY_OX03C10= 0.3; +const float DC_GAIN_OFF_GREY_OX03C10 = 0.375; + +const int DC_GAIN_MIN_WEIGHT = 0; +const int DC_GAIN_MAX_WEIGHT_AR0231 = 1; +const int DC_GAIN_MAX_WEIGHT_OX03C10 = 32; + +const float sensor_analog_gains_AR0231[] = { 1.0/8.0, 2.0/8.0, 2.0/7.0, 3.0/7.0, // 0, 1, 2, 3 3.0/6.0, 4.0/6.0, 4.0/5.0, 5.0/5.0, // 4, 5, 6, 7 5.0/4.0, 6.0/4.0, 6.0/3.0, 7.0/3.0, // 8, 9, 10, 11 7.0/2.0, 8.0/2.0, 8.0/1.0}; // 12, 13, 14, 15 = bypass -const int ANALOG_GAIN_MIN_IDX = 0x1; // 0.25x -const int ANALOG_GAIN_REC_IDX = 0x6; // 0.8x -const int ANALOG_GAIN_MAX_IDX = 0xD; // 4.0x +// similar gain curve to AR +const float sensor_analog_gains_OX03C10[] = { + 1.0, 1.25, 1.3125, 1.5625, + 1.6875, 2.0, 2.25, 2.625, + 3.125, 3.625, 4.5, 5.0, + 7.25, 8.5, 12.0, 15.5}; + +const uint32_t ox03c10_analog_gains_reg[] = { + 0x100, 0x140, 0x150, 0x190, + 0x1B0, 0x200, 0x240, 0x2A0, + 0x320, 0x3A0, 0x480, 0x500, + 0x740, 0x880, 0xC00, 0xF80}; + +const int ANALOG_GAIN_MIN_IDX_AR0231 = 0x1; // 0.25x +const int ANALOG_GAIN_REC_IDX_AR0231 = 0x6; // 0.8x +const int ANALOG_GAIN_MAX_IDX_AR0231 = 0xD; // 4.0x + +const int ANALOG_GAIN_MIN_IDX_OX03C10 = 0x0; +const int ANALOG_GAIN_REC_IDX_OX03C10 = 0x5; // 2x +const int ANALOG_GAIN_MAX_IDX_OX03C10 = 0xF; + +const int EXPOSURE_TIME_MIN_AR0231 = 2; // with HDR, fastest ss +const int EXPOSURE_TIME_MAX_AR0231 = 0x0855; // with HDR, slowest ss, 40ms -const int EXPOSURE_TIME_MIN = 2; // with HDR, fastest ss -const int EXPOSURE_TIME_MAX = 0x0855; // with HDR, slowest ss, 40ms +const int EXPOSURE_TIME_MIN_OX03C10 = 2; // 1x +const int EXPOSURE_TIME_MAX_OX03C10 = 2016; +const uint32_t VS_TIME_MIN_OX03C10 = 1; +const uint32_t VS_TIME_MAX_OX03C10 = 34; // vs < 35 // ************** low level camera helpers **************** int do_cam_control(int fd, int op_code, void *handle, int size) { @@ -213,8 +248,8 @@ void CameraState::sensors_start() { LOGD("starting sensor %d", camera_num); if (camera_id == CAMERA_ID_AR0231) { sensors_i2c(start_reg_array_ar0231, std::size(start_reg_array_ar0231), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, true); - } else if (camera_id == CAMERA_ID_IMX390) { - sensors_i2c(start_reg_array_imx390, std::size(start_reg_array_imx390), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false); + } else if (camera_id == CAMERA_ID_OX03C10) { + sensors_i2c(start_reg_array_ox03c10, std::size(start_reg_array_ox03c10), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false); } else { assert(false); } @@ -300,15 +335,15 @@ int CameraState::sensors_init() { switch (camera_num) { case 0: // port 0 - i2c_info->slave_addr = (camera_id == CAMERA_ID_AR0231) ? 0x20 : 0x34; + i2c_info->slave_addr = (camera_id == CAMERA_ID_AR0231) ? 0x20 : 0x6C; // 6C = 0x36*2 break; case 1: // port 1 - i2c_info->slave_addr = (camera_id == CAMERA_ID_AR0231) ? 0x30 : 0x36; + i2c_info->slave_addr = (camera_id == CAMERA_ID_AR0231) ? 0x30 : 0x20; break; case 2: // port 2 - i2c_info->slave_addr = (camera_id == CAMERA_ID_AR0231) ? 0x20 : 0x34; + i2c_info->slave_addr = (camera_id == CAMERA_ID_AR0231) ? 0x20 : 0x6C; break; } @@ -324,9 +359,9 @@ int CameraState::sensors_init() { if (camera_id == CAMERA_ID_AR0231) { probe->reg_addr = 0x3000; probe->expected_data = 0x354; - } else if (camera_id == CAMERA_ID_IMX390) { - probe->reg_addr = 0x330; - probe->expected_data = 0x1538; + } else if (camera_id == CAMERA_ID_OX03C10) { + probe->reg_addr = 0x300a; + probe->expected_data = 0x5803; } else { assert(false); } @@ -393,8 +428,8 @@ int CameraState::sensors_init() { power->power_settings[1].power_seq_type = 1; power->power_settings[2].power_seq_type = 3; - LOGD("probing the sensor"); int ret = do_cam_control(sensor_fd, CAM_SENSOR_PROBE_CMD, (void *)(uintptr_t)cam_packet_handle, 0); + LOGD("probing the sensor: %d", ret); mm.free(i2c_info); mm.free(power_settings); @@ -606,12 +641,67 @@ void CameraState::enqueue_req_multi(int start, int n, bool dp) { // ******************* camera ******************* -void CameraState::camera_init(MultiCameraState *multi_cam_state_, VisionIpcServer * v, int camera_id_, int camera_num_, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type, bool enabled_) { - multi_cam_state = multi_cam_state_; - camera_id = camera_id_; - camera_num = camera_num_; - enabled = enabled_; +void CameraState::camera_set_parameters() { + if (camera_id == CAMERA_ID_AR0231) { + dc_gain_factor = DC_GAIN_AR0231; + dc_gain_max_weight = DC_GAIN_MAX_WEIGHT_AR0231; + dc_gain_on_grey = DC_GAIN_ON_GREY_AR0231; + dc_gain_off_grey = DC_GAIN_OFF_GREY_AR0231; + exposure_time_min = EXPOSURE_TIME_MIN_AR0231; + exposure_time_max = EXPOSURE_TIME_MAX_AR0231; + analog_gain_min_idx = ANALOG_GAIN_MIN_IDX_AR0231; + analog_gain_rec_idx = ANALOG_GAIN_REC_IDX_AR0231; + analog_gain_max_idx = ANALOG_GAIN_MAX_IDX_AR0231; + for (int i=0; i<=analog_gain_max_idx; i++) { + sensor_analog_gains[i] = sensor_analog_gains_AR0231[i]; + } + min_ev = exposure_time_min * sensor_analog_gains[analog_gain_min_idx]; + } else if (camera_id == CAMERA_ID_OX03C10) { + dc_gain_factor = DC_GAIN_OX03C10; + dc_gain_max_weight = DC_GAIN_MAX_WEIGHT_OX03C10; + dc_gain_on_grey = DC_GAIN_ON_GREY_OX03C10; + dc_gain_off_grey = DC_GAIN_OFF_GREY_OX03C10; + exposure_time_min = EXPOSURE_TIME_MIN_OX03C10; + exposure_time_max = EXPOSURE_TIME_MAX_OX03C10; + analog_gain_min_idx = ANALOG_GAIN_MIN_IDX_OX03C10; + analog_gain_rec_idx = ANALOG_GAIN_REC_IDX_OX03C10; + analog_gain_max_idx = ANALOG_GAIN_MAX_IDX_OX03C10; + for (int i=0; i<=analog_gain_max_idx; i++) { + sensor_analog_gains[i] = sensor_analog_gains_OX03C10[i]; + } + min_ev = (exposure_time_min + VS_TIME_MIN_OX03C10) * sensor_analog_gains[analog_gain_min_idx]; + } else { + assert(false); + } + + max_ev = exposure_time_max * dc_gain_factor * sensor_analog_gains[analog_gain_max_idx]; + target_grey_fraction = 0.3; + + dc_gain_enabled = false; + dc_gain_weight = DC_GAIN_MIN_WEIGHT; + gain_idx = analog_gain_rec_idx; + exposure_time = 5; + cur_ev[0] = cur_ev[1] = cur_ev[2] = (1 + dc_gain_weight * (dc_gain_factor-1) / dc_gain_max_weight) * sensor_analog_gains[gain_idx] * exposure_time; +} + +void CameraState::camera_map_bufs(MultiCameraState *s) { + for (int i = 0; i < FRAME_BUF_COUNT; i++) { + // configure ISP to put the image in place + struct cam_mem_mgr_map_cmd mem_mgr_map_cmd = {0}; + mem_mgr_map_cmd.mmu_hdls[0] = s->device_iommu; + mem_mgr_map_cmd.num_hdl = 1; + mem_mgr_map_cmd.flags = CAM_MEM_FLAG_HW_READ_WRITE; + mem_mgr_map_cmd.fd = buf.camera_bufs[i].fd; + int ret = do_cam_control(s->video0_fd, CAM_REQ_MGR_MAP_BUF, &mem_mgr_map_cmd, sizeof(mem_mgr_map_cmd)); + LOGD("map buf req: (fd: %d) 0x%x %d", buf.camera_bufs[i].fd, mem_mgr_map_cmd.out.buf_handle, ret); + buf_handle[i] = mem_mgr_map_cmd.out.buf_handle; + } + enqueue_req_multi(1, FRAME_BUF_COUNT, 0); +} + +void CameraState::camera_init(MultiCameraState *s, VisionIpcServer * v, int camera_id_, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type) { if (!enabled) return; + camera_id = camera_id_; LOGD("camera init %d", camera_num); assert(camera_id < std::size(cameras_supported)); @@ -621,19 +711,18 @@ void CameraState::camera_init(MultiCameraState *multi_cam_state_, VisionIpcServe request_id_last = 0; skipped = true; - min_ev = EXPOSURE_TIME_MIN * sensor_analog_gains[ANALOG_GAIN_MIN_IDX]; - max_ev = EXPOSURE_TIME_MAX * sensor_analog_gains[ANALOG_GAIN_MAX_IDX] * DC_GAIN; - target_grey_fraction = 0.3; - - dc_gain_enabled = false; - gain_idx = ANALOG_GAIN_REC_IDX; - exposure_time = 5; - cur_ev[0] = cur_ev[1] = cur_ev[2] = (dc_gain_enabled ? DC_GAIN : 1) * sensor_analog_gains[gain_idx] * exposure_time; + camera_set_parameters(); buf.init(device_id, ctx, this, v, FRAME_BUF_COUNT, yuv_type); + camera_map_bufs(s); } -void CameraState::camera_open() { +void CameraState::camera_open(MultiCameraState *multi_cam_state_, int camera_num_, bool enabled_) { + multi_cam_state = multi_cam_state_; + camera_num = camera_num_; + enabled = enabled_; + if (!enabled) return; + int ret; sensor_fd = open_v4l_by_name_and_index("cam-sensor-driver", camera_num); assert(sensor_fd >= 0); @@ -644,10 +733,12 @@ void CameraState::camera_open() { // probe the sensor LOGD("-- Probing sensor %d", camera_num); + camera_id = CAMERA_ID_AR0231; ret = sensors_init(); if (ret != 0) { - LOGD("AR0231 init failed, trying IMX390"); - camera_id = CAMERA_ID_IMX390; + // TODO: use build flag instead? + LOGD("AR0231 init failed, trying OX03C10"); + camera_id = CAMERA_ID_OX03C10; ret = sensors_init(); } LOGD("-- Probing sensor %d done with %d", camera_num, ret); @@ -671,13 +762,18 @@ void CameraState::camera_open() { LOGD("acquire sensor dev"); LOG("-- Configuring sensor"); + uint32_t dt; if (camera_id == CAMERA_ID_AR0231) { sensors_i2c(init_array_ar0231, std::size(init_array_ar0231), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, true); - } else if (camera_id == CAMERA_ID_IMX390) { - sensors_i2c(init_array_imx390, std::size(init_array_imx390), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false); + dt = 0x12; // Changing stats to 0x2C doesn't work, so change pixels to 0x12 instead + } else if (camera_id == CAMERA_ID_OX03C10) { + sensors_i2c(init_array_ox03c10, std::size(init_array_ox03c10), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false); + // one is 0x2a, two are 0x2b + dt = 0x2c; } else { assert(false); } + printf("dt is %x\n", dt); // NOTE: to be able to disable road and wide road, we still have to configure the sensor over i2c // If you don't do this, the strobe GPIO is an output (even in reset it seems!) @@ -691,7 +787,7 @@ void CameraState::camera_open() { .lane_cfg = 0x3210, .vc = 0x0, - .dt = 0x12, // Changing stats to 0x2C doesn't work, so change pixels to 0x12 instead + .dt = dt, .format = CAM_FORMAT_MIPI_RAW_12, .test_pattern = 0x2, // 0x3? @@ -805,29 +901,15 @@ void CameraState::camera_open() { ret = device_control(multi_cam_state->isp_fd, CAM_START_DEV, session_handle, isp_dev_handle); LOGD("start isp: %d", ret); - for (int i = 0; i < FRAME_BUF_COUNT; i++) { - // configure ISP to put the image in place - struct cam_mem_mgr_map_cmd mem_mgr_map_cmd = {0}; - mem_mgr_map_cmd.mmu_hdls[0] = multi_cam_state->device_iommu; - mem_mgr_map_cmd.num_hdl = 1; - mem_mgr_map_cmd.flags = CAM_MEM_FLAG_HW_READ_WRITE; - mem_mgr_map_cmd.fd = buf.camera_bufs[i].fd; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_MAP_BUF, &mem_mgr_map_cmd, sizeof(mem_mgr_map_cmd)); - LOGD("map buf req: (fd: %d) 0x%x %d", buf.camera_bufs[i].fd, mem_mgr_map_cmd.out.buf_handle, ret); - buf_handle[i] = mem_mgr_map_cmd.out.buf_handle; - } - // TODO: this is unneeded, should we be doing the start i2c in a different way? //ret = device_control(sensor_fd, CAM_START_DEV, session_handle, sensor_dev_handle); //LOGD("start sensor: %d", ret); - - enqueue_req_multi(1, FRAME_BUF_COUNT, 0); } void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) { - s->driver_cam.camera_init(s, v, CAMERA_ID_AR0231, 2, 20, device_id, ctx, VISION_STREAM_DRIVER, !env_disable_driver); - s->road_cam.camera_init(s, v, CAMERA_ID_AR0231, 1, 20, device_id, ctx, VISION_STREAM_ROAD, !env_disable_road); - s->wide_road_cam.camera_init(s, v, CAMERA_ID_AR0231, 0, 20, device_id, ctx, VISION_STREAM_WIDE_ROAD, !env_disable_wide_road); + s->driver_cam.camera_init(s, v, s->driver_cam.camera_id, 20, device_id, ctx, VISION_STREAM_DRIVER); + s->road_cam.camera_init(s, v, s->road_cam.camera_id, 20, device_id, ctx, VISION_STREAM_ROAD); + s->wide_road_cam.camera_init(s, v, s->wide_road_cam.camera_id, 20, device_id, ctx, VISION_STREAM_WIDE_ROAD); s->pm = new PubMaster({"roadCameraState", "driverCameraState", "wideRoadCameraState", "thumbnail"}); } @@ -873,11 +955,11 @@ void cameras_open(MultiCameraState *s) { ret = HANDLE_EINTR(ioctl(s->video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub)); LOGD("req mgr subscribe: %d", ret); - s->driver_cam.camera_open(); + s->driver_cam.camera_open(s, 2, !env_disable_driver); LOGD("driver camera opened"); - s->road_cam.camera_open(); + s->road_cam.camera_open(s, 1, !env_disable_road); LOGD("road camera opened"); - s->wide_road_cam.camera_open(); + s->wide_road_cam.camera_open(s, 0, !env_disable_wide_road); LOGD("wide road camera opened"); } @@ -1044,7 +1126,7 @@ void CameraState::handle_camera_event(void *evdat) { meta_data.frame_id = main_id - idx_offset; meta_data.timestamp_sof = timestamp; exp_lock.lock(); - meta_data.gain = dc_gain_enabled ? analog_gain_frac * DC_GAIN : analog_gain_frac; + meta_data.gain = analog_gain_frac * (1 + dc_gain_weight * (dc_gain_factor-1) / dc_gain_max_weight); meta_data.high_conversion_gain = dc_gain_enabled; meta_data.integ_lines = exposure_time; meta_data.measured_grey_fraction = measured_grey_fraction; @@ -1096,12 +1178,17 @@ void CameraState::set_camera_exposure(float grey_frac) { // Hysteresis around high conversion gain // We usually want this on since it results in lower noise, but turn off in very bright day scenes bool enable_dc_gain = dc_gain_enabled; - if (!enable_dc_gain && target_grey < 0.2) { + if (!enable_dc_gain && target_grey < dc_gain_on_grey) { enable_dc_gain = true; - } else if (enable_dc_gain && target_grey > 0.3) { + dc_gain_weight = DC_GAIN_MIN_WEIGHT; + } else if (enable_dc_gain && target_grey > dc_gain_off_grey) { enable_dc_gain = false; + dc_gain_weight = dc_gain_max_weight; } + if (enable_dc_gain && dc_gain_weight < dc_gain_max_weight) {dc_gain_weight += 1;} + if (!enable_dc_gain && dc_gain_weight > DC_GAIN_MIN_WEIGHT) {dc_gain_weight -= 1;} + std::string gain_bytes, time_bytes; if (env_ctrl_exp_from_params) { gain_bytes = Params().get("CameraDebugExpGain"); @@ -1119,14 +1206,14 @@ void CameraState::set_camera_exposure(float grey_frac) { } else { // Simple brute force optimizer to choose sensor parameters // to reach desired EV - for (int g = std::max((int)ANALOG_GAIN_MIN_IDX, gain_idx - 1); g <= std::min((int)ANALOG_GAIN_MAX_IDX, gain_idx + 1); g++) { - float gain = sensor_analog_gains[g] * (enable_dc_gain ? DC_GAIN : 1); + for (int g = std::max((int)analog_gain_min_idx, gain_idx - 1); g <= std::min((int)analog_gain_max_idx, gain_idx + 1); g++) { + float gain = sensor_analog_gains[g] * (1 + dc_gain_weight * (dc_gain_factor-1) / dc_gain_max_weight); // Compute optimal time for given gain - int t = std::clamp(int(std::round(desired_ev / gain)), EXPOSURE_TIME_MIN, EXPOSURE_TIME_MAX); + int t = std::clamp(int(std::round(desired_ev / gain)), exposure_time_min, exposure_time_max); // Only go below recommended gain when absolutely necessary to not overexpose - if (g < ANALOG_GAIN_REC_IDX && t > 20 && g < gain_idx) { + if (g < analog_gain_rec_idx && t > 20 && g < gain_idx) { continue; } @@ -1134,8 +1221,8 @@ void CameraState::set_camera_exposure(float grey_frac) { float score = std::abs(desired_ev - (t * gain)) * 10; // Going below recommended gain needs lower penalty to not overexpose - float m = g > ANALOG_GAIN_REC_IDX ? 5.0 : 0.1; - score += std::abs(g - (int)ANALOG_GAIN_REC_IDX) * m; + float m = g > analog_gain_rec_idx ? 5.0 : 0.1; + score += std::abs(g - (int)analog_gain_rec_idx) * m; // LOGE("cam: %d - gain: %d, t: %d (%.2f), score %.2f, score + gain %.2f, %.3f, %.3f", camera_num, g, t, desired_ev / gain, score, score + std::abs(g - gain_idx) * (score + 1.0) / 10.0, desired_ev, min_ev); @@ -1160,7 +1247,7 @@ void CameraState::set_camera_exposure(float grey_frac) { exposure_time = new_t; dc_gain_enabled = enable_dc_gain; - float gain = analog_gain_frac * (dc_gain_enabled ? DC_GAIN : 1.0); + float gain = analog_gain_frac * (1 + dc_gain_weight * (dc_gain_factor-1) / dc_gain_max_weight); cur_ev[buf.cur_frame_data.frame_id % 3] = exposure_time * gain; exp_lock.unlock(); @@ -1181,17 +1268,25 @@ void CameraState::set_camera_exposure(float grey_frac) { {0x3012, (uint16_t)exposure_time}, }; sensors_i2c(exp_reg_array, sizeof(exp_reg_array)/sizeof(struct i2c_random_wr_payload), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, true); - } else if (camera_id == CAMERA_ID_IMX390) { - // if gain is sub 1, we have to use exposure to mimic sub 1 gains - uint32_t real_exposure_time = (gain < 1.0) ? (exposure_time*gain) : exposure_time; - // invert real_exposure_time, max exposure is 2 - real_exposure_time = (exposure_time >= 0x7cf) ? 2 : (0x7cf - exposure_time); - uint32_t real_gain = int((10*log10(fmax(1.0, gain)))/0.3); - //printf("%d expose: %d gain: %f = %d\n", camera_num, exposure_time, gain, real_gain); + } else if (camera_id == CAMERA_ID_OX03C10) { + // t_HCG + t_LCG + t_VS on LPD, t_SPD on SPD + uint32_t hcg_time = std::max((dc_gain_weight * exposure_time / dc_gain_max_weight), 0); + uint32_t lcg_time = std::max(((dc_gain_max_weight - dc_gain_weight) * exposure_time / dc_gain_max_weight), 0); + uint32_t spd_time = std::max(hcg_time / 16, (uint32_t)exposure_time_min); + uint32_t vs_time = std::min(std::max(hcg_time / 64, VS_TIME_MIN_OX03C10), VS_TIME_MAX_OX03C10); + + uint32_t real_gain = ox03c10_analog_gains_reg[new_g]; struct i2c_random_wr_payload exp_reg_array[] = { - {0x000c, real_exposure_time&0xFF}, {0x000d, real_exposure_time>>8}, - {0x0010, real_exposure_time&0xFF}, {0x0011, real_exposure_time>>8}, - {0x0018, real_gain&0xFF}, {0x0019, real_gain>>8}, + + {0x3501, hcg_time>>8}, {0x3502, hcg_time&0xFF}, + {0x3581, lcg_time>>8}, {0x3582, lcg_time&0xFF}, + {0x3541, spd_time>>8}, {0x3542, spd_time&0xFF}, + {0x35c1, vs_time>>8}, {0x35c2, vs_time&0xFF}, + + {0x3508, real_gain>>8}, {0x3509, real_gain&0xFF}, + {0x3588, real_gain>>8}, {0x3589, real_gain&0xFF}, + {0x3548, real_gain>>8}, {0x3549, real_gain&0xFF}, + {0x35c8, real_gain>>8}, {0x35c9, real_gain&0xFF}, }; sensors_i2c(exp_reg_array, sizeof(exp_reg_array)/sizeof(struct i2c_random_wr_payload), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false); } diff --git a/system/camerad/cameras/camera_qcom2.h b/system/camerad/cameras/camera_qcom2.h index e75e7e586a..470576a1ec 100644 --- a/system/camerad/cameras/camera_qcom2.h +++ b/system/camerad/cameras/camera_qcom2.h @@ -36,14 +36,28 @@ public: int exposure_time; bool dc_gain_enabled; + int dc_gain_weight; + int gain_idx; float analog_gain_frac; + int exposure_time_min; + int exposure_time_max; + + float dc_gain_factor; + int dc_gain_max_weight; + float dc_gain_on_grey; + float dc_gain_off_grey; + + float sensor_analog_gains[16]; + int analog_gain_min_idx; + int analog_gain_max_idx; + int analog_gain_rec_idx; + float cur_ev[3]; float min_ev, max_ev; float measured_grey_fraction; float target_grey_fraction; - int gain_idx; unique_fd sensor_fd; unique_fd csiphy_fd; @@ -55,8 +69,10 @@ public: void sensors_start(); - void camera_open(); - void camera_init(MultiCameraState *multi_cam_state, VisionIpcServer * v, int camera_id, int camera_num, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type, bool enabled); + void camera_open(MultiCameraState *multi_cam_state, int camera_num, bool enabled); + void camera_set_parameters(); + void camera_map_bufs(MultiCameraState *s); + void camera_init(MultiCameraState *s, VisionIpcServer *v, int camera_id, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type); void camera_close(); std::map ar0231_parse_registers(uint8_t *data, std::initializer_list addrs); diff --git a/system/camerad/cameras/real_debayer.cl b/system/camerad/cameras/real_debayer.cl index fc9f410494..4a36a03bf5 100644 --- a/system/camerad/cameras/real_debayer.cl +++ b/system/camerad/cameras/real_debayer.cl @@ -8,9 +8,15 @@ float3 color_correct(float3 rgb) { // color correction + #if IS_OX + float3 x = rgb.x * (float3)(1.81485125, -0.51650643, -0.06985117); + x += rgb.y * (float3)(-0.51681964, 1.85935946, -0.49871889); + x += rgb.z * (float3)(-0.29803161, -0.34285304, 1.56857006); + #else float3 x = rgb.x * (float3)(1.82717181, -0.31231438, 0.07307673); x += rgb.y * (float3)(-0.5743977, 1.36858544, -0.53183455); x += rgb.z * (float3)(-0.25277411, -0.05627105, 1.45875782); + #endif // tone mapping params const float gamma_k = 0.75; @@ -36,14 +42,43 @@ float get_vignetting_s(float r) { } } +constant float ox03c10_lut[] = { + 0.0000e+00, 5.9488e-08, 1.1898e-07, 1.7846e-07, 2.3795e-07, 2.9744e-07, 3.5693e-07, 4.1642e-07, 4.7591e-07, 5.3539e-07, 5.9488e-07, 6.5437e-07, 7.1386e-07, 7.7335e-07, 8.3284e-07, 8.9232e-07, 9.5181e-07, 1.0113e-06, 1.0708e-06, 1.1303e-06, 1.1898e-06, 1.2493e-06, 1.3087e-06, 1.3682e-06, 1.4277e-06, 1.4872e-06, 1.5467e-06, 1.6062e-06, 1.6657e-06, 1.7252e-06, 1.7846e-06, 1.8441e-06, 1.9036e-06, 1.9631e-06, 2.0226e-06, 2.0821e-06, 2.1416e-06, 2.2011e-06, 2.2606e-06, 2.3200e-06, 2.3795e-06, 2.4390e-06, 2.4985e-06, 2.5580e-06, 2.6175e-06, 2.6770e-06, 2.7365e-06, 2.7959e-06, 2.8554e-06, 2.9149e-06, 2.9744e-06, 3.0339e-06, 3.0934e-06, 3.1529e-06, 3.2124e-06, 3.2719e-06, 3.3313e-06, 3.3908e-06, 3.4503e-06, 3.5098e-06, 3.5693e-06, 3.6288e-06, 3.6883e-06, 3.7478e-06, 3.8072e-06, 3.8667e-06, 3.9262e-06, 3.9857e-06, 4.0452e-06, 4.1047e-06, 4.1642e-06, 4.2237e-06, 4.2832e-06, 4.3426e-06, 4.4021e-06, 4.4616e-06, 4.5211e-06, 4.5806e-06, 4.6401e-06, 4.6996e-06, 4.7591e-06, 4.8185e-06, 4.8780e-06, 4.9375e-06, 4.9970e-06, 5.0565e-06, 5.1160e-06, 5.1755e-06, 5.2350e-06, 5.2945e-06, 5.3539e-06, 5.4134e-06, 5.4729e-06, 5.5324e-06, 5.5919e-06, 5.6514e-06, 5.7109e-06, 5.7704e-06, 5.8298e-06, 5.8893e-06, 5.9488e-06, 6.0083e-06, 6.0678e-06, 6.1273e-06, 6.1868e-06, 6.2463e-06, 6.3058e-06, 6.3652e-06, 6.4247e-06, 6.4842e-06, 6.5437e-06, 6.6032e-06, 6.6627e-06, 6.7222e-06, 6.7817e-06, 6.8411e-06, 6.9006e-06, 6.9601e-06, 7.0196e-06, 7.0791e-06, 7.1386e-06, 7.1981e-06, 7.2576e-06, 7.3171e-06, 7.3765e-06, 7.4360e-06, 7.4955e-06, 7.5550e-06, 7.6145e-06, 7.6740e-06, 7.7335e-06, 7.7930e-06, 7.8524e-06, 7.9119e-06, 7.9714e-06, 8.0309e-06, 8.0904e-06, 8.1499e-06, 8.2094e-06, 8.2689e-06, 8.3284e-06, 8.3878e-06, 8.4473e-06, 8.5068e-06, 8.5663e-06, 8.6258e-06, 8.6853e-06, 8.7448e-06, 8.8043e-06, 8.8637e-06, 8.9232e-06, 8.9827e-06, 9.0422e-06, 9.1017e-06, 9.1612e-06, 9.2207e-06, 9.2802e-06, 9.3397e-06, 9.3991e-06, 9.4586e-06, 9.5181e-06, 9.5776e-06, 9.6371e-06, 9.6966e-06, 9.7561e-06, 9.8156e-06, 9.8750e-06, 9.9345e-06, 9.9940e-06, 1.0054e-05, 1.0113e-05, 1.0172e-05, 1.0232e-05, 1.0291e-05, 1.0351e-05, 1.0410e-05, 1.0470e-05, 1.0529e-05, 1.0589e-05, 1.0648e-05, 1.0708e-05, 1.0767e-05, 1.0827e-05, 1.0886e-05, 1.0946e-05, 1.1005e-05, 1.1065e-05, 1.1124e-05, 1.1184e-05, 1.1243e-05, 1.1303e-05, 1.1362e-05, 1.1422e-05, 1.1481e-05, 1.1541e-05, 1.1600e-05, 1.1660e-05, 1.1719e-05, 1.1779e-05, 1.1838e-05, 1.1898e-05, 1.1957e-05, 1.2017e-05, 1.2076e-05, 1.2136e-05, 1.2195e-05, 1.2255e-05, 1.2314e-05, 1.2374e-05, 1.2433e-05, 1.2493e-05, 1.2552e-05, 1.2612e-05, 1.2671e-05, 1.2730e-05, 1.2790e-05, 1.2849e-05, 1.2909e-05, 1.2968e-05, 1.3028e-05, 1.3087e-05, 1.3147e-05, 1.3206e-05, 1.3266e-05, 1.3325e-05, 1.3385e-05, 1.3444e-05, 1.3504e-05, 1.3563e-05, 1.3623e-05, 1.3682e-05, 1.3742e-05, 1.3801e-05, 1.3861e-05, 1.3920e-05, 1.3980e-05, 1.4039e-05, 1.4099e-05, 1.4158e-05, 1.4218e-05, 1.4277e-05, 1.4337e-05, 1.4396e-05, 1.4456e-05, 1.4515e-05, 1.4575e-05, 1.4634e-05, 1.4694e-05, 1.4753e-05, 1.4813e-05, 1.4872e-05, 1.4932e-05, 1.4991e-05, 1.5051e-05, 1.5110e-05, 1.5169e-05, + 1.5229e-05, 1.5288e-05, 1.5348e-05, 1.5407e-05, 1.5467e-05, 1.5526e-05, 1.5586e-05, 1.5645e-05, 1.5705e-05, 1.5764e-05, 1.5824e-05, 1.5883e-05, 1.5943e-05, 1.6002e-05, 1.6062e-05, 1.6121e-05, 1.6181e-05, 1.6240e-05, 1.6300e-05, 1.6359e-05, 1.6419e-05, 1.6478e-05, 1.6538e-05, 1.6597e-05, 1.6657e-05, 1.6716e-05, 1.6776e-05, 1.6835e-05, 1.6895e-05, 1.6954e-05, 1.7014e-05, 1.7073e-05, 1.7133e-05, 1.7192e-05, 1.7252e-05, 1.7311e-05, 1.7371e-05, 1.7430e-05, 1.7490e-05, 1.7549e-05, 1.7609e-05, 1.7668e-05, 1.7727e-05, 1.7787e-05, 1.7846e-05, 1.7906e-05, 1.7965e-05, 1.8025e-05, 1.8084e-05, 1.8144e-05, 1.8203e-05, 1.8263e-05, 1.8322e-05, 1.8382e-05, 1.8441e-05, 1.8501e-05, 1.8560e-05, 1.8620e-05, 1.8679e-05, 1.8739e-05, 1.8798e-05, 1.8858e-05, 1.8917e-05, 1.8977e-05, 1.9036e-05, 1.9096e-05, 1.9155e-05, 1.9215e-05, 1.9274e-05, 1.9334e-05, 1.9393e-05, 1.9453e-05, 1.9512e-05, 1.9572e-05, 1.9631e-05, 1.9691e-05, 1.9750e-05, 1.9810e-05, 1.9869e-05, 1.9929e-05, 1.9988e-05, 2.0048e-05, 2.0107e-05, 2.0167e-05, 2.0226e-05, 2.0285e-05, 2.0345e-05, 2.0404e-05, 2.0464e-05, 2.0523e-05, 2.0583e-05, 2.0642e-05, 2.0702e-05, 2.0761e-05, 2.0821e-05, 2.0880e-05, 2.0940e-05, 2.0999e-05, 2.1059e-05, 2.1118e-05, 2.1178e-05, 2.1237e-05, 2.1297e-05, 2.1356e-05, 2.1416e-05, 2.1475e-05, 2.1535e-05, 2.1594e-05, 2.1654e-05, 2.1713e-05, 2.1773e-05, 2.1832e-05, 2.1892e-05, 2.1951e-05, 2.2011e-05, 2.2070e-05, 2.2130e-05, 2.2189e-05, 2.2249e-05, 2.2308e-05, 2.2368e-05, 2.2427e-05, 2.2487e-05, 2.2546e-05, 2.2606e-05, 2.2665e-05, 2.2725e-05, 2.2784e-05, 2.2843e-05, 2.2903e-05, 2.2962e-05, 2.3022e-05, 2.3081e-05, 2.3141e-05, 2.3200e-05, 2.3260e-05, 2.3319e-05, 2.3379e-05, 2.3438e-05, 2.3498e-05, 2.3557e-05, 2.3617e-05, 2.3676e-05, 2.3736e-05, 2.3795e-05, 2.3855e-05, 2.3914e-05, 2.3974e-05, 2.4033e-05, 2.4093e-05, 2.4152e-05, 2.4212e-05, 2.4271e-05, 2.4331e-05, 2.4390e-05, 2.4450e-05, 2.4509e-05, 2.4569e-05, 2.4628e-05, 2.4688e-05, 2.4747e-05, 2.4807e-05, 2.4866e-05, 2.4926e-05, 2.4985e-05, 2.5045e-05, 2.5104e-05, 2.5164e-05, 2.5223e-05, 2.5282e-05, 2.5342e-05, 2.5401e-05, 2.5461e-05, 2.5520e-05, 2.5580e-05, 2.5639e-05, 2.5699e-05, 2.5758e-05, 2.5818e-05, 2.5877e-05, 2.5937e-05, 2.5996e-05, 2.6056e-05, 2.6115e-05, 2.6175e-05, 2.6234e-05, 2.6294e-05, 2.6353e-05, 2.6413e-05, 2.6472e-05, 2.6532e-05, 2.6591e-05, 2.6651e-05, 2.6710e-05, 2.6770e-05, 2.6829e-05, 2.6889e-05, 2.6948e-05, 2.7008e-05, 2.7067e-05, 2.7127e-05, 2.7186e-05, 2.7246e-05, 2.7305e-05, 2.7365e-05, 2.7424e-05, 2.7484e-05, 2.7543e-05, 2.7603e-05, 2.7662e-05, 2.7722e-05, 2.7781e-05, 2.7840e-05, 2.7900e-05, 2.7959e-05, 2.8019e-05, 2.8078e-05, 2.8138e-05, 2.8197e-05, 2.8257e-05, 2.8316e-05, 2.8376e-05, 2.8435e-05, 2.8495e-05, 2.8554e-05, 2.8614e-05, 2.8673e-05, 2.8733e-05, 2.8792e-05, 2.8852e-05, 2.8911e-05, 2.8971e-05, 2.9030e-05, 2.9090e-05, 2.9149e-05, 2.9209e-05, 2.9268e-05, 2.9328e-05, 2.9387e-05, 2.9447e-05, 2.9506e-05, 2.9566e-05, 2.9625e-05, 2.9685e-05, 2.9744e-05, 2.9804e-05, 2.9863e-05, 2.9923e-05, 2.9982e-05, 3.0042e-05, 3.0101e-05, 3.0161e-05, 3.0220e-05, 3.0280e-05, 3.0339e-05, 3.0398e-05, + 3.0458e-05, 3.0577e-05, 3.0697e-05, 3.0816e-05, 3.0936e-05, 3.1055e-05, 3.1175e-05, 3.1294e-05, 3.1414e-05, 3.1533e-05, 3.1652e-05, 3.1772e-05, 3.1891e-05, 3.2011e-05, 3.2130e-05, 3.2250e-05, 3.2369e-05, 3.2489e-05, 3.2608e-05, 3.2727e-05, 3.2847e-05, 3.2966e-05, 3.3086e-05, 3.3205e-05, 3.3325e-05, 3.3444e-05, 3.3563e-05, 3.3683e-05, 3.3802e-05, 3.3922e-05, 3.4041e-05, 3.4161e-05, 3.4280e-05, 3.4400e-05, 3.4519e-05, 3.4638e-05, 3.4758e-05, 3.4877e-05, 3.4997e-05, 3.5116e-05, 3.5236e-05, 3.5355e-05, 3.5475e-05, 3.5594e-05, 3.5713e-05, 3.5833e-05, 3.5952e-05, 3.6072e-05, 3.6191e-05, 3.6311e-05, 3.6430e-05, 3.6550e-05, 3.6669e-05, 3.6788e-05, 3.6908e-05, 3.7027e-05, 3.7147e-05, 3.7266e-05, 3.7386e-05, 3.7505e-05, 3.7625e-05, 3.7744e-05, 3.7863e-05, 3.7983e-05, 3.8102e-05, 3.8222e-05, 3.8341e-05, 3.8461e-05, 3.8580e-05, 3.8700e-05, 3.8819e-05, 3.8938e-05, 3.9058e-05, 3.9177e-05, 3.9297e-05, 3.9416e-05, 3.9536e-05, 3.9655e-05, 3.9775e-05, 3.9894e-05, 4.0013e-05, 4.0133e-05, 4.0252e-05, 4.0372e-05, 4.0491e-05, 4.0611e-05, 4.0730e-05, 4.0850e-05, 4.0969e-05, 4.1088e-05, 4.1208e-05, 4.1327e-05, 4.1447e-05, 4.1566e-05, 4.1686e-05, 4.1805e-05, 4.1925e-05, 4.2044e-05, 4.2163e-05, 4.2283e-05, 4.2402e-05, 4.2522e-05, 4.2641e-05, 4.2761e-05, 4.2880e-05, 4.2999e-05, 4.3119e-05, 4.3238e-05, 4.3358e-05, 4.3477e-05, 4.3597e-05, 4.3716e-05, 4.3836e-05, 4.3955e-05, 4.4074e-05, 4.4194e-05, 4.4313e-05, 4.4433e-05, 4.4552e-05, 4.4672e-05, 4.4791e-05, 4.4911e-05, 4.5030e-05, 4.5149e-05, 4.5269e-05, 4.5388e-05, 4.5508e-05, 4.5627e-05, 4.5747e-05, 4.5866e-05, 4.5986e-05, 4.6105e-05, 4.6224e-05, 4.6344e-05, 4.6463e-05, 4.6583e-05, 4.6702e-05, 4.6822e-05, 4.6941e-05, 4.7061e-05, 4.7180e-05, 4.7299e-05, 4.7419e-05, 4.7538e-05, 4.7658e-05, 4.7777e-05, 4.7897e-05, 4.8016e-05, 4.8136e-05, 4.8255e-05, 4.8374e-05, 4.8494e-05, 4.8613e-05, 4.8733e-05, 4.8852e-05, 4.8972e-05, 4.9091e-05, 4.9211e-05, 4.9330e-05, 4.9449e-05, 4.9569e-05, 4.9688e-05, 4.9808e-05, 4.9927e-05, 5.0047e-05, 5.0166e-05, 5.0286e-05, 5.0405e-05, 5.0524e-05, 5.0644e-05, 5.0763e-05, 5.0883e-05, 5.1002e-05, 5.1122e-05, 5.1241e-05, 5.1361e-05, 5.1480e-05, 5.1599e-05, 5.1719e-05, 5.1838e-05, 5.1958e-05, 5.2077e-05, 5.2197e-05, 5.2316e-05, 5.2435e-05, 5.2555e-05, 5.2674e-05, 5.2794e-05, 5.2913e-05, 5.3033e-05, 5.3152e-05, 5.3272e-05, 5.3391e-05, 5.3510e-05, 5.3630e-05, 5.3749e-05, 5.3869e-05, 5.3988e-05, 5.4108e-05, 5.4227e-05, 5.4347e-05, 5.4466e-05, 5.4585e-05, 5.4705e-05, 5.4824e-05, 5.4944e-05, 5.5063e-05, 5.5183e-05, 5.5302e-05, 5.5422e-05, 5.5541e-05, 5.5660e-05, 5.5780e-05, 5.5899e-05, 5.6019e-05, 5.6138e-05, 5.6258e-05, 5.6377e-05, 5.6497e-05, 5.6616e-05, 5.6735e-05, 5.6855e-05, 5.6974e-05, 5.7094e-05, 5.7213e-05, 5.7333e-05, 5.7452e-05, 5.7572e-05, 5.7691e-05, 5.7810e-05, 5.7930e-05, 5.8049e-05, 5.8169e-05, 5.8288e-05, 5.8408e-05, 5.8527e-05, 5.8647e-05, 5.8766e-05, 5.8885e-05, 5.9005e-05, 5.9124e-05, 5.9244e-05, 5.9363e-05, 5.9483e-05, 5.9602e-05, 5.9722e-05, 5.9841e-05, 5.9960e-05, 6.0080e-05, 6.0199e-05, 6.0319e-05, 6.0438e-05, 6.0558e-05, 6.0677e-05, 6.0797e-05, 6.0916e-05, + 6.1154e-05, 6.1392e-05, 6.1631e-05, 6.1869e-05, 6.2107e-05, 6.2345e-05, 6.2583e-05, 6.2821e-05, 6.3060e-05, 6.3298e-05, 6.3536e-05, 6.3774e-05, 6.4012e-05, 6.4251e-05, 6.4489e-05, 6.4727e-05, 6.4965e-05, 6.5203e-05, 6.5441e-05, 6.5680e-05, 6.5918e-05, 6.6156e-05, 6.6394e-05, 6.6632e-05, 6.6871e-05, 6.7109e-05, 6.7347e-05, 6.7585e-05, 6.7823e-05, 6.8062e-05, 6.8300e-05, 6.8538e-05, 6.8776e-05, 6.9014e-05, 6.9252e-05, 6.9491e-05, 6.9729e-05, 6.9967e-05, 7.0205e-05, 7.0443e-05, 7.0682e-05, 7.0920e-05, 7.1158e-05, 7.1396e-05, 7.1634e-05, 7.1872e-05, 7.2111e-05, 7.2349e-05, 7.2587e-05, 7.2825e-05, 7.3063e-05, 7.3302e-05, 7.3540e-05, 7.3778e-05, 7.4016e-05, 7.4254e-05, 7.4493e-05, 7.4731e-05, 7.4969e-05, 7.5207e-05, 7.5445e-05, 7.5683e-05, 7.5922e-05, 7.6160e-05, 7.6398e-05, 7.6636e-05, 7.6874e-05, 7.7113e-05, 7.7351e-05, 7.7589e-05, 7.7827e-05, 7.8065e-05, 7.8304e-05, 7.8542e-05, 7.8780e-05, 7.9018e-05, 7.9256e-05, 7.9494e-05, 7.9733e-05, 7.9971e-05, 8.0209e-05, 8.0447e-05, 8.0685e-05, 8.0924e-05, 8.1162e-05, 8.1400e-05, 8.1638e-05, 8.1876e-05, 8.2114e-05, 8.2353e-05, 8.2591e-05, 8.2829e-05, 8.3067e-05, 8.3305e-05, 8.3544e-05, 8.3782e-05, 8.4020e-05, 8.4258e-05, 8.4496e-05, 8.4735e-05, 8.4973e-05, 8.5211e-05, 8.5449e-05, 8.5687e-05, 8.5925e-05, 8.6164e-05, 8.6402e-05, 8.6640e-05, 8.6878e-05, 8.7116e-05, 8.7355e-05, 8.7593e-05, 8.7831e-05, 8.8069e-05, 8.8307e-05, 8.8545e-05, 8.8784e-05, 8.9022e-05, 8.9260e-05, 8.9498e-05, 8.9736e-05, 8.9975e-05, 9.0213e-05, 9.0451e-05, 9.0689e-05, 9.0927e-05, 9.1166e-05, 9.1404e-05, 9.1642e-05, 9.1880e-05, 9.2118e-05, 9.2356e-05, 9.2595e-05, 9.2833e-05, 9.3071e-05, 9.3309e-05, 9.3547e-05, 9.3786e-05, 9.4024e-05, 9.4262e-05, 9.4500e-05, 9.4738e-05, 9.4977e-05, 9.5215e-05, 9.5453e-05, 9.5691e-05, 9.5929e-05, 9.6167e-05, 9.6406e-05, 9.6644e-05, 9.6882e-05, 9.7120e-05, 9.7358e-05, 9.7597e-05, 9.7835e-05, 9.8073e-05, 9.8311e-05, 9.8549e-05, 9.8787e-05, 9.9026e-05, 9.9264e-05, 9.9502e-05, 9.9740e-05, 9.9978e-05, 1.0022e-04, 1.0045e-04, 1.0069e-04, 1.0093e-04, 1.0117e-04, 1.0141e-04, 1.0165e-04, 1.0188e-04, 1.0212e-04, 1.0236e-04, 1.0260e-04, 1.0284e-04, 1.0307e-04, 1.0331e-04, 1.0355e-04, 1.0379e-04, 1.0403e-04, 1.0427e-04, 1.0450e-04, 1.0474e-04, 1.0498e-04, 1.0522e-04, 1.0546e-04, 1.0569e-04, 1.0593e-04, 1.0617e-04, 1.0641e-04, 1.0665e-04, 1.0689e-04, 1.0712e-04, 1.0736e-04, 1.0760e-04, 1.0784e-04, 1.0808e-04, 1.0831e-04, 1.0855e-04, 1.0879e-04, 1.0903e-04, 1.0927e-04, 1.0951e-04, 1.0974e-04, 1.0998e-04, 1.1022e-04, 1.1046e-04, 1.1070e-04, 1.1093e-04, 1.1117e-04, 1.1141e-04, 1.1165e-04, 1.1189e-04, 1.1213e-04, 1.1236e-04, 1.1260e-04, 1.1284e-04, 1.1308e-04, 1.1332e-04, 1.1355e-04, 1.1379e-04, 1.1403e-04, 1.1427e-04, 1.1451e-04, 1.1475e-04, 1.1498e-04, 1.1522e-04, 1.1546e-04, 1.1570e-04, 1.1594e-04, 1.1618e-04, 1.1641e-04, 1.1665e-04, 1.1689e-04, 1.1713e-04, 1.1737e-04, 1.1760e-04, 1.1784e-04, 1.1808e-04, 1.1832e-04, 1.1856e-04, 1.1880e-04, 1.1903e-04, 1.1927e-04, 1.1951e-04, 1.1975e-04, 1.1999e-04, 1.2022e-04, 1.2046e-04, 1.2070e-04, 1.2094e-04, 1.2118e-04, 1.2142e-04, 1.2165e-04, 1.2189e-04, + 1.2213e-04, 1.2237e-04, 1.2261e-04, 1.2284e-04, 1.2308e-04, 1.2332e-04, 1.2356e-04, 1.2380e-04, 1.2404e-04, 1.2427e-04, 1.2451e-04, 1.2475e-04, 1.2499e-04, 1.2523e-04, 1.2546e-04, 1.2570e-04, 1.2594e-04, 1.2618e-04, 1.2642e-04, 1.2666e-04, 1.2689e-04, 1.2713e-04, 1.2737e-04, 1.2761e-04, 1.2785e-04, 1.2808e-04, 1.2832e-04, 1.2856e-04, 1.2880e-04, 1.2904e-04, 1.2928e-04, 1.2951e-04, 1.2975e-04, 1.2999e-04, 1.3023e-04, 1.3047e-04, 1.3070e-04, 1.3094e-04, 1.3118e-04, 1.3142e-04, 1.3166e-04, 1.3190e-04, 1.3213e-04, 1.3237e-04, 1.3261e-04, 1.3285e-04, 1.3309e-04, 1.3332e-04, 1.3356e-04, 1.3380e-04, 1.3404e-04, 1.3428e-04, 1.3452e-04, 1.3475e-04, 1.3499e-04, 1.3523e-04, 1.3547e-04, 1.3571e-04, 1.3594e-04, 1.3618e-04, 1.3642e-04, 1.3666e-04, 1.3690e-04, 1.3714e-04, 1.3737e-04, 1.3761e-04, 1.3785e-04, 1.3809e-04, 1.3833e-04, 1.3856e-04, 1.3880e-04, 1.3904e-04, 1.3928e-04, 1.3952e-04, 1.3976e-04, 1.3999e-04, 1.4023e-04, 1.4047e-04, 1.4071e-04, 1.4095e-04, 1.4118e-04, 1.4142e-04, 1.4166e-04, 1.4190e-04, 1.4214e-04, 1.4238e-04, 1.4261e-04, 1.4285e-04, 1.4309e-04, 1.4333e-04, 1.4357e-04, 1.4380e-04, 1.4404e-04, 1.4428e-04, 1.4452e-04, 1.4476e-04, 1.4500e-04, 1.4523e-04, 1.4547e-04, 1.4571e-04, 1.4595e-04, 1.4619e-04, 1.4642e-04, 1.4666e-04, 1.4690e-04, 1.4714e-04, 1.4738e-04, 1.4762e-04, 1.4785e-04, 1.4809e-04, 1.4833e-04, 1.4857e-04, 1.4881e-04, 1.4904e-04, 1.4928e-04, 1.4952e-04, 1.4976e-04, 1.5000e-04, 1.5024e-04, 1.5047e-04, 1.5071e-04, 1.5095e-04, 1.5119e-04, 1.5143e-04, 1.5166e-04, 1.5190e-04, 1.5214e-04, 1.5238e-04, 1.5262e-04, 1.5286e-04, 1.5309e-04, 1.5333e-04, 1.5357e-04, 1.5381e-04, 1.5405e-04, 1.5428e-04, 1.5452e-04, 1.5476e-04, 1.5500e-04, 1.5524e-04, 1.5548e-04, 1.5571e-04, 1.5595e-04, 1.5619e-04, 1.5643e-04, 1.5667e-04, 1.5690e-04, 1.5714e-04, 1.5738e-04, 1.5762e-04, 1.5786e-04, 1.5810e-04, 1.5833e-04, 1.5857e-04, 1.5881e-04, 1.5905e-04, 1.5929e-04, 1.5952e-04, 1.5976e-04, 1.6000e-04, 1.6024e-04, 1.6048e-04, 1.6072e-04, 1.6095e-04, 1.6119e-04, 1.6143e-04, 1.6167e-04, 1.6191e-04, 1.6214e-04, 1.6238e-04, 1.6262e-04, 1.6286e-04, 1.6310e-04, 1.6334e-04, 1.6357e-04, 1.6381e-04, 1.6405e-04, 1.6429e-04, 1.6453e-04, 1.6476e-04, 1.6500e-04, 1.6524e-04, 1.6548e-04, 1.6572e-04, 1.6596e-04, 1.6619e-04, 1.6643e-04, 1.6667e-04, 1.6691e-04, 1.6715e-04, 1.6738e-04, 1.6762e-04, 1.6786e-04, 1.6810e-04, 1.6834e-04, 1.6858e-04, 1.6881e-04, 1.6905e-04, 1.6929e-04, 1.6953e-04, 1.6977e-04, 1.7001e-04, 1.7024e-04, 1.7048e-04, 1.7072e-04, 1.7096e-04, 1.7120e-04, 1.7143e-04, 1.7167e-04, 1.7191e-04, 1.7215e-04, 1.7239e-04, 1.7263e-04, 1.7286e-04, 1.7310e-04, 1.7334e-04, 1.7358e-04, 1.7382e-04, 1.7405e-04, 1.7429e-04, 1.7453e-04, 1.7477e-04, 1.7501e-04, 1.7525e-04, 1.7548e-04, 1.7572e-04, 1.7596e-04, 1.7620e-04, 1.7644e-04, 1.7667e-04, 1.7691e-04, 1.7715e-04, 1.7739e-04, 1.7763e-04, 1.7787e-04, 1.7810e-04, 1.7834e-04, 1.7858e-04, 1.7882e-04, 1.7906e-04, 1.7929e-04, 1.7953e-04, 1.7977e-04, 1.8001e-04, 1.8025e-04, 1.8049e-04, 1.8072e-04, 1.8096e-04, 1.8120e-04, 1.8144e-04, 1.8168e-04, 1.8191e-04, 1.8215e-04, 1.8239e-04, 1.8263e-04, 1.8287e-04, + 1.8311e-04, 1.8334e-04, 1.8358e-04, 1.8382e-04, 1.8406e-04, 1.8430e-04, 1.8453e-04, 1.8477e-04, 1.8501e-04, 1.8525e-04, 1.8549e-04, 1.8573e-04, 1.8596e-04, 1.8620e-04, 1.8644e-04, 1.8668e-04, 1.8692e-04, 1.8715e-04, 1.8739e-04, 1.8763e-04, 1.8787e-04, 1.8811e-04, 1.8835e-04, 1.8858e-04, 1.8882e-04, 1.8906e-04, 1.8930e-04, 1.8954e-04, 1.8977e-04, 1.9001e-04, 1.9025e-04, 1.9049e-04, 1.9073e-04, 1.9097e-04, 1.9120e-04, 1.9144e-04, 1.9168e-04, 1.9192e-04, 1.9216e-04, 1.9239e-04, 1.9263e-04, 1.9287e-04, 1.9311e-04, 1.9335e-04, 1.9359e-04, 1.9382e-04, 1.9406e-04, 1.9430e-04, 1.9454e-04, 1.9478e-04, 1.9501e-04, 1.9525e-04, 1.9549e-04, 1.9573e-04, 1.9597e-04, 1.9621e-04, 1.9644e-04, 1.9668e-04, 1.9692e-04, 1.9716e-04, 1.9740e-04, 1.9763e-04, 1.9787e-04, 1.9811e-04, 1.9835e-04, 1.9859e-04, 1.9883e-04, 1.9906e-04, 1.9930e-04, 1.9954e-04, 1.9978e-04, 2.0002e-04, 2.0025e-04, 2.0049e-04, 2.0073e-04, 2.0097e-04, 2.0121e-04, 2.0145e-04, 2.0168e-04, 2.0192e-04, 2.0216e-04, 2.0240e-04, 2.0264e-04, 2.0287e-04, 2.0311e-04, 2.0335e-04, 2.0359e-04, 2.0383e-04, 2.0407e-04, 2.0430e-04, 2.0454e-04, 2.0478e-04, 2.0502e-04, 2.0526e-04, 2.0549e-04, 2.0573e-04, 2.0597e-04, 2.0621e-04, 2.0645e-04, 2.0669e-04, 2.0692e-04, 2.0716e-04, 2.0740e-04, 2.0764e-04, 2.0788e-04, 2.0811e-04, 2.0835e-04, 2.0859e-04, 2.0883e-04, 2.0907e-04, 2.0931e-04, 2.0954e-04, 2.0978e-04, 2.1002e-04, 2.1026e-04, 2.1050e-04, 2.1073e-04, 2.1097e-04, 2.1121e-04, 2.1145e-04, 2.1169e-04, 2.1193e-04, 2.1216e-04, 2.1240e-04, 2.1264e-04, 2.1288e-04, 2.1312e-04, 2.1335e-04, 2.1359e-04, 2.1383e-04, 2.1407e-04, 2.1431e-04, 2.1455e-04, 2.1478e-04, 2.1502e-04, 2.1526e-04, 2.1550e-04, 2.1574e-04, 2.1597e-04, 2.1621e-04, 2.1645e-04, 2.1669e-04, 2.1693e-04, 2.1717e-04, 2.1740e-04, 2.1764e-04, 2.1788e-04, 2.1812e-04, 2.1836e-04, 2.1859e-04, 2.1883e-04, 2.1907e-04, 2.1931e-04, 2.1955e-04, 2.1979e-04, 2.2002e-04, 2.2026e-04, 2.2050e-04, 2.2074e-04, 2.2098e-04, 2.2121e-04, 2.2145e-04, 2.2169e-04, 2.2193e-04, 2.2217e-04, 2.2241e-04, 2.2264e-04, 2.2288e-04, 2.2312e-04, 2.2336e-04, 2.2360e-04, 2.2383e-04, 2.2407e-04, 2.2431e-04, 2.2455e-04, 2.2479e-04, 2.2503e-04, 2.2526e-04, 2.2550e-04, 2.2574e-04, 2.2598e-04, 2.2622e-04, 2.2646e-04, 2.2669e-04, 2.2693e-04, 2.2717e-04, 2.2741e-04, 2.2765e-04, 2.2788e-04, 2.2812e-04, 2.2836e-04, 2.2860e-04, 2.2884e-04, 2.2908e-04, 2.2931e-04, 2.2955e-04, 2.2979e-04, 2.3003e-04, 2.3027e-04, 2.3050e-04, 2.3074e-04, 2.3098e-04, 2.3122e-04, 2.3146e-04, 2.3170e-04, 2.3193e-04, 2.3217e-04, 2.3241e-04, 2.3265e-04, 2.3289e-04, 2.3312e-04, 2.3336e-04, 2.3360e-04, 2.3384e-04, 2.3408e-04, 2.3432e-04, 2.3455e-04, 2.3479e-04, 2.3503e-04, 2.3527e-04, 2.3551e-04, 2.3574e-04, 2.3598e-04, 2.3622e-04, 2.3646e-04, 2.3670e-04, 2.3694e-04, 2.3717e-04, 2.3741e-04, 2.3765e-04, 2.3789e-04, 2.3813e-04, 2.3836e-04, 2.3860e-04, 2.3884e-04, 2.3908e-04, 2.3932e-04, 2.3956e-04, 2.3979e-04, 2.4003e-04, 2.4027e-04, 2.4051e-04, 2.4075e-04, 2.4098e-04, 2.4122e-04, 2.4146e-04, 2.4170e-04, 2.4194e-04, 2.4218e-04, 2.4241e-04, 2.4265e-04, 2.4289e-04, 2.4313e-04, 2.4337e-04, 2.4360e-04, 2.4384e-04, + 2.4480e-04, 2.4575e-04, 2.4670e-04, 2.4766e-04, 2.4861e-04, 2.4956e-04, 2.5052e-04, 2.5147e-04, 2.5242e-04, 2.5337e-04, 2.5433e-04, 2.5528e-04, 2.5623e-04, 2.5719e-04, 2.5814e-04, 2.5909e-04, 2.6005e-04, 2.6100e-04, 2.6195e-04, 2.6291e-04, 2.6386e-04, 2.6481e-04, 2.6577e-04, 2.6672e-04, 2.6767e-04, 2.6863e-04, 2.6958e-04, 2.7053e-04, 2.7149e-04, 2.7244e-04, 2.7339e-04, 2.7435e-04, 2.7530e-04, 2.7625e-04, 2.7720e-04, 2.7816e-04, 2.7911e-04, 2.8006e-04, 2.8102e-04, 2.8197e-04, 2.8292e-04, 2.8388e-04, 2.8483e-04, 2.8578e-04, 2.8674e-04, 2.8769e-04, 2.8864e-04, 2.8960e-04, 2.9055e-04, 2.9150e-04, 2.9246e-04, 2.9341e-04, 2.9436e-04, 2.9532e-04, 2.9627e-04, 2.9722e-04, 2.9818e-04, 2.9913e-04, 3.0008e-04, 3.0104e-04, 3.0199e-04, 3.0294e-04, 3.0389e-04, 3.0485e-04, 3.0580e-04, 3.0675e-04, 3.0771e-04, 3.0866e-04, 3.0961e-04, 3.1057e-04, 3.1152e-04, 3.1247e-04, 3.1343e-04, 3.1438e-04, 3.1533e-04, 3.1629e-04, 3.1724e-04, 3.1819e-04, 3.1915e-04, 3.2010e-04, 3.2105e-04, 3.2201e-04, 3.2296e-04, 3.2391e-04, 3.2487e-04, 3.2582e-04, 3.2677e-04, 3.2772e-04, 3.2868e-04, 3.2963e-04, 3.3058e-04, 3.3154e-04, 3.3249e-04, 3.3344e-04, 3.3440e-04, 3.3535e-04, 3.3630e-04, 3.3726e-04, 3.3821e-04, 3.3916e-04, 3.4012e-04, 3.4107e-04, 3.4202e-04, 3.4298e-04, 3.4393e-04, 3.4488e-04, 3.4584e-04, 3.4679e-04, 3.4774e-04, 3.4870e-04, 3.4965e-04, 3.5060e-04, 3.5156e-04, 3.5251e-04, 3.5346e-04, 3.5441e-04, 3.5537e-04, 3.5632e-04, 3.5727e-04, 3.5823e-04, 3.5918e-04, 3.6013e-04, 3.6109e-04, 3.6204e-04, 3.6299e-04, 3.6395e-04, 3.6490e-04, 3.6585e-04, 3.6681e-04, 3.6776e-04, 3.6871e-04, 3.6967e-04, 3.7062e-04, 3.7157e-04, 3.7253e-04, 3.7348e-04, 3.7443e-04, 3.7539e-04, 3.7634e-04, 3.7729e-04, 3.7825e-04, 3.7920e-04, 3.8015e-04, 3.8110e-04, 3.8206e-04, 3.8301e-04, 3.8396e-04, 3.8492e-04, 3.8587e-04, 3.8682e-04, 3.8778e-04, 3.8873e-04, 3.8968e-04, 3.9064e-04, 3.9159e-04, 3.9254e-04, 3.9350e-04, 3.9445e-04, 3.9540e-04, 3.9636e-04, 3.9731e-04, 3.9826e-04, 3.9922e-04, 4.0017e-04, 4.0112e-04, 4.0208e-04, 4.0303e-04, 4.0398e-04, 4.0493e-04, 4.0589e-04, 4.0684e-04, 4.0779e-04, 4.0875e-04, 4.0970e-04, 4.1065e-04, 4.1161e-04, 4.1256e-04, 4.1351e-04, 4.1447e-04, 4.1542e-04, 4.1637e-04, 4.1733e-04, 4.1828e-04, 4.1923e-04, 4.2019e-04, 4.2114e-04, 4.2209e-04, 4.2305e-04, 4.2400e-04, 4.2495e-04, 4.2591e-04, 4.2686e-04, 4.2781e-04, 4.2877e-04, 4.2972e-04, 4.3067e-04, 4.3162e-04, 4.3258e-04, 4.3353e-04, 4.3448e-04, 4.3544e-04, 4.3639e-04, 4.3734e-04, 4.3830e-04, 4.3925e-04, 4.4020e-04, 4.4116e-04, 4.4211e-04, 4.4306e-04, 4.4402e-04, 4.4497e-04, 4.4592e-04, 4.4688e-04, 4.4783e-04, 4.4878e-04, 4.4974e-04, 4.5069e-04, 4.5164e-04, 4.5260e-04, 4.5355e-04, 4.5450e-04, 4.5545e-04, 4.5641e-04, 4.5736e-04, 4.5831e-04, 4.5927e-04, 4.6022e-04, 4.6117e-04, 4.6213e-04, 4.6308e-04, 4.6403e-04, 4.6499e-04, 4.6594e-04, 4.6689e-04, 4.6785e-04, 4.6880e-04, 4.6975e-04, 4.7071e-04, 4.7166e-04, 4.7261e-04, 4.7357e-04, 4.7452e-04, 4.7547e-04, 4.7643e-04, 4.7738e-04, 4.7833e-04, 4.7929e-04, 4.8024e-04, 4.8119e-04, 4.8214e-04, 4.8310e-04, 4.8405e-04, 4.8500e-04, 4.8596e-04, 4.8691e-04, 4.8786e-04, + 4.8977e-04, 4.9168e-04, 4.9358e-04, 4.9549e-04, 4.9740e-04, 4.9931e-04, 5.0121e-04, 5.0312e-04, 5.0503e-04, 5.0693e-04, 5.0884e-04, 5.1075e-04, 5.1265e-04, 5.1456e-04, 5.1647e-04, 5.1837e-04, 5.2028e-04, 5.2219e-04, 5.2409e-04, 5.2600e-04, 5.2791e-04, 5.2982e-04, 5.3172e-04, 5.3363e-04, 5.3554e-04, 5.3744e-04, 5.3935e-04, 5.4126e-04, 5.4316e-04, 5.4507e-04, 5.4698e-04, 5.4888e-04, 5.5079e-04, 5.5270e-04, 5.5460e-04, 5.5651e-04, 5.5842e-04, 5.6033e-04, 5.6223e-04, 5.6414e-04, 5.6605e-04, 5.6795e-04, 5.6986e-04, 5.7177e-04, 5.7367e-04, 5.7558e-04, 5.7749e-04, 5.7939e-04, 5.8130e-04, 5.8321e-04, 5.8512e-04, 5.8702e-04, 5.8893e-04, 5.9084e-04, 5.9274e-04, 5.9465e-04, 5.9656e-04, 5.9846e-04, 6.0037e-04, 6.0228e-04, 6.0418e-04, 6.0609e-04, 6.0800e-04, 6.0990e-04, 6.1181e-04, 6.1372e-04, 6.1563e-04, 6.1753e-04, 6.1944e-04, 6.2135e-04, 6.2325e-04, 6.2516e-04, 6.2707e-04, 6.2897e-04, 6.3088e-04, 6.3279e-04, 6.3469e-04, 6.3660e-04, 6.3851e-04, 6.4041e-04, 6.4232e-04, 6.4423e-04, 6.4614e-04, 6.4804e-04, 6.4995e-04, 6.5186e-04, 6.5376e-04, 6.5567e-04, 6.5758e-04, 6.5948e-04, 6.6139e-04, 6.6330e-04, 6.6520e-04, 6.6711e-04, 6.6902e-04, 6.7092e-04, 6.7283e-04, 6.7474e-04, 6.7665e-04, 6.7855e-04, 6.8046e-04, 6.8237e-04, 6.8427e-04, 6.8618e-04, 6.8809e-04, 6.8999e-04, 6.9190e-04, 6.9381e-04, 6.9571e-04, 6.9762e-04, 6.9953e-04, 7.0143e-04, 7.0334e-04, 7.0525e-04, 7.0716e-04, 7.0906e-04, 7.1097e-04, 7.1288e-04, 7.1478e-04, 7.1669e-04, 7.1860e-04, 7.2050e-04, 7.2241e-04, 7.2432e-04, 7.2622e-04, 7.2813e-04, 7.3004e-04, 7.3195e-04, 7.3385e-04, 7.3576e-04, 7.3767e-04, 7.3957e-04, 7.4148e-04, 7.4339e-04, 7.4529e-04, 7.4720e-04, 7.4911e-04, 7.5101e-04, 7.5292e-04, 7.5483e-04, 7.5673e-04, 7.5864e-04, 7.6055e-04, 7.6246e-04, 7.6436e-04, 7.6627e-04, 7.6818e-04, 7.7008e-04, 7.7199e-04, 7.7390e-04, 7.7580e-04, 7.7771e-04, 7.7962e-04, 7.8152e-04, 7.8343e-04, 7.8534e-04, 7.8724e-04, 7.8915e-04, 7.9106e-04, 7.9297e-04, 7.9487e-04, 7.9678e-04, 7.9869e-04, 8.0059e-04, 8.0250e-04, 8.0441e-04, 8.0631e-04, 8.0822e-04, 8.1013e-04, 8.1203e-04, 8.1394e-04, 8.1585e-04, 8.1775e-04, 8.1966e-04, 8.2157e-04, 8.2348e-04, 8.2538e-04, 8.2729e-04, 8.2920e-04, 8.3110e-04, 8.3301e-04, 8.3492e-04, 8.3682e-04, 8.3873e-04, 8.4064e-04, 8.4254e-04, 8.4445e-04, 8.4636e-04, 8.4826e-04, 8.5017e-04, 8.5208e-04, 8.5399e-04, 8.5589e-04, 8.5780e-04, 8.5971e-04, 8.6161e-04, 8.6352e-04, 8.6543e-04, 8.6733e-04, 8.6924e-04, 8.7115e-04, 8.7305e-04, 8.7496e-04, 8.7687e-04, 8.7878e-04, 8.8068e-04, 8.8259e-04, 8.8450e-04, 8.8640e-04, 8.8831e-04, 8.9022e-04, 8.9212e-04, 8.9403e-04, 8.9594e-04, 8.9784e-04, 8.9975e-04, 9.0166e-04, 9.0356e-04, 9.0547e-04, 9.0738e-04, 9.0929e-04, 9.1119e-04, 9.1310e-04, 9.1501e-04, 9.1691e-04, 9.1882e-04, 9.2073e-04, 9.2263e-04, 9.2454e-04, 9.2645e-04, 9.2835e-04, 9.3026e-04, 9.3217e-04, 9.3407e-04, 9.3598e-04, 9.3789e-04, 9.3980e-04, 9.4170e-04, 9.4361e-04, 9.4552e-04, 9.4742e-04, 9.4933e-04, 9.5124e-04, 9.5314e-04, 9.5505e-04, 9.5696e-04, 9.5886e-04, 9.6077e-04, 9.6268e-04, 9.6458e-04, 9.6649e-04, 9.6840e-04, 9.7031e-04, 9.7221e-04, 9.7412e-04, 9.7603e-04, + 9.7984e-04, 9.8365e-04, 9.8747e-04, 9.9128e-04, 9.9510e-04, 9.9891e-04, 1.0027e-03, 1.0065e-03, 1.0104e-03, 1.0142e-03, 1.0180e-03, 1.0218e-03, 1.0256e-03, 1.0294e-03, 1.0332e-03, 1.0371e-03, 1.0409e-03, 1.0447e-03, 1.0485e-03, 1.0523e-03, 1.0561e-03, 1.0599e-03, 1.0638e-03, 1.0676e-03, 1.0714e-03, 1.0752e-03, 1.0790e-03, 1.0828e-03, 1.0866e-03, 1.0905e-03, 1.0943e-03, 1.0981e-03, 1.1019e-03, 1.1057e-03, 1.1095e-03, 1.1133e-03, 1.1172e-03, 1.1210e-03, 1.1248e-03, 1.1286e-03, 1.1324e-03, 1.1362e-03, 1.1400e-03, 1.1439e-03, 1.1477e-03, 1.1515e-03, 1.1553e-03, 1.1591e-03, 1.1629e-03, 1.1667e-03, 1.1706e-03, 1.1744e-03, 1.1782e-03, 1.1820e-03, 1.1858e-03, 1.1896e-03, 1.1934e-03, 1.1973e-03, 1.2011e-03, 1.2049e-03, 1.2087e-03, 1.2125e-03, 1.2163e-03, 1.2201e-03, 1.2240e-03, 1.2278e-03, 1.2316e-03, 1.2354e-03, 1.2392e-03, 1.2430e-03, 1.2468e-03, 1.2507e-03, 1.2545e-03, 1.2583e-03, 1.2621e-03, 1.2659e-03, 1.2697e-03, 1.2735e-03, 1.2774e-03, 1.2812e-03, 1.2850e-03, 1.2888e-03, 1.2926e-03, 1.2964e-03, 1.3002e-03, 1.3040e-03, 1.3079e-03, 1.3117e-03, 1.3155e-03, 1.3193e-03, 1.3231e-03, 1.3269e-03, 1.3307e-03, 1.3346e-03, 1.3384e-03, 1.3422e-03, 1.3460e-03, 1.3498e-03, 1.3536e-03, 1.3574e-03, 1.3613e-03, 1.3651e-03, 1.3689e-03, 1.3727e-03, 1.3765e-03, 1.3803e-03, 1.3841e-03, 1.3880e-03, 1.3918e-03, 1.3956e-03, 1.3994e-03, 1.4032e-03, 1.4070e-03, 1.4108e-03, 1.4147e-03, 1.4185e-03, 1.4223e-03, 1.4261e-03, 1.4299e-03, 1.4337e-03, 1.4375e-03, 1.4414e-03, 1.4452e-03, 1.4490e-03, 1.4528e-03, 1.4566e-03, 1.4604e-03, 1.4642e-03, 1.4681e-03, 1.4719e-03, 1.4757e-03, 1.4795e-03, 1.4833e-03, 1.4871e-03, 1.4909e-03, 1.4948e-03, 1.4986e-03, 1.5024e-03, 1.5062e-03, 1.5100e-03, 1.5138e-03, 1.5176e-03, 1.5215e-03, 1.5253e-03, 1.5291e-03, 1.5329e-03, 1.5367e-03, 1.5405e-03, 1.5443e-03, 1.5482e-03, 1.5520e-03, 1.5558e-03, 1.5596e-03, 1.5634e-03, 1.5672e-03, 1.5710e-03, 1.5749e-03, 1.5787e-03, 1.5825e-03, 1.5863e-03, 1.5901e-03, 1.5939e-03, 1.5977e-03, 1.6016e-03, 1.6054e-03, 1.6092e-03, 1.6130e-03, 1.6168e-03, 1.6206e-03, 1.6244e-03, 1.6283e-03, 1.6321e-03, 1.6359e-03, 1.6397e-03, 1.6435e-03, 1.6473e-03, 1.6511e-03, 1.6550e-03, 1.6588e-03, 1.6626e-03, 1.6664e-03, 1.6702e-03, 1.6740e-03, 1.6778e-03, 1.6817e-03, 1.6855e-03, 1.6893e-03, 1.6931e-03, 1.6969e-03, 1.7007e-03, 1.7045e-03, 1.7084e-03, 1.7122e-03, 1.7160e-03, 1.7198e-03, 1.7236e-03, 1.7274e-03, 1.7312e-03, 1.7351e-03, 1.7389e-03, 1.7427e-03, 1.7465e-03, 1.7503e-03, 1.7541e-03, 1.7579e-03, 1.7618e-03, 1.7656e-03, 1.7694e-03, 1.7732e-03, 1.7770e-03, 1.7808e-03, 1.7846e-03, 1.7885e-03, 1.7923e-03, 1.7961e-03, 1.7999e-03, 1.8037e-03, 1.8075e-03, 1.8113e-03, 1.8152e-03, 1.8190e-03, 1.8228e-03, 1.8266e-03, 1.8304e-03, 1.8342e-03, 1.8380e-03, 1.8419e-03, 1.8457e-03, 1.8495e-03, 1.8533e-03, 1.8571e-03, 1.8609e-03, 1.8647e-03, 1.8686e-03, 1.8724e-03, 1.8762e-03, 1.8800e-03, 1.8838e-03, 1.8876e-03, 1.8914e-03, 1.8953e-03, 1.8991e-03, 1.9029e-03, 1.9067e-03, 1.9105e-03, 1.9143e-03, 1.9181e-03, 1.9220e-03, 1.9258e-03, 1.9296e-03, 1.9334e-03, 1.9372e-03, 1.9410e-03, 1.9448e-03, 1.9487e-03, 1.9525e-03, + 1.9601e-03, 1.9677e-03, 1.9754e-03, 1.9830e-03, 1.9906e-03, 1.9982e-03, 2.0059e-03, 2.0135e-03, 2.0211e-03, 2.0288e-03, 2.0364e-03, 2.0440e-03, 2.0516e-03, 2.0593e-03, 2.0669e-03, 2.0745e-03, 2.0822e-03, 2.0898e-03, 2.0974e-03, 2.1050e-03, 2.1127e-03, 2.1203e-03, 2.1279e-03, 2.1356e-03, 2.1432e-03, 2.1508e-03, 2.1585e-03, 2.1661e-03, 2.1737e-03, 2.1813e-03, 2.1890e-03, 2.1966e-03, 2.2042e-03, 2.2119e-03, 2.2195e-03, 2.2271e-03, 2.2347e-03, 2.2424e-03, 2.2500e-03, 2.2576e-03, 2.2653e-03, 2.2729e-03, 2.2805e-03, 2.2881e-03, 2.2958e-03, 2.3034e-03, 2.3110e-03, 2.3187e-03, 2.3263e-03, 2.3339e-03, 2.3415e-03, 2.3492e-03, 2.3568e-03, 2.3644e-03, 2.3721e-03, 2.3797e-03, 2.3873e-03, 2.3949e-03, 2.4026e-03, 2.4102e-03, 2.4178e-03, 2.4255e-03, 2.4331e-03, 2.4407e-03, 2.4483e-03, 2.4560e-03, 2.4636e-03, 2.4712e-03, 2.4789e-03, 2.4865e-03, 2.4941e-03, 2.5018e-03, 2.5094e-03, 2.5170e-03, 2.5246e-03, 2.5323e-03, 2.5399e-03, 2.5475e-03, 2.5552e-03, 2.5628e-03, 2.5704e-03, 2.5780e-03, 2.5857e-03, 2.5933e-03, 2.6009e-03, 2.6086e-03, 2.6162e-03, 2.6238e-03, 2.6314e-03, 2.6391e-03, 2.6467e-03, 2.6543e-03, 2.6620e-03, 2.6696e-03, 2.6772e-03, 2.6848e-03, 2.6925e-03, 2.7001e-03, 2.7077e-03, 2.7154e-03, 2.7230e-03, 2.7306e-03, 2.7382e-03, 2.7459e-03, 2.7535e-03, 2.7611e-03, 2.7688e-03, 2.7764e-03, 2.7840e-03, 2.7917e-03, 2.7993e-03, 2.8069e-03, 2.8145e-03, 2.8222e-03, 2.8298e-03, 2.8374e-03, 2.8451e-03, 2.8527e-03, 2.8603e-03, 2.8679e-03, 2.8756e-03, 2.8832e-03, 2.8908e-03, 2.8985e-03, 2.9061e-03, 2.9137e-03, 2.9213e-03, 2.9290e-03, 2.9366e-03, 2.9442e-03, 2.9519e-03, 2.9595e-03, 2.9671e-03, 2.9747e-03, 2.9824e-03, 2.9900e-03, 2.9976e-03, 3.0053e-03, 3.0129e-03, 3.0205e-03, 3.0281e-03, 3.0358e-03, 3.0434e-03, 3.0510e-03, 3.0587e-03, 3.0663e-03, 3.0739e-03, 3.0816e-03, 3.0892e-03, 3.0968e-03, 3.1044e-03, 3.1121e-03, 3.1197e-03, 3.1273e-03, 3.1350e-03, 3.1426e-03, 3.1502e-03, 3.1578e-03, 3.1655e-03, 3.1731e-03, 3.1807e-03, 3.1884e-03, 3.1960e-03, 3.2036e-03, 3.2112e-03, 3.2189e-03, 3.2265e-03, 3.2341e-03, 3.2418e-03, 3.2494e-03, 3.2570e-03, 3.2646e-03, 3.2723e-03, 3.2799e-03, 3.2875e-03, 3.2952e-03, 3.3028e-03, 3.3104e-03, 3.3180e-03, 3.3257e-03, 3.3333e-03, 3.3409e-03, 3.3486e-03, 3.3562e-03, 3.3638e-03, 3.3715e-03, 3.3791e-03, 3.3867e-03, 3.3943e-03, 3.4020e-03, 3.4096e-03, 3.4172e-03, 3.4249e-03, 3.4325e-03, 3.4401e-03, 3.4477e-03, 3.4554e-03, 3.4630e-03, 3.4706e-03, 3.4783e-03, 3.4859e-03, 3.4935e-03, 3.5011e-03, 3.5088e-03, 3.5164e-03, 3.5240e-03, 3.5317e-03, 3.5393e-03, 3.5469e-03, 3.5545e-03, 3.5622e-03, 3.5698e-03, 3.5774e-03, 3.5851e-03, 3.5927e-03, 3.6003e-03, 3.6079e-03, 3.6156e-03, 3.6232e-03, 3.6308e-03, 3.6385e-03, 3.6461e-03, 3.6537e-03, 3.6613e-03, 3.6690e-03, 3.6766e-03, 3.6842e-03, 3.6919e-03, 3.6995e-03, 3.7071e-03, 3.7148e-03, 3.7224e-03, 3.7300e-03, 3.7376e-03, 3.7453e-03, 3.7529e-03, 3.7605e-03, 3.7682e-03, 3.7758e-03, 3.7834e-03, 3.7910e-03, 3.7987e-03, 3.8063e-03, 3.8139e-03, 3.8216e-03, 3.8292e-03, 3.8368e-03, 3.8444e-03, 3.8521e-03, 3.8597e-03, 3.8673e-03, 3.8750e-03, 3.8826e-03, 3.8902e-03, 3.8978e-03, 3.9055e-03, + 3.9207e-03, 3.9360e-03, 3.9513e-03, 3.9665e-03, 3.9818e-03, 3.9970e-03, 4.0123e-03, 4.0275e-03, 4.0428e-03, 4.0581e-03, 4.0733e-03, 4.0886e-03, 4.1038e-03, 4.1191e-03, 4.1343e-03, 4.1496e-03, 4.1649e-03, 4.1801e-03, 4.1954e-03, 4.2106e-03, 4.2259e-03, 4.2412e-03, 4.2564e-03, 4.2717e-03, 4.2869e-03, 4.3022e-03, 4.3174e-03, 4.3327e-03, 4.3480e-03, 4.3632e-03, 4.3785e-03, 4.3937e-03, 4.4090e-03, 4.4243e-03, 4.4395e-03, 4.4548e-03, 4.4700e-03, 4.4853e-03, 4.5005e-03, 4.5158e-03, 4.5311e-03, 4.5463e-03, 4.5616e-03, 4.5768e-03, 4.5921e-03, 4.6074e-03, 4.6226e-03, 4.6379e-03, 4.6531e-03, 4.6684e-03, 4.6836e-03, 4.6989e-03, 4.7142e-03, 4.7294e-03, 4.7447e-03, 4.7599e-03, 4.7752e-03, 4.7905e-03, 4.8057e-03, 4.8210e-03, 4.8362e-03, 4.8515e-03, 4.8667e-03, 4.8820e-03, 4.8973e-03, 4.9125e-03, 4.9278e-03, 4.9430e-03, 4.9583e-03, 4.9736e-03, 4.9888e-03, 5.0041e-03, 5.0193e-03, 5.0346e-03, 5.0498e-03, 5.0651e-03, 5.0804e-03, 5.0956e-03, 5.1109e-03, 5.1261e-03, 5.1414e-03, 5.1567e-03, 5.1719e-03, 5.1872e-03, 5.2024e-03, 5.2177e-03, 5.2329e-03, 5.2482e-03, 5.2635e-03, 5.2787e-03, 5.2940e-03, 5.3092e-03, 5.3245e-03, 5.3398e-03, 5.3550e-03, 5.3703e-03, 5.3855e-03, 5.4008e-03, 5.4160e-03, 5.4313e-03, 5.4466e-03, 5.4618e-03, 5.4771e-03, 5.4923e-03, 5.5076e-03, 5.5229e-03, 5.5381e-03, 5.5534e-03, 5.5686e-03, 5.5839e-03, 5.5991e-03, 5.6144e-03, 5.6297e-03, 5.6449e-03, 5.6602e-03, 5.6754e-03, 5.6907e-03, 5.7060e-03, 5.7212e-03, 5.7365e-03, 5.7517e-03, 5.7670e-03, 5.7822e-03, 5.7975e-03, 5.8128e-03, 5.8280e-03, 5.8433e-03, 5.8585e-03, 5.8738e-03, 5.8891e-03, 5.9043e-03, 5.9196e-03, 5.9348e-03, 5.9501e-03, 5.9653e-03, 5.9806e-03, 5.9959e-03, 6.0111e-03, 6.0264e-03, 6.0416e-03, 6.0569e-03, 6.0722e-03, 6.0874e-03, 6.1027e-03, 6.1179e-03, 6.1332e-03, 6.1484e-03, 6.1637e-03, 6.1790e-03, 6.1942e-03, 6.2095e-03, 6.2247e-03, 6.2400e-03, 6.2553e-03, 6.2705e-03, 6.2858e-03, 6.3010e-03, 6.3163e-03, 6.3315e-03, 6.3468e-03, 6.3621e-03, 6.3773e-03, 6.3926e-03, 6.4078e-03, 6.4231e-03, 6.4384e-03, 6.4536e-03, 6.4689e-03, 6.4841e-03, 6.4994e-03, 6.5146e-03, 6.5299e-03, 6.5452e-03, 6.5604e-03, 6.5757e-03, 6.5909e-03, 6.6062e-03, 6.6215e-03, 6.6367e-03, 6.6520e-03, 6.6672e-03, 6.6825e-03, 6.6977e-03, 6.7130e-03, 6.7283e-03, 6.7435e-03, 6.7588e-03, 6.7740e-03, 6.7893e-03, 6.8046e-03, 6.8198e-03, 6.8351e-03, 6.8503e-03, 6.8656e-03, 6.8808e-03, 6.8961e-03, 6.9114e-03, 6.9266e-03, 6.9419e-03, 6.9571e-03, 6.9724e-03, 6.9877e-03, 7.0029e-03, 7.0182e-03, 7.0334e-03, 7.0487e-03, 7.0639e-03, 7.0792e-03, 7.0945e-03, 7.1097e-03, 7.1250e-03, 7.1402e-03, 7.1555e-03, 7.1708e-03, 7.1860e-03, 7.2013e-03, 7.2165e-03, 7.2318e-03, 7.2470e-03, 7.2623e-03, 7.2776e-03, 7.2928e-03, 7.3081e-03, 7.3233e-03, 7.3386e-03, 7.3539e-03, 7.3691e-03, 7.3844e-03, 7.3996e-03, 7.4149e-03, 7.4301e-03, 7.4454e-03, 7.4607e-03, 7.4759e-03, 7.4912e-03, 7.5064e-03, 7.5217e-03, 7.5370e-03, 7.5522e-03, 7.5675e-03, 7.5827e-03, 7.5980e-03, 7.6132e-03, 7.6285e-03, 7.6438e-03, 7.6590e-03, 7.6743e-03, 7.6895e-03, 7.7048e-03, 7.7201e-03, 7.7353e-03, 7.7506e-03, 7.7658e-03, 7.7811e-03, 7.7963e-03, 7.8116e-03, + 7.8421e-03, 7.8726e-03, 7.9032e-03, 7.9337e-03, 7.9642e-03, 7.9947e-03, 8.0252e-03, 8.0557e-03, 8.0863e-03, 8.1168e-03, 8.1473e-03, 8.1778e-03, 8.2083e-03, 8.2388e-03, 8.2694e-03, 8.2999e-03, 8.3304e-03, 8.3609e-03, 8.3914e-03, 8.4219e-03, 8.4525e-03, 8.4830e-03, 8.5135e-03, 8.5440e-03, 8.5745e-03, 8.6051e-03, 8.6356e-03, 8.6661e-03, 8.6966e-03, 8.7271e-03, 8.7576e-03, 8.7882e-03, 8.8187e-03, 8.8492e-03, 8.8797e-03, 8.9102e-03, 8.9407e-03, 8.9713e-03, 9.0018e-03, 9.0323e-03, 9.0628e-03, 9.0933e-03, 9.1238e-03, 9.1544e-03, 9.1849e-03, 9.2154e-03, 9.2459e-03, 9.2764e-03, 9.3069e-03, 9.3375e-03, 9.3680e-03, 9.3985e-03, 9.4290e-03, 9.4595e-03, 9.4900e-03, 9.5206e-03, 9.5511e-03, 9.5816e-03, 9.6121e-03, 9.6426e-03, 9.6731e-03, 9.7037e-03, 9.7342e-03, 9.7647e-03, 9.7952e-03, 9.8257e-03, 9.8563e-03, 9.8868e-03, 9.9173e-03, 9.9478e-03, 9.9783e-03, 1.0009e-02, 1.0039e-02, 1.0070e-02, 1.0100e-02, 1.0131e-02, 1.0161e-02, 1.0192e-02, 1.0222e-02, 1.0253e-02, 1.0283e-02, 1.0314e-02, 1.0345e-02, 1.0375e-02, 1.0406e-02, 1.0436e-02, 1.0467e-02, 1.0497e-02, 1.0528e-02, 1.0558e-02, 1.0589e-02, 1.0619e-02, 1.0650e-02, 1.0680e-02, 1.0711e-02, 1.0741e-02, 1.0772e-02, 1.0802e-02, 1.0833e-02, 1.0863e-02, 1.0894e-02, 1.0924e-02, 1.0955e-02, 1.0985e-02, 1.1016e-02, 1.1046e-02, 1.1077e-02, 1.1107e-02, 1.1138e-02, 1.1168e-02, 1.1199e-02, 1.1230e-02, 1.1260e-02, 1.1291e-02, 1.1321e-02, 1.1352e-02, 1.1382e-02, 1.1413e-02, 1.1443e-02, 1.1474e-02, 1.1504e-02, 1.1535e-02, 1.1565e-02, 1.1596e-02, 1.1626e-02, 1.1657e-02, 1.1687e-02, 1.1718e-02, 1.1748e-02, 1.1779e-02, 1.1809e-02, 1.1840e-02, 1.1870e-02, 1.1901e-02, 1.1931e-02, 1.1962e-02, 1.1992e-02, 1.2023e-02, 1.2053e-02, 1.2084e-02, 1.2115e-02, 1.2145e-02, 1.2176e-02, 1.2206e-02, 1.2237e-02, 1.2267e-02, 1.2298e-02, 1.2328e-02, 1.2359e-02, 1.2389e-02, 1.2420e-02, 1.2450e-02, 1.2481e-02, 1.2511e-02, 1.2542e-02, 1.2572e-02, 1.2603e-02, 1.2633e-02, 1.2664e-02, 1.2694e-02, 1.2725e-02, 1.2755e-02, 1.2786e-02, 1.2816e-02, 1.2847e-02, 1.2877e-02, 1.2908e-02, 1.2938e-02, 1.2969e-02, 1.3000e-02, 1.3030e-02, 1.3061e-02, 1.3091e-02, 1.3122e-02, 1.3152e-02, 1.3183e-02, 1.3213e-02, 1.3244e-02, 1.3274e-02, 1.3305e-02, 1.3335e-02, 1.3366e-02, 1.3396e-02, 1.3427e-02, 1.3457e-02, 1.3488e-02, 1.3518e-02, 1.3549e-02, 1.3579e-02, 1.3610e-02, 1.3640e-02, 1.3671e-02, 1.3701e-02, 1.3732e-02, 1.3762e-02, 1.3793e-02, 1.3823e-02, 1.3854e-02, 1.3885e-02, 1.3915e-02, 1.3946e-02, 1.3976e-02, 1.4007e-02, 1.4037e-02, 1.4068e-02, 1.4098e-02, 1.4129e-02, 1.4159e-02, 1.4190e-02, 1.4220e-02, 1.4251e-02, 1.4281e-02, 1.4312e-02, 1.4342e-02, 1.4373e-02, 1.4403e-02, 1.4434e-02, 1.4464e-02, 1.4495e-02, 1.4525e-02, 1.4556e-02, 1.4586e-02, 1.4617e-02, 1.4647e-02, 1.4678e-02, 1.4708e-02, 1.4739e-02, 1.4770e-02, 1.4800e-02, 1.4831e-02, 1.4861e-02, 1.4892e-02, 1.4922e-02, 1.4953e-02, 1.4983e-02, 1.5014e-02, 1.5044e-02, 1.5075e-02, 1.5105e-02, 1.5136e-02, 1.5166e-02, 1.5197e-02, 1.5227e-02, 1.5258e-02, 1.5288e-02, 1.5319e-02, 1.5349e-02, 1.5380e-02, 1.5410e-02, 1.5441e-02, 1.5471e-02, 1.5502e-02, 1.5532e-02, 1.5563e-02, 1.5593e-02, 1.5624e-02, + 1.5746e-02, 1.5868e-02, 1.5990e-02, 1.6112e-02, 1.6234e-02, 1.6356e-02, 1.6478e-02, 1.6601e-02, 1.6723e-02, 1.6845e-02, 1.6967e-02, 1.7089e-02, 1.7211e-02, 1.7333e-02, 1.7455e-02, 1.7577e-02, 1.7699e-02, 1.7821e-02, 1.7943e-02, 1.8065e-02, 1.8187e-02, 1.8310e-02, 1.8432e-02, 1.8554e-02, 1.8676e-02, 1.8798e-02, 1.8920e-02, 1.9042e-02, 1.9164e-02, 1.9286e-02, 1.9408e-02, 1.9530e-02, 1.9652e-02, 1.9774e-02, 1.9896e-02, 2.0018e-02, 2.0141e-02, 2.0263e-02, 2.0385e-02, 2.0507e-02, 2.0629e-02, 2.0751e-02, 2.0873e-02, 2.0995e-02, 2.1117e-02, 2.1239e-02, 2.1361e-02, 2.1483e-02, 2.1605e-02, 2.1727e-02, 2.1850e-02, 2.1972e-02, 2.2094e-02, 2.2216e-02, 2.2338e-02, 2.2460e-02, 2.2582e-02, 2.2704e-02, 2.2826e-02, 2.2948e-02, 2.3070e-02, 2.3192e-02, 2.3314e-02, 2.3436e-02, 2.3558e-02, 2.3681e-02, 2.3803e-02, 2.3925e-02, 2.4047e-02, 2.4169e-02, 2.4291e-02, 2.4413e-02, 2.4535e-02, 2.4657e-02, 2.4779e-02, 2.4901e-02, 2.5023e-02, 2.5145e-02, 2.5267e-02, 2.5390e-02, 2.5512e-02, 2.5634e-02, 2.5756e-02, 2.5878e-02, 2.6000e-02, 2.6122e-02, 2.6244e-02, 2.6366e-02, 2.6488e-02, 2.6610e-02, 2.6732e-02, 2.6854e-02, 2.6976e-02, 2.7099e-02, 2.7221e-02, 2.7343e-02, 2.7465e-02, 2.7587e-02, 2.7709e-02, 2.7831e-02, 2.7953e-02, 2.8075e-02, 2.8197e-02, 2.8319e-02, 2.8441e-02, 2.8563e-02, 2.8685e-02, 2.8807e-02, 2.8930e-02, 2.9052e-02, 2.9174e-02, 2.9296e-02, 2.9418e-02, 2.9540e-02, 2.9662e-02, 2.9784e-02, 2.9906e-02, 3.0028e-02, 3.0150e-02, 3.0272e-02, 3.0394e-02, 3.0516e-02, 3.0639e-02, 3.0761e-02, 3.0883e-02, 3.1005e-02, 3.1127e-02, 3.1249e-02, 3.1493e-02, 3.1737e-02, 3.1981e-02, 3.2225e-02, 3.2470e-02, 3.2714e-02, 3.2958e-02, 3.3202e-02, 3.3446e-02, 3.3690e-02, 3.3934e-02, 3.4179e-02, 3.4423e-02, 3.4667e-02, 3.4911e-02, 3.5155e-02, 3.5399e-02, 3.5643e-02, 3.5888e-02, 3.6132e-02, 3.6376e-02, 3.6620e-02, 3.6864e-02, 3.7108e-02, 3.7352e-02, 3.7596e-02, 3.7841e-02, 3.8085e-02, 3.8329e-02, 3.8573e-02, 3.8817e-02, 3.9061e-02, 3.9305e-02, 3.9550e-02, 3.9794e-02, 4.0038e-02, 4.0282e-02, 4.0526e-02, 4.0770e-02, 4.1014e-02, 4.1259e-02, 4.1503e-02, 4.1747e-02, 4.1991e-02, 4.2235e-02, 4.2479e-02, 4.2723e-02, 4.2968e-02, 4.3212e-02, 4.3456e-02, 4.3700e-02, 4.3944e-02, 4.4188e-02, 4.4432e-02, 4.4677e-02, 4.4921e-02, 4.5165e-02, 4.5409e-02, 4.5653e-02, 4.5897e-02, 4.6141e-02, 4.6386e-02, 4.6630e-02, 4.6874e-02, 4.7118e-02, 4.7362e-02, 4.7606e-02, 4.7850e-02, 4.8095e-02, 4.8339e-02, 4.8583e-02, 4.8827e-02, 4.9071e-02, 4.9315e-02, 4.9559e-02, 4.9803e-02, 5.0048e-02, 5.0292e-02, 5.0536e-02, 5.0780e-02, 5.1024e-02, 5.1268e-02, 5.1512e-02, 5.1757e-02, 5.2001e-02, 5.2245e-02, 5.2489e-02, 5.2733e-02, 5.2977e-02, 5.3221e-02, 5.3466e-02, 5.3710e-02, 5.3954e-02, 5.4198e-02, 5.4442e-02, 5.4686e-02, 5.4930e-02, 5.5175e-02, 5.5419e-02, 5.5663e-02, 5.5907e-02, 5.6151e-02, 5.6395e-02, 5.6639e-02, 5.6884e-02, 5.7128e-02, 5.7372e-02, 5.7616e-02, 5.7860e-02, 5.8104e-02, 5.8348e-02, 5.8593e-02, 5.8837e-02, 5.9081e-02, 5.9325e-02, 5.9569e-02, 5.9813e-02, 6.0057e-02, 6.0301e-02, 6.0546e-02, 6.0790e-02, 6.1034e-02, 6.1278e-02, 6.1522e-02, 6.1766e-02, 6.2010e-02, 6.2255e-02, 6.2499e-02, + 6.2743e-02, 6.2987e-02, 6.3231e-02, 6.3475e-02, 6.3719e-02, 6.3964e-02, 6.4208e-02, 6.4452e-02, 6.4696e-02, 6.4940e-02, 6.5184e-02, 6.5428e-02, 6.5673e-02, 6.5917e-02, 6.6161e-02, 6.6405e-02, 6.6649e-02, 6.6893e-02, 6.7137e-02, 6.7382e-02, 6.7626e-02, 6.7870e-02, 6.8114e-02, 6.8358e-02, 6.8602e-02, 6.8846e-02, 6.9091e-02, 6.9335e-02, 6.9579e-02, 6.9823e-02, 7.0067e-02, 7.0311e-02, 7.0555e-02, 7.0799e-02, 7.1044e-02, 7.1288e-02, 7.1532e-02, 7.1776e-02, 7.2020e-02, 7.2264e-02, 7.2508e-02, 7.2753e-02, 7.2997e-02, 7.3241e-02, 7.3485e-02, 7.3729e-02, 7.3973e-02, 7.4217e-02, 7.4462e-02, 7.4706e-02, 7.4950e-02, 7.5194e-02, 7.5438e-02, 7.5682e-02, 7.5926e-02, 7.6171e-02, 7.6415e-02, 7.6659e-02, 7.6903e-02, 7.7147e-02, 7.7391e-02, 7.7635e-02, 7.7880e-02, 7.8124e-02, 7.8368e-02, 7.8612e-02, 7.8856e-02, 7.9100e-02, 7.9344e-02, 7.9589e-02, 7.9833e-02, 8.0077e-02, 8.0321e-02, 8.0565e-02, 8.0809e-02, 8.1053e-02, 8.1298e-02, 8.1542e-02, 8.1786e-02, 8.2030e-02, 8.2274e-02, 8.2518e-02, 8.2762e-02, 8.3006e-02, 8.3251e-02, 8.3495e-02, 8.3739e-02, 8.3983e-02, 8.4227e-02, 8.4471e-02, 8.4715e-02, 8.4960e-02, 8.5204e-02, 8.5448e-02, 8.5692e-02, 8.5936e-02, 8.6180e-02, 8.6424e-02, 8.6669e-02, 8.6913e-02, 8.7157e-02, 8.7401e-02, 8.7645e-02, 8.7889e-02, 8.8133e-02, 8.8378e-02, 8.8622e-02, 8.8866e-02, 8.9110e-02, 8.9354e-02, 8.9598e-02, 8.9842e-02, 9.0087e-02, 9.0331e-02, 9.0575e-02, 9.0819e-02, 9.1063e-02, 9.1307e-02, 9.1551e-02, 9.1796e-02, 9.2040e-02, 9.2284e-02, 9.2528e-02, 9.2772e-02, 9.3016e-02, 9.3260e-02, 9.3504e-02, 9.3749e-02, 9.4237e-02, 9.4725e-02, 9.5213e-02, 9.5702e-02, 9.6190e-02, 9.6678e-02, 9.7167e-02, 9.7655e-02, 9.8143e-02, 9.8631e-02, 9.9120e-02, 9.9608e-02, 1.0010e-01, 1.0058e-01, 1.0107e-01, 1.0156e-01, 1.0205e-01, 1.0254e-01, 1.0303e-01, 1.0351e-01, 1.0400e-01, 1.0449e-01, 1.0498e-01, 1.0547e-01, 1.0596e-01, 1.0644e-01, 1.0693e-01, 1.0742e-01, 1.0791e-01, 1.0840e-01, 1.0889e-01, 1.0937e-01, 1.0986e-01, 1.1035e-01, 1.1084e-01, 1.1133e-01, 1.1182e-01, 1.1230e-01, 1.1279e-01, 1.1328e-01, 1.1377e-01, 1.1426e-01, 1.1474e-01, 1.1523e-01, 1.1572e-01, 1.1621e-01, 1.1670e-01, 1.1719e-01, 1.1767e-01, 1.1816e-01, 1.1865e-01, 1.1914e-01, 1.1963e-01, 1.2012e-01, 1.2060e-01, 1.2109e-01, 1.2158e-01, 1.2207e-01, 1.2256e-01, 1.2305e-01, 1.2353e-01, 1.2402e-01, 1.2451e-01, 1.2500e-01, 1.2549e-01, 1.2598e-01, 1.2646e-01, 1.2695e-01, 1.2744e-01, 1.2793e-01, 1.2842e-01, 1.2890e-01, 1.2939e-01, 1.2988e-01, 1.3037e-01, 1.3086e-01, 1.3135e-01, 1.3183e-01, 1.3232e-01, 1.3281e-01, 1.3330e-01, 1.3379e-01, 1.3428e-01, 1.3476e-01, 1.3525e-01, 1.3574e-01, 1.3623e-01, 1.3672e-01, 1.3721e-01, 1.3769e-01, 1.3818e-01, 1.3867e-01, 1.3916e-01, 1.3965e-01, 1.4014e-01, 1.4062e-01, 1.4111e-01, 1.4160e-01, 1.4209e-01, 1.4258e-01, 1.4306e-01, 1.4355e-01, 1.4404e-01, 1.4453e-01, 1.4502e-01, 1.4551e-01, 1.4599e-01, 1.4648e-01, 1.4697e-01, 1.4746e-01, 1.4795e-01, 1.4844e-01, 1.4892e-01, 1.4941e-01, 1.4990e-01, 1.5039e-01, 1.5088e-01, 1.5137e-01, 1.5185e-01, 1.5234e-01, 1.5283e-01, 1.5332e-01, 1.5381e-01, 1.5430e-01, 1.5478e-01, 1.5527e-01, 1.5576e-01, 1.5625e-01, + 1.5674e-01, 1.5723e-01, 1.5771e-01, 1.5820e-01, 1.5869e-01, 1.5918e-01, 1.5967e-01, 1.6015e-01, 1.6064e-01, 1.6113e-01, 1.6162e-01, 1.6211e-01, 1.6260e-01, 1.6308e-01, 1.6357e-01, 1.6406e-01, 1.6455e-01, 1.6504e-01, 1.6553e-01, 1.6601e-01, 1.6650e-01, 1.6699e-01, 1.6748e-01, 1.6797e-01, 1.6846e-01, 1.6894e-01, 1.6943e-01, 1.6992e-01, 1.7041e-01, 1.7090e-01, 1.7139e-01, 1.7187e-01, 1.7236e-01, 1.7285e-01, 1.7334e-01, 1.7383e-01, 1.7431e-01, 1.7480e-01, 1.7529e-01, 1.7578e-01, 1.7627e-01, 1.7676e-01, 1.7724e-01, 1.7773e-01, 1.7822e-01, 1.7871e-01, 1.7920e-01, 1.7969e-01, 1.8017e-01, 1.8066e-01, 1.8115e-01, 1.8164e-01, 1.8213e-01, 1.8262e-01, 1.8310e-01, 1.8359e-01, 1.8408e-01, 1.8457e-01, 1.8506e-01, 1.8555e-01, 1.8603e-01, 1.8652e-01, 1.8701e-01, 1.8750e-01, 1.8848e-01, 1.8945e-01, 1.9043e-01, 1.9140e-01, 1.9238e-01, 1.9336e-01, 1.9433e-01, 1.9531e-01, 1.9629e-01, 1.9726e-01, 1.9824e-01, 1.9922e-01, 2.0019e-01, 2.0117e-01, 2.0215e-01, 2.0312e-01, 2.0410e-01, 2.0508e-01, 2.0605e-01, 2.0703e-01, 2.0801e-01, 2.0898e-01, 2.0996e-01, 2.1094e-01, 2.1191e-01, 2.1289e-01, 2.1387e-01, 2.1484e-01, 2.1582e-01, 2.1680e-01, 2.1777e-01, 2.1875e-01, 2.1972e-01, 2.2070e-01, 2.2168e-01, 2.2265e-01, 2.2363e-01, 2.2461e-01, 2.2558e-01, 2.2656e-01, 2.2754e-01, 2.2851e-01, 2.2949e-01, 2.3047e-01, 2.3144e-01, 2.3242e-01, 2.3340e-01, 2.3437e-01, 2.3535e-01, 2.3633e-01, 2.3730e-01, 2.3828e-01, 2.3926e-01, 2.4023e-01, 2.4121e-01, 2.4219e-01, 2.4316e-01, 2.4414e-01, 2.4512e-01, 2.4609e-01, 2.4707e-01, 2.4805e-01, 2.4902e-01, 2.5000e-01, 2.5097e-01, 2.5195e-01, 2.5293e-01, 2.5390e-01, 2.5488e-01, 2.5586e-01, 2.5683e-01, 2.5781e-01, 2.5879e-01, 2.5976e-01, 2.6074e-01, 2.6172e-01, 2.6269e-01, 2.6367e-01, 2.6465e-01, 2.6562e-01, 2.6660e-01, 2.6758e-01, 2.6855e-01, 2.6953e-01, 2.7051e-01, 2.7148e-01, 2.7246e-01, 2.7344e-01, 2.7441e-01, 2.7539e-01, 2.7637e-01, 2.7734e-01, 2.7832e-01, 2.7930e-01, 2.8027e-01, 2.8125e-01, 2.8222e-01, 2.8320e-01, 2.8418e-01, 2.8515e-01, 2.8613e-01, 2.8711e-01, 2.8808e-01, 2.8906e-01, 2.9004e-01, 2.9101e-01, 2.9199e-01, 2.9297e-01, 2.9394e-01, 2.9492e-01, 2.9590e-01, 2.9687e-01, 2.9785e-01, 2.9883e-01, 2.9980e-01, 3.0078e-01, 3.0176e-01, 3.0273e-01, 3.0371e-01, 3.0469e-01, 3.0566e-01, 3.0664e-01, 3.0762e-01, 3.0859e-01, 3.0957e-01, 3.1055e-01, 3.1152e-01, 3.1250e-01, 3.1347e-01, 3.1445e-01, 3.1543e-01, 3.1640e-01, 3.1738e-01, 3.1836e-01, 3.1933e-01, 3.2031e-01, 3.2129e-01, 3.2226e-01, 3.2324e-01, 3.2422e-01, 3.2519e-01, 3.2617e-01, 3.2715e-01, 3.2812e-01, 3.2910e-01, 3.3008e-01, 3.3105e-01, 3.3203e-01, 3.3301e-01, 3.3398e-01, 3.3496e-01, 3.3594e-01, 3.3691e-01, 3.3789e-01, 3.3887e-01, 3.3984e-01, 3.4082e-01, 3.4180e-01, 3.4277e-01, 3.4375e-01, 3.4472e-01, 3.4570e-01, 3.4668e-01, 3.4765e-01, 3.4863e-01, 3.4961e-01, 3.5058e-01, 3.5156e-01, 3.5254e-01, 3.5351e-01, 3.5449e-01, 3.5547e-01, 3.5644e-01, 3.5742e-01, 3.5840e-01, 3.5937e-01, 3.6035e-01, 3.6133e-01, 3.6230e-01, 3.6328e-01, 3.6426e-01, 3.6523e-01, 3.6621e-01, 3.6719e-01, 3.6816e-01, 3.6914e-01, 3.7012e-01, 3.7109e-01, 3.7207e-01, 3.7305e-01, 3.7402e-01, 3.7500e-01, + 3.7695e-01, 3.7890e-01, 3.8086e-01, 3.8281e-01, 3.8476e-01, 3.8672e-01, 3.8867e-01, 3.9062e-01, 3.9258e-01, 3.9453e-01, 3.9648e-01, 3.9844e-01, 4.0039e-01, 4.0234e-01, 4.0430e-01, 4.0625e-01, 4.0820e-01, 4.1015e-01, 4.1211e-01, 4.1406e-01, 4.1601e-01, 4.1797e-01, 4.1992e-01, 4.2187e-01, 4.2383e-01, 4.2578e-01, 4.2773e-01, 4.2969e-01, 4.3164e-01, 4.3359e-01, 4.3555e-01, 4.3750e-01, 4.3945e-01, 4.4140e-01, 4.4336e-01, 4.4531e-01, 4.4726e-01, 4.4922e-01, 4.5117e-01, 4.5312e-01, 4.5508e-01, 4.5703e-01, 4.5898e-01, 4.6094e-01, 4.6289e-01, 4.6484e-01, 4.6680e-01, 4.6875e-01, 4.7070e-01, 4.7265e-01, 4.7461e-01, 4.7656e-01, 4.7851e-01, 4.8047e-01, 4.8242e-01, 4.8437e-01, 4.8633e-01, 4.8828e-01, 4.9023e-01, 4.9219e-01, 4.9414e-01, 4.9609e-01, 4.9805e-01, 5.0000e-01, 5.0195e-01, 5.0390e-01, 5.0586e-01, 5.0781e-01, 5.0976e-01, 5.1172e-01, 5.1367e-01, 5.1562e-01, 5.1758e-01, 5.1953e-01, 5.2148e-01, 5.2344e-01, 5.2539e-01, 5.2734e-01, 5.2930e-01, 5.3125e-01, 5.3320e-01, 5.3515e-01, 5.3711e-01, 5.3906e-01, 5.4101e-01, 5.4297e-01, 5.4492e-01, 5.4687e-01, 5.4883e-01, 5.5078e-01, 5.5273e-01, 5.5469e-01, 5.5664e-01, 5.5859e-01, 5.6055e-01, 5.6250e-01, 5.6445e-01, 5.6640e-01, 5.6836e-01, 5.7031e-01, 5.7226e-01, 5.7422e-01, 5.7617e-01, 5.7812e-01, 5.8008e-01, 5.8203e-01, 5.8398e-01, 5.8594e-01, 5.8789e-01, 5.8984e-01, 5.9180e-01, 5.9375e-01, 5.9570e-01, 5.9765e-01, 5.9961e-01, 6.0156e-01, 6.0351e-01, 6.0547e-01, 6.0742e-01, 6.0937e-01, 6.1133e-01, 6.1328e-01, 6.1523e-01, 6.1719e-01, 6.1914e-01, 6.2109e-01, 6.2305e-01, 6.2500e-01, 6.2695e-01, 6.2890e-01, 6.3086e-01, 6.3281e-01, 6.3476e-01, 6.3672e-01, 6.3867e-01, 6.4062e-01, 6.4258e-01, 6.4453e-01, 6.4648e-01, 6.4844e-01, 6.5039e-01, 6.5234e-01, 6.5430e-01, 6.5625e-01, 6.5820e-01, 6.6015e-01, 6.6211e-01, 6.6406e-01, 6.6601e-01, 6.6797e-01, 6.6992e-01, 6.7187e-01, 6.7383e-01, 6.7578e-01, 6.7773e-01, 6.7969e-01, 6.8164e-01, 6.8359e-01, 6.8554e-01, 6.8750e-01, 6.8945e-01, 6.9140e-01, 6.9336e-01, 6.9531e-01, 6.9726e-01, 6.9922e-01, 7.0117e-01, 7.0312e-01, 7.0508e-01, 7.0703e-01, 7.0898e-01, 7.1094e-01, 7.1289e-01, 7.1484e-01, 7.1679e-01, 7.1875e-01, 7.2070e-01, 7.2265e-01, 7.2461e-01, 7.2656e-01, 7.2851e-01, 7.3047e-01, 7.3242e-01, 7.3437e-01, 7.3633e-01, 7.3828e-01, 7.4023e-01, 7.4219e-01, 7.4414e-01, 7.4609e-01, 7.4804e-01, 7.5000e-01, 7.5390e-01, 7.5781e-01, 7.6172e-01, 7.6562e-01, 7.6953e-01, 7.7344e-01, 7.7734e-01, 7.8125e-01, 7.8515e-01, 7.8906e-01, 7.9297e-01, 7.9687e-01, 8.0078e-01, 8.0469e-01, 8.0859e-01, 8.1250e-01, 8.1640e-01, 8.2031e-01, 8.2422e-01, 8.2812e-01, 8.3203e-01, 8.3594e-01, 8.3984e-01, 8.4375e-01, 8.4765e-01, 8.5156e-01, 8.5547e-01, 8.5937e-01, 8.6328e-01, 8.6719e-01, 8.7109e-01, 8.7500e-01, 8.7890e-01, 8.8281e-01, 8.8672e-01, 8.9062e-01, 8.9453e-01, 8.9844e-01, 9.0234e-01, 9.0625e-01, 9.1015e-01, 9.1406e-01, 9.1797e-01, 9.2187e-01, 9.2578e-01, 9.2969e-01, 9.3359e-01, 9.3750e-01, 9.4140e-01, 9.4531e-01, 9.4922e-01, 9.5312e-01, 9.5703e-01, 9.6094e-01, 9.6484e-01, 9.6875e-01, 9.7265e-01, 9.7656e-01, 9.8047e-01, 9.8437e-01, 9.8828e-01, 9.9219e-01, 9.9609e-01, 1.0000e+00 +}; + float4 val4_from_12(uchar8 pvs, float gain) { uint4 parsed = (uint4)(((uint)pvs.s0<<4) + (pvs.s1>>4), // is from the previous 10 bit ((uint)pvs.s2<<4) + (pvs.s4&0xF), ((uint)pvs.s3<<4) + (pvs.s4>>4), ((uint)pvs.s5<<4) + (pvs.s7&0xF)); + #if IS_OX + // PWL + //float4 pv = (convert_float4(parsed) - 64.0) / (4096.0 - 64.0); + float4 pv = {ox03c10_lut[parsed.s0], ox03c10_lut[parsed.s1], ox03c10_lut[parsed.s2], ox03c10_lut[parsed.s3]}; + + // it's a 24 bit signal, center in the middle 8 bits + return pv*256.0; + #else // AR // normalize and scale float4 pv = (convert_float4(parsed) - 168.0) / (4096.0 - 168.0); return clamp(pv*gain, 0.0, 1.0); + #endif + } float get_k(float a, float b, float c, float d) { diff --git a/system/camerad/cameras/sensor2_i2c.h b/system/camerad/cameras/sensor2_i2c.h index 284347623b..9df99552e1 100644 --- a/system/camerad/cameras/sensor2_i2c.h +++ b/system/camerad/cameras/sensor2_i2c.h @@ -1,48 +1,754 @@ struct i2c_random_wr_payload start_reg_array_ar0231[] = {{0x301A, 0x91C}}; struct i2c_random_wr_payload stop_reg_array_ar0231[] = {{0x301A, 0x918}}; -struct i2c_random_wr_payload start_reg_array_imx390[] = {{0x0, 0}}; -struct i2c_random_wr_payload stop_reg_array_imx390[] = {{0x0, 1}}; +struct i2c_random_wr_payload start_reg_array_ox03c10[] = {{0x100, 1}}; +struct i2c_random_wr_payload stop_reg_array_ox03c10[] = {{0x100, 0}}; -struct i2c_random_wr_payload init_array_imx390[] = { - {0x2008, 0xd0}, {0x2009, 0x07}, {0x200a, 0x00}, // MODE_VMAX = time between frames - {0x200C, 0xe4}, {0x200D, 0x0c}, // MODE_HMAX +struct i2c_random_wr_payload init_array_ox03c10[] = { + {0x103, 1}, + {0x107, 1}, - // crop - {0x3410, 0x88}, {0x3411, 0x7}, // CROP_H_SIZE - {0x3418, 0xb8}, {0x3419, 0x4}, // CROP_V_SIZE - {0x0078, 1}, {0x03c0, 1}, + // X3C_1920x1280_60fps_HDR4_LFR_PWL12_mipi1200 - // external trigger (off) - // while images still come in, they are blank with this - {0x3650, 0}, // CU_MODE + // TPM + {0x4d5a, 0x1a}, {0x4d09, 0xff}, {0x4d09, 0xdf}, - // exposure - {0x000c, 0xc0}, {0x000d, 0x07}, - {0x0010, 0xc0}, {0x0011, 0x07}, + /*) + // group 4 + {0x3208, 0x04}, + {0x4620, 0x04}, + {0x3208, 0x14}, - // WUXGA mode - // not in datasheet, from https://github.com/bogsen/STLinux-Kernel/blob/master/drivers/media/platform/tegra/imx185.c - {0x0086, 0xc4}, {0x0087, 0xff}, // WND_SHIFT_V = -60 - {0x03c6, 0xc4}, {0x03c7, 0xff}, // SM_WND_SHIFT_V_APL = -60 + // group 5 + {0x3208, 0x05}, + {0x4620, 0x04}, + {0x3208, 0x15}, - {0x201c, 0xe1}, {0x201d, 0x12}, // image read amount - {0x21ee, 0xc4}, {0x21ef, 0x04}, // image send amount (1220 is the end) - {0x21f0, 0xc4}, {0x21f1, 0x04}, // image processing amount + // group 2 + {0x3208, 0x02}, + {0x3507, 0x00}, + {0x3208, 0x12}, - // disable a bunch of errors causing blanking - {0x0390, 0x00}, {0x0391, 0x00}, {0x0392, 0x00}, + // delay launch group 2 + {0x3208, 0xa2},*/ - // flip bayer - {0x2D64, 0x64 + 2}, + // PLL setup + {0x0301, 0xc8}, // pll1_divs, pll1_predivp, pll1_divpix + {0x0303, 0x01}, // pll1_prediv + {0x0304, 0x01}, {0x0305, 0x2c}, // pll1_loopdiv = 300 + {0x0306, 0x04}, // pll1_divmipi = 4 + {0x0307, 0x01}, // pll1_divm = 1 + {0x0316, 0x00}, + {0x0317, 0x00}, + {0x0318, 0x00}, + {0x0323, 0x05}, // pll2_prediv + {0x0324, 0x01}, {0x0325, 0x2c}, // pll2_divp = 300 - // color correction - {0x0030, 0xf8}, {0x0031, 0x00}, // red gain - {0x0032, 0x9a}, {0x0033, 0x00}, // gr gain - {0x0034, 0x9a}, {0x0035, 0x00}, // gb gain - {0x0036, 0x22}, {0x0037, 0x01}, // blue gain + // SCLK/PCLK + {0x0400, 0xe0}, {0x0401, 0x80}, + {0x0403, 0xde}, {0x0404, 0x34}, + {0x0405, 0x3b}, {0x0406, 0xde}, + {0x0407, 0x08}, + {0x0408, 0xe0}, {0x0409, 0x7f}, + {0x040a, 0xde}, {0x040b, 0x34}, + {0x040c, 0x47}, {0x040d, 0xd8}, + {0x040e, 0x08}, - // hdr enable (noise with this on for now) - {0x00f9, 0} + // xchk + {0x2803, 0xfe}, {0x280b, 0x00}, {0x280c, 0x79}, + + // SC ctrl + {0x3001, 0x03}, // io_pad_oen + {0x3002, 0xf8}, // io_pad_oen + {0x3005, 0x80}, // io_pad_out + {0x3007, 0x01}, // io_pad_sel + {0x3008, 0x80}, // io_pad_sel + + // FSIN first frame + /* + {0x3009, 0x2}, + {0x3015, 0x2}, + {0x3822, 0x20}, + {0x3823, 0x58}, + + {0x3826, 0x0}, {0x3827, 0x8}, + {0x3881, 0x4}, + + {0x3882, 0x8}, {0x3883, 0x0D}, + {0x3836, 0x1F}, {0x3837, 0x40}, + */ + + // FSIN with external pulses + {0x3009, 0x2}, + {0x3015, 0x2}, + {0x383E, 0x80}, + {0x3881, 0x4}, + {0x3882, 0x8}, {0x3883, 0x0D}, + {0x3836, 0x1F}, {0x3837, 0x40}, + + {0x3012, 0x41}, // SC_PHY_CTRL = 4 lane MIPI + {0x3020, 0x05}, // SC_CTRL_20 + + // this is not in the datasheet, listed as RSVD + // but the camera doesn't work without it + {0x3700, 0x28}, {0x3701, 0x15}, {0x3702, 0x19}, {0x3703, 0x23}, + {0x3704, 0x0a}, {0x3705, 0x00}, {0x3706, 0x3e}, {0x3707, 0x0d}, + {0x3708, 0x50}, {0x3709, 0x5a}, {0x370a, 0x00}, {0x370b, 0x96}, + {0x3711, 0x11}, {0x3712, 0x13}, {0x3717, 0x02}, {0x3718, 0x73}, + {0x372c, 0x40}, {0x3733, 0x01}, {0x3738, 0x36}, {0x3739, 0x36}, + {0x373a, 0x25}, {0x373b, 0x25}, {0x373f, 0x21}, {0x3740, 0x21}, + {0x3741, 0x21}, {0x3742, 0x21}, {0x3747, 0x28}, {0x3748, 0x28}, + {0x3749, 0x19}, {0x3755, 0x1a}, {0x3756, 0x0a}, {0x3757, 0x1c}, + {0x3765, 0x19}, {0x3766, 0x05}, {0x3767, 0x05}, {0x3768, 0x13}, + {0x376c, 0x07}, {0x3778, 0x20}, {0x377c, 0xc8}, {0x3781, 0x02}, + {0x3783, 0x02}, {0x379c, 0x58}, {0x379e, 0x00}, {0x379f, 0x00}, + {0x37a0, 0x00}, {0x37bc, 0x22}, {0x37c0, 0x01}, {0x37c4, 0x3e}, + {0x37c5, 0x3e}, {0x37c6, 0x2a}, {0x37c7, 0x28}, {0x37c8, 0x02}, + {0x37c9, 0x12}, {0x37cb, 0x29}, {0x37cd, 0x29}, {0x37d2, 0x00}, + {0x37d3, 0x73}, {0x37d6, 0x00}, {0x37d7, 0x6b}, {0x37dc, 0x00}, + {0x37df, 0x54}, {0x37e2, 0x00}, {0x37e3, 0x00}, {0x37f8, 0x00}, + {0x37f9, 0x01}, {0x37fa, 0x00}, {0x37fb, 0x19}, + + // also RSVD + {0x3c03, 0x01}, {0x3c04, 0x01}, {0x3c06, 0x21}, {0x3c08, 0x01}, + {0x3c09, 0x01}, {0x3c0a, 0x01}, {0x3c0b, 0x21}, {0x3c13, 0x21}, + {0x3c14, 0x82}, {0x3c16, 0x13}, {0x3c21, 0x00}, {0x3c22, 0xf3}, + {0x3c37, 0x12}, {0x3c38, 0x31}, {0x3c3c, 0x00}, {0x3c3d, 0x03}, + {0x3c44, 0x16}, {0x3c5c, 0x8a}, {0x3c5f, 0x03}, {0x3c61, 0x80}, + {0x3c6f, 0x2b}, {0x3c70, 0x5f}, {0x3c71, 0x2c}, {0x3c72, 0x2c}, + {0x3c73, 0x2c}, {0x3c76, 0x12}, + + // PEC checks + {0x3182, 0x12}, + + {0x320e, 0x00}, {0x320f, 0x00}, // RSVD + {0x3211, 0x61}, + {0x3215, 0xcd}, + {0x3219, 0x08}, + + {0x3506, 0x20}, {0x3507, 0x00}, // hcg fine exposure + {0x350a, 0x04}, {0x350b, 0x00}, {0x350c, 0x00}, // hcg digital gain + + {0x3586, 0x40}, {0x3587, 0x00}, // lcg fine exposure + {0x358a, 0x04}, {0x358b, 0x00}, {0x358c, 0x00}, // lcg digital gain + + {0x3546, 0x20}, {0x3547, 0x00}, // spd fine exposure + {0x354a, 0x04}, {0x354b, 0x00}, {0x354c, 0x00}, // spd digital gain + + {0x35c6, 0xb0}, {0x35c7, 0x00}, // vs fine exposure + {0x35ca, 0x04}, {0x35cb, 0x00}, {0x35cc, 0x00}, // vs digital gain + + // also RSVD + {0x3600, 0x8f}, {0x3605, 0x16}, {0x3609, 0xf0}, {0x360a, 0x01}, + {0x360e, 0x1d}, {0x360f, 0x10}, {0x3610, 0x70}, {0x3611, 0x3a}, + {0x3612, 0x28}, {0x361a, 0x29}, {0x361b, 0x6c}, {0x361c, 0x0b}, + {0x361d, 0x00}, {0x361e, 0xfc}, {0x362a, 0x00}, {0x364d, 0x0f}, + {0x364e, 0x18}, {0x364f, 0x12}, {0x3653, 0x1c}, {0x3654, 0x00}, + {0x3655, 0x1f}, {0x3656, 0x1f}, {0x3657, 0x0c}, {0x3658, 0x0a}, + {0x3659, 0x14}, {0x365a, 0x18}, {0x365b, 0x14}, {0x365c, 0x10}, + {0x365e, 0x12}, {0x3674, 0x08}, {0x3677, 0x3a}, {0x3678, 0x3a}, + {0x3679, 0x19}, + + // Y_ADDR_START = 4 + {0x3802, 0x00}, {0x3803, 0x04}, + // Y_ADDR_END = 0x50b + {0x3806, 0x05}, {0x3807, 0x0b}, + + // X_OUTPUT_SIZE = 0x780 = 1920 (changed to 1928) + {0x3808, 0x07}, {0x3809, 0x88}, + + // Y_OUTPUT_SIZE = 0x500 = 1280 (changed to 1208) + {0x380a, 0x04}, {0x380b, 0xb8}, + + // horizontal timing 0x447 + {0x380c, 0x04}, {0x380d, 0x47}, + + // rows per frame (was 0x2ae) + // 0x8ae = 53.65 ms + {0x380e, 0x08}, {0x380f, 0x15}, + // this should be triggered by FSIN, not free running + + {0x3810, 0x00}, {0x3811, 0x08}, // x cutoff + {0x3812, 0x00}, {0x3813, 0x04}, // y cutoff + {0x3816, 0x01}, + {0x3817, 0x01}, + {0x381c, 0x18}, + {0x381e, 0x01}, + {0x381f, 0x01}, + + // don't mirror, just flip + {0x3820, 0x04}, + + {0x3821, 0x19}, + {0x3832, 0x00}, + {0x3834, 0x00}, + {0x384c, 0x02}, + {0x384d, 0x0d}, + {0x3850, 0x00}, + {0x3851, 0x42}, + {0x3852, 0x00}, + {0x3853, 0x40}, + {0x3858, 0x04}, + {0x388c, 0x02}, + {0x388d, 0x2b}, + + // APC + {0x3b40, 0x05}, {0x3b41, 0x40}, {0x3b42, 0x00}, {0x3b43, 0x90}, + {0x3b44, 0x00}, {0x3b45, 0x20}, {0x3b46, 0x00}, {0x3b47, 0x20}, + {0x3b48, 0x19}, {0x3b49, 0x12}, {0x3b4a, 0x16}, {0x3b4b, 0x2e}, + {0x3b4c, 0x00}, {0x3b4d, 0x00}, + {0x3b86, 0x00}, {0x3b87, 0x34}, {0x3b88, 0x00}, {0x3b89, 0x08}, + {0x3b8a, 0x05}, {0x3b8b, 0x00}, {0x3b8c, 0x07}, {0x3b8d, 0x80}, + {0x3b8e, 0x00}, {0x3b8f, 0x00}, {0x3b92, 0x05}, {0x3b93, 0x00}, + {0x3b94, 0x07}, {0x3b95, 0x80}, {0x3b9e, 0x09}, + + // OTP + {0x3d82, 0x73}, + {0x3d85, 0x05}, + {0x3d8a, 0x03}, + {0x3d8b, 0xff}, + {0x3d99, 0x00}, + {0x3d9a, 0x9f}, + {0x3d9b, 0x00}, + {0x3d9c, 0xa0}, + {0x3da4, 0x00}, + {0x3da7, 0x50}, + + // DTR + {0x420e, 0x6b}, + {0x420f, 0x6e}, + {0x4210, 0x06}, + {0x4211, 0xc1}, + {0x421e, 0x02}, + {0x421f, 0x45}, + {0x4220, 0xe1}, + {0x4221, 0x01}, + {0x4301, 0xff}, + {0x4307, 0x03}, + {0x4308, 0x13}, + {0x430a, 0x13}, + {0x430d, 0x93}, + {0x430f, 0x57}, + {0x4310, 0x95}, + {0x4311, 0x16}, + {0x4316, 0x00}, + + {0x4317, 0x38}, // both embedded rows are enabled + + {0x4319, 0x03}, // spd dcg + {0x431a, 0x00}, // 8 bit mipi + {0x431b, 0x00}, + {0x431d, 0x2a}, + {0x431e, 0x11}, + + {0x431f, 0x20}, // enable PWL (pwl0_en), 12 bits + //{0x431f, 0x00}, // disable PWL + + {0x4320, 0x19}, + {0x4323, 0x80}, + {0x4324, 0x00}, + {0x4503, 0x4e}, + {0x4505, 0x00}, + {0x4509, 0x00}, + {0x450a, 0x00}, + {0x4580, 0xf8}, + {0x4583, 0x07}, + {0x4584, 0x6a}, + {0x4585, 0x08}, + {0x4586, 0x05}, + {0x4587, 0x04}, + {0x4588, 0x73}, + {0x4589, 0x05}, + {0x458a, 0x1f}, + {0x458b, 0x02}, + {0x458c, 0xdc}, + {0x458d, 0x03}, + {0x458e, 0x02}, + {0x4597, 0x07}, + {0x4598, 0x40}, + {0x4599, 0x0e}, + {0x459a, 0x0e}, + {0x459b, 0xfb}, + {0x459c, 0xf3}, + {0x4602, 0x00}, + {0x4603, 0x13}, + {0x4604, 0x00}, + {0x4609, 0x0a}, + {0x460a, 0x30}, + {0x4610, 0x00}, + {0x4611, 0x70}, + {0x4612, 0x01}, + {0x4613, 0x00}, + {0x4614, 0x00}, + {0x4615, 0x70}, + {0x4616, 0x01}, + {0x4617, 0x00}, + + {0x4800, 0x04}, // invert output PCLK + {0x480a, 0x22}, + {0x4813, 0xe4}, + + // mipi + {0x4814, 0x2a}, + {0x4837, 0x0d}, + {0x484b, 0x47}, + {0x484f, 0x00}, + {0x4887, 0x51}, + {0x4d00, 0x4a}, + {0x4d01, 0x18}, + {0x4d05, 0xff}, + {0x4d06, 0x88}, + {0x4d08, 0x63}, + {0x4d09, 0xdf}, + {0x4d15, 0x7d}, + {0x4d1a, 0x20}, + {0x4d30, 0x0a}, + {0x4d31, 0x00}, + {0x4d34, 0x7d}, + {0x4d3c, 0x7d}, + {0x4f00, 0x00}, + {0x4f01, 0x00}, + {0x4f02, 0x00}, + {0x4f03, 0x20}, + {0x4f04, 0xe0}, + {0x6a00, 0x00}, + {0x6a01, 0x20}, + {0x6a02, 0x00}, + {0x6a03, 0x20}, + {0x6a04, 0x02}, + {0x6a05, 0x80}, + {0x6a06, 0x01}, + {0x6a07, 0xe0}, + {0x6a08, 0xcf}, + {0x6a09, 0x01}, + {0x6a0a, 0x40}, + {0x6a20, 0x00}, + {0x6a21, 0x02}, + {0x6a22, 0x00}, + {0x6a23, 0x00}, + {0x6a24, 0x00}, + {0x6a25, 0x00}, + {0x6a26, 0x00}, + {0x6a27, 0x00}, + {0x6a28, 0x00}, + + // isp + {0x5000, 0x8f}, + {0x5001, 0x75}, + {0x5002, 0x7f}, // PWL0 + //{0x5002, 0x3f}, // PWL disable + {0x5003, 0x7a}, + + {0x5004, 0x3e}, + {0x5005, 0x1e}, + {0x5006, 0x1e}, + {0x5007, 0x1e}, + + {0x5008, 0x00}, + {0x500c, 0x00}, + {0x502c, 0x00}, + {0x502e, 0x00}, + {0x502f, 0x00}, + {0x504b, 0x00}, + {0x5053, 0x00}, + {0x505b, 0x00}, + {0x5063, 0x00}, + {0x5070, 0x00}, + {0x5074, 0x04}, + {0x507a, 0x04}, + {0x507b, 0x09}, + {0x5500, 0x02}, + {0x5700, 0x02}, + {0x5900, 0x02}, + {0x6007, 0x04}, + {0x6008, 0x05}, + {0x6009, 0x02}, + {0x600b, 0x08}, + {0x600c, 0x07}, + {0x600d, 0x88}, + {0x6016, 0x00}, + {0x6027, 0x04}, + {0x6028, 0x05}, + {0x6029, 0x02}, + {0x602b, 0x08}, + {0x602c, 0x07}, + {0x602d, 0x88}, + {0x6047, 0x04}, + {0x6048, 0x05}, + {0x6049, 0x02}, + {0x604b, 0x08}, + {0x604c, 0x07}, + {0x604d, 0x88}, + {0x6067, 0x04}, + {0x6068, 0x05}, + {0x6069, 0x02}, + {0x606b, 0x08}, + {0x606c, 0x07}, + {0x606d, 0x88}, + {0x6087, 0x04}, + {0x6088, 0x05}, + {0x6089, 0x02}, + {0x608b, 0x08}, + {0x608c, 0x07}, + {0x608d, 0x88}, + + // 12-bit PWL0 + {0x5e00, 0x00}, + + // m_ndX_exp[0:32] + // 9*2+0xa*3+0xb*2+0xc*2+0xd*2+0xe*2+0xf*2+0x10*2+0x11*2+0x12*4+0x13*3+0x14*3+0x15*3+0x16 = 518 + {0x5e01, 0x09}, + {0x5e02, 0x09}, + {0x5e03, 0x0a}, + {0x5e04, 0x0a}, + {0x5e05, 0x0a}, + {0x5e06, 0x0b}, + {0x5e07, 0x0b}, + {0x5e08, 0x0c}, + {0x5e09, 0x0c}, + {0x5e0a, 0x0d}, + {0x5e0b, 0x0d}, + {0x5e0c, 0x0e}, + {0x5e0d, 0x0e}, + {0x5e0e, 0x0f}, + {0x5e0f, 0x0f}, + {0x5e10, 0x10}, + {0x5e11, 0x10}, + {0x5e12, 0x11}, + {0x5e13, 0x11}, + {0x5e14, 0x12}, + {0x5e15, 0x12}, + {0x5e16, 0x12}, + {0x5e17, 0x12}, + {0x5e18, 0x13}, + {0x5e19, 0x13}, + {0x5e1a, 0x13}, + {0x5e1b, 0x14}, + {0x5e1c, 0x14}, + {0x5e1d, 0x14}, + {0x5e1e, 0x15}, + {0x5e1f, 0x15}, + {0x5e20, 0x15}, + {0x5e21, 0x16}, + + // m_ndY_val[0:32] + // 0x200+0xff+0x100*3+0x80*12+0x40*16 = 4095 + {0x5e22, 0x00}, {0x5e23, 0x02}, {0x5e24, 0x00}, + {0x5e25, 0x00}, {0x5e26, 0x00}, {0x5e27, 0xff}, + {0x5e28, 0x00}, {0x5e29, 0x01}, {0x5e2a, 0x00}, + {0x5e2b, 0x00}, {0x5e2c, 0x01}, {0x5e2d, 0x00}, + {0x5e2e, 0x00}, {0x5e2f, 0x01}, {0x5e30, 0x00}, + {0x5e31, 0x00}, {0x5e32, 0x00}, {0x5e33, 0x80}, + {0x5e34, 0x00}, {0x5e35, 0x00}, {0x5e36, 0x80}, + {0x5e37, 0x00}, {0x5e38, 0x00}, {0x5e39, 0x80}, + {0x5e3a, 0x00}, {0x5e3b, 0x00}, {0x5e3c, 0x80}, + {0x5e3d, 0x00}, {0x5e3e, 0x00}, {0x5e3f, 0x80}, + {0x5e40, 0x00}, {0x5e41, 0x00}, {0x5e42, 0x80}, + {0x5e43, 0x00}, {0x5e44, 0x00}, {0x5e45, 0x80}, + {0x5e46, 0x00}, {0x5e47, 0x00}, {0x5e48, 0x80}, + {0x5e49, 0x00}, {0x5e4a, 0x00}, {0x5e4b, 0x80}, + {0x5e4c, 0x00}, {0x5e4d, 0x00}, {0x5e4e, 0x80}, + {0x5e4f, 0x00}, {0x5e50, 0x00}, {0x5e51, 0x80}, + {0x5e52, 0x00}, {0x5e53, 0x00}, {0x5e54, 0x80}, + {0x5e55, 0x00}, {0x5e56, 0x00}, {0x5e57, 0x40}, + {0x5e58, 0x00}, {0x5e59, 0x00}, {0x5e5a, 0x40}, + {0x5e5b, 0x00}, {0x5e5c, 0x00}, {0x5e5d, 0x40}, + {0x5e5e, 0x00}, {0x5e5f, 0x00}, {0x5e60, 0x40}, + {0x5e61, 0x00}, {0x5e62, 0x00}, {0x5e63, 0x40}, + {0x5e64, 0x00}, {0x5e65, 0x00}, {0x5e66, 0x40}, + {0x5e67, 0x00}, {0x5e68, 0x00}, {0x5e69, 0x40}, + {0x5e6a, 0x00}, {0x5e6b, 0x00}, {0x5e6c, 0x40}, + {0x5e6d, 0x00}, {0x5e6e, 0x00}, {0x5e6f, 0x40}, + {0x5e70, 0x00}, {0x5e71, 0x00}, {0x5e72, 0x40}, + {0x5e73, 0x00}, {0x5e74, 0x00}, {0x5e75, 0x40}, + {0x5e76, 0x00}, {0x5e77, 0x00}, {0x5e78, 0x40}, + {0x5e79, 0x00}, {0x5e7a, 0x00}, {0x5e7b, 0x40}, + {0x5e7c, 0x00}, {0x5e7d, 0x00}, {0x5e7e, 0x40}, + {0x5e7f, 0x00}, {0x5e80, 0x00}, {0x5e81, 0x40}, + {0x5e82, 0x00}, {0x5e83, 0x00}, {0x5e84, 0x40}, + + // disable PWL + /*{0x5e01, 0x18}, {0x5e02, 0x00}, {0x5e03, 0x00}, {0x5e04, 0x00}, + {0x5e05, 0x00}, {0x5e06, 0x00}, {0x5e07, 0x00}, {0x5e08, 0x00}, + {0x5e09, 0x00}, {0x5e0a, 0x00}, {0x5e0b, 0x00}, {0x5e0c, 0x00}, + {0x5e0d, 0x00}, {0x5e0e, 0x00}, {0x5e0f, 0x00}, {0x5e10, 0x00}, + {0x5e11, 0x00}, {0x5e12, 0x00}, {0x5e13, 0x00}, {0x5e14, 0x00}, + {0x5e15, 0x00}, {0x5e16, 0x00}, {0x5e17, 0x00}, {0x5e18, 0x00}, + {0x5e19, 0x00}, {0x5e1a, 0x00}, {0x5e1b, 0x00}, {0x5e1c, 0x00}, + {0x5e1d, 0x00}, {0x5e1e, 0x00}, {0x5e1f, 0x00}, {0x5e20, 0x00}, + {0x5e21, 0x00}, + + {0x5e22, 0x00}, {0x5e23, 0x0f}, {0x5e24, 0xFF},*/ + + {0x4001, 0x2b}, // BLC_CTRL_1 + {0x4008, 0x02}, {0x4009, 0x03}, + {0x4018, 0x12}, + {0x4022, 0x40}, + {0x4023, 0x20}, + + // all black level targets are 0x40 + {0x4026, 0x00}, {0x4027, 0x40}, + {0x4028, 0x00}, {0x4029, 0x40}, + {0x402a, 0x00}, {0x402b, 0x40}, + {0x402c, 0x00}, {0x402d, 0x40}, + + {0x407e, 0xcc}, + {0x407f, 0x18}, + {0x4080, 0xff}, + {0x4081, 0xff}, + {0x4082, 0x01}, + {0x4083, 0x53}, + {0x4084, 0x01}, + {0x4085, 0x2b}, + {0x4086, 0x00}, + {0x4087, 0xb3}, + + {0x4640, 0x40}, + {0x4641, 0x11}, + {0x4642, 0x0e}, + {0x4643, 0xee}, + {0x4646, 0x0f}, + {0x4648, 0x00}, + {0x4649, 0x03}, + + {0x4f00, 0x00}, + {0x4f01, 0x00}, + {0x4f02, 0x80}, + {0x4f03, 0x2c}, + {0x4f04, 0xf8}, + + {0x4d09, 0xff}, + {0x4d09, 0xdf}, + + {0x5003, 0x7a}, + {0x5b80, 0x08}, + {0x5c00, 0x08}, + {0x5c80, 0x00}, + {0x5bbe, 0x12}, + {0x5c3e, 0x12}, + {0x5cbe, 0x12}, + {0x5b8a, 0x80}, + {0x5b8b, 0x80}, + {0x5b8c, 0x80}, + {0x5b8d, 0x80}, + {0x5b8e, 0x60}, + {0x5b8f, 0x80}, + {0x5b90, 0x80}, + {0x5b91, 0x80}, + {0x5b92, 0x80}, + {0x5b93, 0x20}, + {0x5b94, 0x80}, + {0x5b95, 0x80}, + {0x5b96, 0x80}, + {0x5b97, 0x20}, + {0x5b98, 0x00}, + {0x5b99, 0x80}, + {0x5b9a, 0x40}, + {0x5b9b, 0x20}, + {0x5b9c, 0x00}, + {0x5b9d, 0x00}, + {0x5b9e, 0x80}, + {0x5b9f, 0x00}, + {0x5ba0, 0x00}, + {0x5ba1, 0x00}, + {0x5ba2, 0x00}, + {0x5ba3, 0x00}, + {0x5ba4, 0x00}, + {0x5ba5, 0x00}, + {0x5ba6, 0x00}, + {0x5ba7, 0x00}, + {0x5ba8, 0x02}, + {0x5ba9, 0x00}, + {0x5baa, 0x02}, + {0x5bab, 0x76}, + {0x5bac, 0x03}, + {0x5bad, 0x08}, + {0x5bae, 0x00}, + {0x5baf, 0x80}, + {0x5bb0, 0x00}, + {0x5bb1, 0xc0}, + {0x5bb2, 0x01}, + {0x5bb3, 0x00}, + + // m_nNormCombineWeight + {0x5c0a, 0x80}, {0x5c0b, 0x80}, {0x5c0c, 0x80}, {0x5c0d, 0x80}, {0x5c0e, 0x60}, + {0x5c0f, 0x80}, {0x5c10, 0x80}, {0x5c11, 0x80}, {0x5c12, 0x60}, {0x5c13, 0x20}, + {0x5c14, 0x80}, {0x5c15, 0x80}, {0x5c16, 0x80}, {0x5c17, 0x20}, {0x5c18, 0x00}, + {0x5c19, 0x80}, {0x5c1a, 0x40}, {0x5c1b, 0x20}, {0x5c1c, 0x00}, {0x5c1d, 0x00}, + {0x5c1e, 0x80}, {0x5c1f, 0x00}, {0x5c20, 0x00}, {0x5c21, 0x00}, {0x5c22, 0x00}, + {0x5c23, 0x00}, {0x5c24, 0x00}, {0x5c25, 0x00}, {0x5c26, 0x00}, {0x5c27, 0x00}, + + // m_nCombinThreL + {0x5c28, 0x02}, {0x5c29, 0x00}, + {0x5c2a, 0x02}, {0x5c2b, 0x76}, + {0x5c2c, 0x03}, {0x5c2d, 0x08}, + + // m_nCombinThreS + {0x5c2e, 0x00}, {0x5c2f, 0x80}, + {0x5c30, 0x00}, {0x5c31, 0xc0}, + {0x5c32, 0x01}, {0x5c33, 0x00}, + + // m_nNormCombineWeight + {0x5c8a, 0x80}, {0x5c8b, 0x80}, {0x5c8c, 0x80}, {0x5c8d, 0x80}, {0x5c8e, 0x80}, + {0x5c8f, 0x80}, {0x5c90, 0x80}, {0x5c91, 0x80}, {0x5c92, 0x80}, {0x5c93, 0x60}, + {0x5c94, 0x80}, {0x5c95, 0x80}, {0x5c96, 0x80}, {0x5c97, 0x60}, {0x5c98, 0x40}, + {0x5c99, 0x80}, {0x5c9a, 0x80}, {0x5c9b, 0x80}, {0x5c9c, 0x40}, {0x5c9d, 0x00}, + {0x5c9e, 0x80}, {0x5c9f, 0x80}, {0x5ca0, 0x80}, {0x5ca1, 0x20}, {0x5ca2, 0x00}, + {0x5ca3, 0x80}, {0x5ca4, 0x80}, {0x5ca5, 0x00}, {0x5ca6, 0x00}, {0x5ca7, 0x00}, + + {0x5ca8, 0x01}, {0x5ca9, 0x00}, + {0x5caa, 0x02}, {0x5cab, 0x00}, + {0x5cac, 0x03}, {0x5cad, 0x08}, + + {0x5cae, 0x01}, {0x5caf, 0x00}, + {0x5cb0, 0x02}, {0x5cb1, 0x00}, + {0x5cb2, 0x03}, {0x5cb3, 0x08}, + + // combine ISP + {0x5be7, 0x80}, + {0x5bc9, 0x80}, + {0x5bca, 0x80}, + {0x5bcb, 0x80}, + {0x5bcc, 0x80}, + {0x5bcd, 0x80}, + {0x5bce, 0x80}, + {0x5bcf, 0x80}, + {0x5bd0, 0x80}, + {0x5bd1, 0x80}, + {0x5bd2, 0x20}, + {0x5bd3, 0x80}, + {0x5bd4, 0x40}, + {0x5bd5, 0x20}, + {0x5bd6, 0x00}, + {0x5bd7, 0x00}, + {0x5bd8, 0x00}, + {0x5bd9, 0x00}, + {0x5bda, 0x00}, + {0x5bdb, 0x00}, + {0x5bdc, 0x00}, + {0x5bdd, 0x00}, + {0x5bde, 0x00}, + {0x5bdf, 0x00}, + {0x5be0, 0x00}, + {0x5be1, 0x00}, + {0x5be2, 0x00}, + {0x5be3, 0x00}, + {0x5be4, 0x00}, + {0x5be5, 0x00}, + {0x5be6, 0x00}, + + // m_nSPDCombineWeight + {0x5c49, 0x80}, {0x5c4a, 0x80}, {0x5c4b, 0x80}, {0x5c4c, 0x80}, {0x5c4d, 0x40}, + {0x5c4e, 0x80}, {0x5c4f, 0x80}, {0x5c50, 0x80}, {0x5c51, 0x60}, {0x5c52, 0x20}, + {0x5c53, 0x80}, {0x5c54, 0x80}, {0x5c55, 0x80}, {0x5c56, 0x20}, {0x5c57, 0x00}, + {0x5c58, 0x80}, {0x5c59, 0x40}, {0x5c5a, 0x20}, {0x5c5b, 0x00}, {0x5c5c, 0x00}, + {0x5c5d, 0x80}, {0x5c5e, 0x00}, {0x5c5f, 0x00}, {0x5c60, 0x00}, {0x5c61, 0x00}, + {0x5c62, 0x00}, {0x5c63, 0x00}, {0x5c64, 0x00}, {0x5c65, 0x00}, {0x5c66, 0x00}, + + // m_nSPDCombineWeight + {0x5cc9, 0x80}, {0x5cca, 0x80}, {0x5ccb, 0x80}, {0x5ccc, 0x80}, {0x5ccd, 0x80}, + {0x5cce, 0x80}, {0x5ccf, 0x80}, {0x5cd0, 0x80}, {0x5cd1, 0x80}, {0x5cd2, 0x60}, + {0x5cd3, 0x80}, {0x5cd4, 0x80}, {0x5cd5, 0x80}, {0x5cd6, 0x60}, {0x5cd7, 0x40}, + {0x5cd8, 0x80}, {0x5cd9, 0x80}, {0x5cda, 0x80}, {0x5cdb, 0x40}, {0x5cdc, 0x20}, + {0x5cdd, 0x80}, {0x5cde, 0x80}, {0x5cdf, 0x80}, {0x5ce0, 0x20}, {0x5ce1, 0x00}, + {0x5ce2, 0x80}, {0x5ce3, 0x80}, {0x5ce4, 0x80}, {0x5ce5, 0x00}, {0x5ce6, 0x00}, + + {0x5d74, 0x01}, + {0x5d75, 0x00}, + + {0x5d1f, 0x81}, + {0x5d11, 0x00}, + {0x5d12, 0x10}, + {0x5d13, 0x10}, + {0x5d15, 0x05}, + {0x5d16, 0x05}, + {0x5d17, 0x05}, + {0x5d08, 0x03}, + {0x5d09, 0xb6}, + {0x5d0a, 0x03}, + {0x5d0b, 0xb6}, + {0x5d18, 0x03}, + {0x5d19, 0xb6}, + {0x5d62, 0x01}, + {0x5d40, 0x02}, + {0x5d41, 0x01}, + {0x5d63, 0x1f}, + {0x5d64, 0x00}, + {0x5d65, 0x80}, + {0x5d56, 0x00}, + {0x5d57, 0x20}, + {0x5d58, 0x00}, + {0x5d59, 0x20}, + {0x5d5a, 0x00}, + {0x5d5b, 0x0c}, + {0x5d5c, 0x02}, + {0x5d5d, 0x40}, + {0x5d5e, 0x02}, + {0x5d5f, 0x40}, + {0x5d60, 0x03}, + {0x5d61, 0x40}, + {0x5d4a, 0x02}, + {0x5d4b, 0x40}, + {0x5d4c, 0x02}, + {0x5d4d, 0x40}, + {0x5d4e, 0x02}, + {0x5d4f, 0x40}, + {0x5d50, 0x18}, + {0x5d51, 0x80}, + {0x5d52, 0x18}, + {0x5d53, 0x80}, + {0x5d54, 0x18}, + {0x5d55, 0x80}, + {0x5d46, 0x20}, + {0x5d47, 0x00}, + {0x5d48, 0x22}, + {0x5d49, 0x00}, + {0x5d42, 0x20}, + {0x5d43, 0x00}, + {0x5d44, 0x22}, + {0x5d45, 0x00}, + + {0x5004, 0x1e}, + {0x4221, 0x03}, // this is changed from 1 -> 3 + + // DCG exposure coarse + {0x3501, 0x01}, {0x3502, 0xc8}, + // SPD exposure coarse + {0x3541, 0x01}, {0x3542, 0xc8}, + // VS exposure coarse + {0x35c1, 0x00}, {0x35c2, 0x01}, + + // crc reference + {0x420e, 0x66}, {0x420f, 0x5d}, {0x4210, 0xa8}, {0x4211, 0x55}, + // crc stat check + {0x507a, 0x5f}, {0x507b, 0x46}, + + // watchdog control + {0x4f00, 0x00}, {0x4f01, 0x01}, {0x4f02, 0x80}, {0x4f04, 0x2c}, + + // color balance gains + // blue + {0x5280, 0x06}, {0x5281, 0x4A}, // hcg + {0x5480, 0x06}, {0x5481, 0x4A}, // lcg + {0x5680, 0x07}, {0x5681, 0xDD}, // spd + {0x5880, 0x06}, {0x5881, 0x4A}, // vs + + // green(blue) + {0x5282, 0x04}, {0x5283, 0x00}, + {0x5482, 0x04}, {0x5483, 0x00}, + {0x5682, 0x04}, {0x5683, 0x00}, + {0x5882, 0x04}, {0x5883, 0x00}, + + // green(red) + {0x5284, 0x04}, {0x5285, 0x00}, + {0x5484, 0x04}, {0x5485, 0x00}, + {0x5684, 0x04}, {0x5685, 0x00}, + {0x5884, 0x04}, {0x5885, 0x00}, + + // red + {0x5286, 0x08}, {0x5287, 0x6C}, + {0x5486, 0x08}, {0x5487, 0x6C}, + {0x5686, 0x08}, {0x5687, 0xAA}, + {0x5886, 0x08}, {0x5887, 0x6C}, }; struct i2c_random_wr_payload init_array_ar0231[] = { diff --git a/system/camerad/test/camera_test.h b/system/camerad/test/camera_test.h index a9f213c923..c173f9b84c 100644 --- a/system/camerad/test/camera_test.h +++ b/system/camerad/test/camera_test.h @@ -12,6 +12,8 @@ typedef struct CameraState { int fps; float digital_gain = 0; + int camera_id; + CameraBuf buf; } CameraState; From 1544734a540cf28d12df98038d7b9ecc48f7ffb9 Mon Sep 17 00:00:00 2001 From: Jeroen Date: Sat, 10 Sep 2022 21:02:27 +0200 Subject: [PATCH 066/152] CI: remove redundant env variables in 'openpilot env setup' (#25721) --- .github/workflows/setup/action.yaml | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/.github/workflows/setup/action.yaml b/.github/workflows/setup/action.yaml index 79ec921235..79c4c890ab 100644 --- a/.github/workflows/setup/action.yaml +++ b/.github/workflows/setup/action.yaml @@ -1,13 +1,5 @@ name: 'openpilot env setup' -env: - BASE_IMAGE: openpilot-base - DOCKER_REGISTRY: ghcr.io/commaai - BUILD: | - docker pull $(grep -iohP '(?<=^from)\s+\S+' Dockerfile.openpilot_base) || true - docker pull $DOCKER_REGISTRY/$BASE_IMAGE:latest || true - docker build --cache-from $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $BASE_IMAGE:latest -f Dockerfile.openpilot_base . - inputs: save-cache: default: false @@ -42,4 +34,4 @@ runs: # build our docker image - shell: bash - run: eval "$BUILD" + run: eval ${{ env.BUILD }} From 1c8aa8816189b464329e12187a81eef85893a724 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 11 Sep 2022 05:22:43 +0800 Subject: [PATCH 067/152] camera_qcom2: move util functions to separate files (#25720) --- release/files_tici | 2 + system/camerad/SConscript | 1 + system/camerad/cameras/camera_qcom2.cc | 127 ----------------------- system/camerad/cameras/camera_qcom2.h | 15 +-- system/camerad/cameras/camera_util.cc | 135 +++++++++++++++++++++++++ system/camerad/cameras/camera_util.h | 30 ++++++ 6 files changed, 169 insertions(+), 141 deletions(-) create mode 100644 system/camerad/cameras/camera_util.cc create mode 100644 system/camerad/cameras/camera_util.h diff --git a/release/files_tici b/release/files_tici index 8e3249cdfd..c8abd720d5 100644 --- a/release/files_tici +++ b/release/files_tici @@ -9,6 +9,8 @@ selfdrive/assets/training_wide/* system/camerad/cameras/camera_qcom2.cc system/camerad/cameras/camera_qcom2.h +system/camerad/cameras/camera_util.cc +system/camerad/cameras/camera_util.h system/camerad/cameras/real_debayer.cl selfdrive/sensord/rawgps/* diff --git a/system/camerad/SConscript b/system/camerad/SConscript index b03fbdc9a0..65f682dcce 100644 --- a/system/camerad/SConscript +++ b/system/camerad/SConscript @@ -10,6 +10,7 @@ if arch == "larch64": env.Program('camerad', [ 'main.cc', 'cameras/camera_common.cc', + 'cameras/camera_util.cc', 'imgproc/utils.cc', cameras, ], LIBS=libs) diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 3d0cc3a70f..2f674cb50c 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -103,133 +103,6 @@ const int EXPOSURE_TIME_MAX_OX03C10 = 2016; const uint32_t VS_TIME_MIN_OX03C10 = 1; const uint32_t VS_TIME_MAX_OX03C10 = 34; // vs < 35 -// ************** low level camera helpers **************** -int do_cam_control(int fd, int op_code, void *handle, int size) { - struct cam_control camcontrol = {0}; - camcontrol.op_code = op_code; - camcontrol.handle = (uint64_t)handle; - if (size == 0) { - camcontrol.size = 8; - camcontrol.handle_type = CAM_HANDLE_MEM_HANDLE; - } else { - camcontrol.size = size; - camcontrol.handle_type = CAM_HANDLE_USER_POINTER; - } - - int ret = HANDLE_EINTR(ioctl(fd, VIDIOC_CAM_CONTROL, &camcontrol)); - if (ret == -1) { - LOGE("VIDIOC_CAM_CONTROL error: op_code %d - errno %d", op_code, errno); - } - return ret; -} - -std::optional device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources=1) { - struct cam_acquire_dev_cmd cmd = { - .session_handle = session_handle, - .handle_type = CAM_HANDLE_USER_POINTER, - .num_resources = (uint32_t)(data ? num_resources : 0), - .resource_hdl = (uint64_t)data, - }; - int err = do_cam_control(fd, CAM_ACQUIRE_DEV, &cmd, sizeof(cmd)); - return err == 0 ? std::make_optional(cmd.dev_handle) : std::nullopt; -}; - -int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle) { - struct cam_config_dev_cmd cmd = { - .session_handle = session_handle, - .dev_handle = dev_handle, - .packet_handle = packet_handle, - }; - return do_cam_control(fd, CAM_CONFIG_DEV, &cmd, sizeof(cmd)); -} - -int device_control(int fd, int op_code, int session_handle, int dev_handle) { - // start stop and release are all the same - struct cam_start_stop_dev_cmd cmd { .session_handle = session_handle, .dev_handle = dev_handle }; - return do_cam_control(fd, op_code, &cmd, sizeof(cmd)); -} - -void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align = 8, int flags = CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, - int mmu_hdl = 0, int mmu_hdl2 = 0) { - struct cam_mem_mgr_alloc_cmd mem_mgr_alloc_cmd = {0}; - mem_mgr_alloc_cmd.len = len; - mem_mgr_alloc_cmd.align = align; - mem_mgr_alloc_cmd.flags = flags; - mem_mgr_alloc_cmd.num_hdl = 0; - if (mmu_hdl != 0) { - mem_mgr_alloc_cmd.mmu_hdls[0] = mmu_hdl; - mem_mgr_alloc_cmd.num_hdl++; - } - if (mmu_hdl2 != 0) { - mem_mgr_alloc_cmd.mmu_hdls[1] = mmu_hdl2; - mem_mgr_alloc_cmd.num_hdl++; - } - - do_cam_control(video0_fd, CAM_REQ_MGR_ALLOC_BUF, &mem_mgr_alloc_cmd, sizeof(mem_mgr_alloc_cmd)); - *handle = mem_mgr_alloc_cmd.out.buf_handle; - - void *ptr = NULL; - if (mem_mgr_alloc_cmd.out.fd > 0) { - ptr = mmap(NULL, len, PROT_READ | PROT_WRITE, MAP_SHARED, mem_mgr_alloc_cmd.out.fd, 0); - assert(ptr != MAP_FAILED); - } - - // LOGD("allocated: %x %d %llx mapped %p", mem_mgr_alloc_cmd.out.buf_handle, mem_mgr_alloc_cmd.out.fd, mem_mgr_alloc_cmd.out.vaddr, ptr); - - return ptr; -} - -void release(int video0_fd, uint32_t handle) { - int ret; - struct cam_mem_mgr_release_cmd mem_mgr_release_cmd = {0}; - mem_mgr_release_cmd.buf_handle = handle; - - ret = do_cam_control(video0_fd, CAM_REQ_MGR_RELEASE_BUF, &mem_mgr_release_cmd, sizeof(mem_mgr_release_cmd)); - assert(ret == 0); -} - -void release_fd(int video0_fd, uint32_t handle) { - // handle to fd - close(handle>>16); - release(video0_fd, handle); -} - -void *MemoryManager::alloc(int size, uint32_t *handle) { - lock.lock(); - void *ptr; - if (!cached_allocations[size].empty()) { - ptr = cached_allocations[size].front(); - cached_allocations[size].pop(); - *handle = handle_lookup[ptr]; - } else { - ptr = alloc_w_mmu_hdl(video0_fd, size, handle); - handle_lookup[ptr] = *handle; - size_lookup[ptr] = size; - } - lock.unlock(); - return ptr; -} - -void MemoryManager::free(void *ptr) { - lock.lock(); - cached_allocations[size_lookup[ptr]].push(ptr); - lock.unlock(); -} - -MemoryManager::~MemoryManager() { - for (auto& x : cached_allocations) { - while (!x.second.empty()) { - void *ptr = x.second.front(); - x.second.pop(); - LOGD("freeing cached allocation %p with size %d", ptr, size_lookup[ptr]); - munmap(ptr, size_lookup[ptr]); - release_fd(video0_fd, handle_lookup[ptr]); - handle_lookup.erase(ptr); - size_lookup.erase(ptr); - } - } -} - int CameraState::clear_req_queue() { struct cam_req_mgr_flush_info req_mgr_flush_request = {0}; req_mgr_flush_request.session_hdl = session_handle; diff --git a/system/camerad/cameras/camera_qcom2.h b/system/camerad/cameras/camera_qcom2.h index 470576a1ec..1b792e7e96 100644 --- a/system/camerad/cameras/camera_qcom2.h +++ b/system/camerad/cameras/camera_qcom2.h @@ -7,25 +7,12 @@ #include #include "system/camerad/cameras/camera_common.h" +#include "system/camerad/cameras/camera_util.h" #include "common/params.h" #include "common/util.h" #define FRAME_BUF_COUNT 4 -class MemoryManager { - public: - void init(int _video0_fd) { video0_fd = _video0_fd; } - void *alloc(int len, uint32_t *handle); - void free(void *ptr); - ~MemoryManager(); - private: - std::mutex lock; - std::map handle_lookup; - std::map size_lookup; - std::map > cached_allocations; - int video0_fd; -}; - class CameraState { public: MultiCameraState *multi_cam_state; diff --git a/system/camerad/cameras/camera_util.cc b/system/camerad/cameras/camera_util.cc new file mode 100644 index 0000000000..6d139590e4 --- /dev/null +++ b/system/camerad/cameras/camera_util.cc @@ -0,0 +1,135 @@ +#include "system/camerad/cameras/camera_util.h" + +#include + +#include +#include + +#include "common/swaglog.h" +#include "common/util.h" + +// ************** low level camera helpers **************** +int do_cam_control(int fd, int op_code, void *handle, int size) { + struct cam_control camcontrol = {0}; + camcontrol.op_code = op_code; + camcontrol.handle = (uint64_t)handle; + if (size == 0) { + camcontrol.size = 8; + camcontrol.handle_type = CAM_HANDLE_MEM_HANDLE; + } else { + camcontrol.size = size; + camcontrol.handle_type = CAM_HANDLE_USER_POINTER; + } + + int ret = HANDLE_EINTR(ioctl(fd, VIDIOC_CAM_CONTROL, &camcontrol)); + if (ret == -1) { + LOGE("VIDIOC_CAM_CONTROL error: op_code %d - errno %d", op_code, errno); + } + return ret; +} + +std::optional device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources) { + struct cam_acquire_dev_cmd cmd = { + .session_handle = session_handle, + .handle_type = CAM_HANDLE_USER_POINTER, + .num_resources = (uint32_t)(data ? num_resources : 0), + .resource_hdl = (uint64_t)data, + }; + int err = do_cam_control(fd, CAM_ACQUIRE_DEV, &cmd, sizeof(cmd)); + return err == 0 ? std::make_optional(cmd.dev_handle) : std::nullopt; +}; + +int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle) { + struct cam_config_dev_cmd cmd = { + .session_handle = session_handle, + .dev_handle = dev_handle, + .packet_handle = packet_handle, + }; + return do_cam_control(fd, CAM_CONFIG_DEV, &cmd, sizeof(cmd)); +} + +int device_control(int fd, int op_code, int session_handle, int dev_handle) { + // start stop and release are all the same + struct cam_start_stop_dev_cmd cmd { .session_handle = session_handle, .dev_handle = dev_handle }; + return do_cam_control(fd, op_code, &cmd, sizeof(cmd)); +} + +void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align, int flags, int mmu_hdl, int mmu_hdl2) { + struct cam_mem_mgr_alloc_cmd mem_mgr_alloc_cmd = {0}; + mem_mgr_alloc_cmd.len = len; + mem_mgr_alloc_cmd.align = align; + mem_mgr_alloc_cmd.flags = flags; + mem_mgr_alloc_cmd.num_hdl = 0; + if (mmu_hdl != 0) { + mem_mgr_alloc_cmd.mmu_hdls[0] = mmu_hdl; + mem_mgr_alloc_cmd.num_hdl++; + } + if (mmu_hdl2 != 0) { + mem_mgr_alloc_cmd.mmu_hdls[1] = mmu_hdl2; + mem_mgr_alloc_cmd.num_hdl++; + } + + do_cam_control(video0_fd, CAM_REQ_MGR_ALLOC_BUF, &mem_mgr_alloc_cmd, sizeof(mem_mgr_alloc_cmd)); + *handle = mem_mgr_alloc_cmd.out.buf_handle; + + void *ptr = NULL; + if (mem_mgr_alloc_cmd.out.fd > 0) { + ptr = mmap(NULL, len, PROT_READ | PROT_WRITE, MAP_SHARED, mem_mgr_alloc_cmd.out.fd, 0); + assert(ptr != MAP_FAILED); + } + + // LOGD("allocated: %x %d %llx mapped %p", mem_mgr_alloc_cmd.out.buf_handle, mem_mgr_alloc_cmd.out.fd, mem_mgr_alloc_cmd.out.vaddr, ptr); + + return ptr; +} + +void release(int video0_fd, uint32_t handle) { + int ret; + struct cam_mem_mgr_release_cmd mem_mgr_release_cmd = {0}; + mem_mgr_release_cmd.buf_handle = handle; + + ret = do_cam_control(video0_fd, CAM_REQ_MGR_RELEASE_BUF, &mem_mgr_release_cmd, sizeof(mem_mgr_release_cmd)); + assert(ret == 0); +} + +void release_fd(int video0_fd, uint32_t handle) { + // handle to fd + close(handle>>16); + release(video0_fd, handle); +} + +void *MemoryManager::alloc(int size, uint32_t *handle) { + lock.lock(); + void *ptr; + if (!cached_allocations[size].empty()) { + ptr = cached_allocations[size].front(); + cached_allocations[size].pop(); + *handle = handle_lookup[ptr]; + } else { + ptr = alloc_w_mmu_hdl(video0_fd, size, handle); + handle_lookup[ptr] = *handle; + size_lookup[ptr] = size; + } + lock.unlock(); + return ptr; +} + +void MemoryManager::free(void *ptr) { + lock.lock(); + cached_allocations[size_lookup[ptr]].push(ptr); + lock.unlock(); +} + +MemoryManager::~MemoryManager() { + for (auto& x : cached_allocations) { + while (!x.second.empty()) { + void *ptr = x.second.front(); + x.second.pop(); + LOGD("freeing cached allocation %p with size %d", ptr, size_lookup[ptr]); + munmap(ptr, size_lookup[ptr]); + release_fd(video0_fd, handle_lookup[ptr]); + handle_lookup.erase(ptr); + size_lookup.erase(ptr); + } + } +} diff --git a/system/camerad/cameras/camera_util.h b/system/camerad/cameras/camera_util.h new file mode 100644 index 0000000000..e408f6c0e2 --- /dev/null +++ b/system/camerad/cameras/camera_util.h @@ -0,0 +1,30 @@ +#pragma once + +#include +#include +#include +#include + +#include + +std::optional device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources=1); +int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle); +int device_control(int fd, int op_code, int session_handle, int dev_handle); +int do_cam_control(int fd, int op_code, void *handle, int size); +void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align = 8, int flags = CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, + int mmu_hdl = 0, int mmu_hdl2 = 0); +void release(int video0_fd, uint32_t handle); + +class MemoryManager { + public: + void init(int _video0_fd) { video0_fd = _video0_fd; } + void *alloc(int len, uint32_t *handle); + void free(void *ptr); + ~MemoryManager(); + private: + std::mutex lock; + std::map handle_lookup; + std::map size_lookup; + std::map > cached_allocations; + int video0_fd; +}; From 115eed9a54ae4f97bbdd0e561b9f796ca4214a9c Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 11 Sep 2022 05:39:57 +0800 Subject: [PATCH 068/152] cleanup map_helpers.cc (#25706) --- selfdrive/ui/qt/maps/map_helpers.cc | 46 +++++------------------------ 1 file changed, 8 insertions(+), 38 deletions(-) diff --git a/selfdrive/ui/qt/maps/map_helpers.cc b/selfdrive/ui/qt/maps/map_helpers.cc index ca81545f7f..8d5d4e1715 100644 --- a/selfdrive/ui/qt/maps/map_helpers.cc +++ b/selfdrive/ui/qt/maps/map_helpers.cc @@ -44,61 +44,31 @@ QMapbox::CoordinatesCollections model_to_collection( for (int i = 0; i < x.size(); i++) { Eigen::Vector3d point_ecef = ecef_from_local * Eigen::Vector3d(x[i], y[i], z[i]) + ecef; Geodetic point_geodetic = ecef2geodetic((ECEF){.x = point_ecef[0], .y = point_ecef[1], .z = point_ecef[2]}); - QMapbox::Coordinate coordinate(point_geodetic.lat, point_geodetic.lon); - coordinates.push_back(coordinate); + coordinates.push_back({point_geodetic.lat, point_geodetic.lon}); } - QMapbox::CoordinatesCollection collection; - collection.push_back(coordinates); - - QMapbox::CoordinatesCollections collections; - collections.push_back(collection); - return collections; + return {QMapbox::CoordinatesCollection{coordinates}}; } QMapbox::CoordinatesCollections coordinate_to_collection(const QMapbox::Coordinate &c) { - QMapbox::Coordinates coordinates; - coordinates.push_back(c); - - QMapbox::CoordinatesCollection collection; - collection.push_back(coordinates); - - QMapbox::CoordinatesCollections collections; - collections.push_back(collection); - return collections; + QMapbox::Coordinates coordinates{c}; + return {QMapbox::CoordinatesCollection{coordinates}}; } QMapbox::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List::Reader& coordinate_list) { QMapbox::Coordinates coordinates; - for (auto const &c: coordinate_list) { - QMapbox::Coordinate coordinate(c.getLatitude(), c.getLongitude()); - coordinates.push_back(coordinate); + coordinates.push_back({c.getLatitude(), c.getLongitude()}); } - - QMapbox::CoordinatesCollection collection; - collection.push_back(coordinates); - - QMapbox::CoordinatesCollections collections; - collections.push_back(collection); - return collections; - + return {QMapbox::CoordinatesCollection{coordinates}}; } QMapbox::CoordinatesCollections coordinate_list_to_collection(const QList &coordinate_list) { QMapbox::Coordinates coordinates; - for (auto &c : coordinate_list) { - QMapbox::Coordinate coordinate(c.latitude(), c.longitude()); - coordinates.push_back(coordinate); + coordinates.push_back({c.latitude(), c.longitude()}); } - - QMapbox::CoordinatesCollection collection; - collection.push_back(coordinates); - - QMapbox::CoordinatesCollections collections; - collections.push_back(collection); - return collections; + return {QMapbox::CoordinatesCollection{coordinates}}; } QList polyline_to_coordinate_list(const QString &polylineString) { From 21972605e7ed0f713d89324777afc2c60f862e6c Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Sat, 10 Sep 2022 18:04:15 -0500 Subject: [PATCH 069/152] VW: Increase stock ACC button spam reliability (#25692) * VW MQB: Fix/simplify stock ACC button spam * try this instead --- selfdrive/car/volkswagen/carcontroller.py | 13 +++++++------ selfdrive/car/volkswagen/mqbcan.py | 4 ++-- selfdrive/car/volkswagen/pqcan.py | 4 ++-- selfdrive/car/volkswagen/values.py | 1 - 4 files changed, 11 insertions(+), 11 deletions(-) diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py index f14c119892..5624c3dd5f 100644 --- a/selfdrive/car/volkswagen/carcontroller.py +++ b/selfdrive/car/volkswagen/carcontroller.py @@ -17,6 +17,7 @@ class CarController: self.packer_pt = CANPacker(dbc_name) self.apply_steer_last = 0 + self.gra_acc_counter_last = None self.frame = 0 self.hcaSameTorqueCount = 0 self.hcaEnabledFrameCount = 0 @@ -91,15 +92,15 @@ class CarController: # **** Stock ACC Button Controls **************************************** # - if self.CP.pcmCruise and self.frame % self.CCP.GRA_ACC_STEP == 0: - idx = (CS.gra_stock_values["COUNTER"] + 1) % 16 - if CC.cruiseControl.cancel: - can_sends.append(self.CCS.create_acc_buttons_control(self.packer_pt, ext_bus, CS.gra_stock_values, idx, cancel=True)) - elif CC.cruiseControl.resume: - can_sends.append(self.CCS.create_acc_buttons_control(self.packer_pt, ext_bus, CS.gra_stock_values, idx, resume=True)) + gra_send_ready = self.CP.pcmCruise and CS.gra_stock_values["COUNTER"] != self.gra_acc_counter_last + if gra_send_ready and (CC.cruiseControl.cancel or CC.cruiseControl.resume): + counter = (CS.gra_stock_values["COUNTER"] + 1) % 16 + can_sends.append(self.CCS.create_acc_buttons_control(self.packer_pt, ext_bus, CS.gra_stock_values, counter, + cancel=CC.cruiseControl.cancel, resume=CC.cruiseControl.resume)) new_actuators = actuators.copy() new_actuators.steer = self.apply_steer_last / self.CCP.STEER_MAX + self.gra_acc_counter_last = CS.gra_stock_values["COUNTER"] self.frame += 1 return new_actuators, can_sends diff --git a/selfdrive/car/volkswagen/mqbcan.py b/selfdrive/car/volkswagen/mqbcan.py index 1a4ca339ab..3819f4f76f 100644 --- a/selfdrive/car/volkswagen/mqbcan.py +++ b/selfdrive/car/volkswagen/mqbcan.py @@ -26,11 +26,11 @@ def create_lka_hud_control(packer, bus, ldw_stock_values, enabled, steering_pres return packer.make_can_msg("LDW_02", bus, values) -def create_acc_buttons_control(packer, bus, gra_stock_values, idx, cancel=False, resume=False): +def create_acc_buttons_control(packer, bus, gra_stock_values, counter, cancel=False, resume=False): values = gra_stock_values.copy() values.update({ - "COUNTER": idx, + "COUNTER": counter, "GRA_Abbrechen": cancel, "GRA_Tip_Wiederaufnahme": resume, }) diff --git a/selfdrive/car/volkswagen/pqcan.py b/selfdrive/car/volkswagen/pqcan.py index 1e7ed21342..e64bb2246e 100644 --- a/selfdrive/car/volkswagen/pqcan.py +++ b/selfdrive/car/volkswagen/pqcan.py @@ -23,11 +23,11 @@ def create_lka_hud_control(packer, bus, ldw_stock_values, enabled, steering_pres return packer.make_can_msg("LDW_Status", bus, values) -def create_acc_buttons_control(packer, bus, gra_stock_values, idx, cancel=False, resume=False): +def create_acc_buttons_control(packer, bus, gra_stock_values, counter, cancel=False, resume=False): values = gra_stock_values.copy() values.update({ - "COUNTER": idx, + "COUNTER": counter, "GRA_Abbrechen": cancel, "GRA_Recall": resume, }) diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index eaf6c042de..05994c0100 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -19,7 +19,6 @@ Button = namedtuple('Button', ['event_type', 'can_addr', 'can_msg', 'values']) class CarControllerParams: HCA_STEP = 2 # HCA_01/HCA_1 message frequency 50Hz - GRA_ACC_STEP = 3 # GRA_ACC_01/GRA_Neu message frequency 33Hz ACC_CONTROL_STEP = 2 # ACC_06/ACC_07/ACC_System frequency 50Hz ACC_HUD_STEP = 4 # ACC_GRA_Anziege frequency 25Hz From 2704e2cf4d805712695422b6c8e513ba7f479877 Mon Sep 17 00:00:00 2001 From: cydia2020 <12470297+cydia2020@users.noreply.github.com> Date: Sun, 11 Sep 2022 09:42:28 +1000 Subject: [PATCH 070/152] Toyota: longitudinal tune condition cleanup (#25676) * Toyota: clean up long tunes a bit * Update selfdrive/car/toyota/interface.py Co-authored-by: Adeeb Shihadeh --- selfdrive/car/toyota/interface.py | 7 +++---- selfdrive/car/toyota/tunes.py | 7 +++---- 2 files changed, 6 insertions(+), 8 deletions(-) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 8528005eb5..28912645ac 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -230,11 +230,10 @@ class CarInterface(CarInterfaceBase): # to a negative value, so it won't matter. ret.minEnableSpeed = -1. if (stop_and_go or ret.enableGasInterceptor) else MIN_ACC_SPEED - if ret.enableGasInterceptor: - set_long_tune(ret.longitudinalTuning, LongTunes.PEDAL) - elif candidate in TSS2_CAR: + if candidate in TSS2_CAR or ret.enableGasInterceptor: set_long_tune(ret.longitudinalTuning, LongTunes.TSS2) - ret.stoppingDecelRate = 0.3 # reach stopping target smoothly + if candidate in TSS2_CAR: + ret.stoppingDecelRate = 0.3 # reach stopping target smoothly else: set_long_tune(ret.longitudinalTuning, LongTunes.TSS) diff --git a/selfdrive/car/toyota/tunes.py b/selfdrive/car/toyota/tunes.py index fc538b9698..b73ab4c8c9 100644 --- a/selfdrive/car/toyota/tunes.py +++ b/selfdrive/car/toyota/tunes.py @@ -2,9 +2,8 @@ from enum import Enum class LongTunes(Enum): - PEDAL = 0 - TSS2 = 1 - TSS = 2 + TSS2 = 0 + TSS = 1 class LatTunes(Enum): INDI_PRIUS = 0 @@ -28,7 +27,7 @@ class LatTunes(Enum): ###### LONG ###### def set_long_tune(tune, name): # Improved longitudinal tune - if name == LongTunes.TSS2 or name == LongTunes.PEDAL: + if name == LongTunes.TSS2: tune.deadzoneBP = [0., 8.05] tune.deadzoneV = [.0, .14] tune.kpBP = [0., 5., 20.] From f6398ea7864779f621f84df65ded7ee083e72c09 Mon Sep 17 00:00:00 2001 From: ambientocclusion <1399123+ambientocclusion@users.noreply.github.com> Date: Sun, 11 Sep 2022 03:35:57 -0700 Subject: [PATCH 071/152] Multilang: add missing Japanese translations (#25727) --- selfdrive/ui/translations/main_ja.ts | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index d6bd9e74ed..a0b2a99866 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -1170,7 +1170,7 @@ location set Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). - 時速31マイル(50km)を超えるスピードで走行中、方向指示器を作動させずに検出された車線ライン上に車両が触れた場合、車線に戻るアラートを受信します。 + 時速31マイル(50km)を超えるスピードで走行中、ウインカーを作動させずに検出された車線ライン上に車両が触れた場合、車線に戻るアラートを受信します。 @@ -1195,22 +1195,22 @@ location set 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + 🌮 エンドツーエンドのアクセル制御 (超アルファ版) 🌮 Experimental openpilot longitudinal control - + 実験段階のopenpilotによるアクセル制御 <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b> - + <b>警告: openpilotによるアクセル制御は実験段階であり、AEBを無効化します。</b> Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. - + アクセルとブレーキの制御をopenpilotに任せます。openpilotが人間と同じように運転します。最初期の実験段階です。 From 29f9c536b410a45001beb63c73f3645a8299c222 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 12 Sep 2022 04:56:38 +0800 Subject: [PATCH 072/152] camerad: build camerad on PC (#25726) * compile camerad on PC * scons cleanup Co-authored-by: Adeeb Shihadeh --- SConstruct | 3 --- system/camerad/SConscript | 24 +++++++++------------- system/camerad/cameras/camera_common.cc | 4 +--- system/camerad/cameras/camera_qcom2.cc | 1 - system/camerad/main.cc | 15 ++++++++------ system/camerad/test/camera_test.h | 27 ------------------------- 6 files changed, 20 insertions(+), 54 deletions(-) delete mode 100644 system/camerad/test/camera_test.h diff --git a/SConstruct b/SConstruct index 8b32eba4ae..178b0cc872 100644 --- a/SConstruct +++ b/SConstruct @@ -99,9 +99,6 @@ if arch == "larch64": "#third_party/libyuv/larch64/lib", "/usr/lib/aarch64-linux-gnu" ] - cpppath += [ - "#system/camerad/include", - ] cflags = ["-DQCOM2", "-mcpu=cortex-a57"] cxxflags = ["-DQCOM2", "-mcpu=cortex-a57"] rpath += ["/usr/local/lib"] diff --git a/system/camerad/SConscript b/system/camerad/SConscript index 65f682dcce..ddc763b53d 100644 --- a/system/camerad/SConscript +++ b/system/camerad/SConscript @@ -1,22 +1,18 @@ Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc') -libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', cereal, messaging, 'zmq', 'capnp', 'kj', visionipc, gpucommon] +libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', cereal, messaging, 'zmq', 'capnp', 'kj', visionipc, gpucommon, 'atomic'] -cameras = [] -if arch == "larch64": - libs += ['atomic'] - cameras = ['cameras/camera_qcom2.cc'] +cenv = env.Clone() +cenv['CPPPATH'].append('include/') - env.Program('camerad', [ - 'main.cc', - 'cameras/camera_common.cc', - 'cameras/camera_util.cc', - 'imgproc/utils.cc', - cameras, - ], LIBS=libs) +camera_obj = cenv.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/camera_util.cc']) +cenv.Program('camerad', [ + 'main.cc', + camera_obj, + ], LIBS=libs) if GetOption("test") and arch == "x86_64": - env.Program('test/ae_gray_test', [ + cenv.Program('test/ae_gray_test', [ 'test/ae_gray_test.cc', - 'cameras/camera_common.cc', + camera_obj, ], LIBS=libs) diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index 313af00b5a..d033d8e6b4 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -18,11 +18,9 @@ #include "system/hardware/hw.h" #include "msm_media_info.h" +#include "system/camerad/cameras/camera_qcom2.h" #ifdef QCOM2 #include "CL/cl_ext_qcom.h" -#include "system/camerad/cameras/camera_qcom2.h" -#else -#include "system/camerad/test/camera_test.h" #endif ExitHandler do_exit; diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 2f674cb50c..b2432bdd72 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -1304,4 +1304,3 @@ void cameras_run(MultiCameraState *s) { cameras_close(s); } - diff --git a/system/camerad/main.cc b/system/camerad/main.cc index c1f38f2224..35a3329f30 100644 --- a/system/camerad/main.cc +++ b/system/camerad/main.cc @@ -7,14 +7,17 @@ #include "system/hardware/hw.h" int main(int argc, char *argv[]) { - if (!Hardware::PC()) { - int ret; - ret = util::set_realtime_priority(53); - assert(ret == 0); - ret = util::set_core_affinity({6}); - assert(ret == 0 || Params().getBool("IsOffroad")); // failure ok while offroad due to offlining cores + if (Hardware::PC()) { + printf("camerad is not meant to run on PC\n"); + return 0; } + int ret; + ret = util::set_realtime_priority(53); + assert(ret == 0); + ret = util::set_core_affinity({6}); + assert(ret == 0 || Params().getBool("IsOffroad")); // failure ok while offroad due to offlining cores + camerad_thread(); return 0; } diff --git a/system/camerad/test/camera_test.h b/system/camerad/test/camera_test.h deleted file mode 100644 index c173f9b84c..0000000000 --- a/system/camerad/test/camera_test.h +++ /dev/null @@ -1,27 +0,0 @@ -// TODO: cleanup AE tests -// needed by camera_common.cc -void camera_autoexposure(CameraState *s, float grey_frac) {} -void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) {} -void cameras_open(MultiCameraState *s) {} -void cameras_run(MultiCameraState *s) {} - -typedef struct CameraState { - int camera_num; - CameraInfo ci; - - int fps; - float digital_gain = 0; - - int camera_id; - - CameraBuf buf; -} CameraState; - -typedef struct MultiCameraState { - CameraState road_cam; - CameraState driver_cam; - - PubMaster *pm = nullptr; -} MultiCameraState; - - From 722e4641fc5aa28ab0ba2de266d230853d5ac321 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 13 Sep 2022 01:30:58 +0800 Subject: [PATCH 073/152] prime.cc: call update() after QR code changed (#25740) --- selfdrive/ui/qt/widgets/prime.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/ui/qt/widgets/prime.cc b/selfdrive/ui/qt/widgets/prime.cc index a8ceee4ca9..1d765d0949 100644 --- a/selfdrive/ui/qt/widgets/prime.cc +++ b/selfdrive/ui/qt/widgets/prime.cc @@ -35,6 +35,7 @@ void PairingQRWidget::refresh() { QString pairToken = CommaApi::create_jwt({{"pair", true}}); QString qrString = "https://connect.comma.ai/?pair=" + pairToken; this->updateQrCode(qrString); + update(); } void PairingQRWidget::updateQrCode(const QString &text) { From f1a2dc36ba15ce374ef13f77c460d3100d3ab3b3 Mon Sep 17 00:00:00 2001 From: Igor Biletskyy Date: Mon, 12 Sep 2022 15:08:19 -0700 Subject: [PATCH 074/152] bump panda and cereal (#25746) bump --- cereal | 2 +- panda | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index cea51afd67..2335f98bbe 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit cea51afd67b5c56f7a18207ef91c5e45d6345526 +Subproject commit 2335f98bbe628ec6fde92c8d929ecaf373b125af diff --git a/panda b/panda index 8f13ca3f66..15eda6a7c9 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 8f13ca3f66bcc72e3ac9028df7ce04851e7e3a48 +Subproject commit 15eda6a7c9cf4b0c7b5a7bbde25fcab3ff0a98fc From f2d9ecb08afdab2c547d4114fb6804ccffde00e5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 12 Sep 2022 15:31:12 -0700 Subject: [PATCH 075/152] updated: run lfs prune (#25729) --- selfdrive/updated.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 7278ef5a80..403ea2172b 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -249,13 +249,14 @@ def finalize_update(wait_helper: WaitTimeHelper) -> None: run(["git", "reset", "--hard"], FINALIZED) run(["git", "submodule", "foreach", "--recursive", "git", "reset"], FINALIZED) - cloudlog.info("Starting git gc") + cloudlog.info("Starting git cleanup in finalized update") t = time.monotonic() try: run(["git", "gc"], FINALIZED) - cloudlog.event("Done git gc", duration=time.monotonic() - t) + run(["git", "lfs", "prune"], FINALIZED) + cloudlog.event("Done git cleanup", duration=time.monotonic() - t) except subprocess.CalledProcessError: - cloudlog.exception(f"Failed git gc, took {time.monotonic() - t:.3f} s") + cloudlog.exception(f"Failed git cleanup, took {time.monotonic() - t:.3f} s") if wait_helper.shutdown: cloudlog.info("got interrupted finalizing overlay") From 5222c90df42655571597b78c5f48f16b9c5439b7 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Mon, 12 Sep 2022 22:55:52 -0500 Subject: [PATCH 076/152] Add several missing CAMRYH_TSS2 firmwares (#25745) `!razor_amd#7792` 2021 Toyota Camry Hybrid (Japanese import) DongleID/route 8553bd6f44d925f8|2022-09-12--22-01-21 --- selfdrive/car/toyota/values.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 94fbdc8bf2..b0fb143113 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -541,13 +541,16 @@ FW_VERSIONS = { CAR.CAMRYH_TSS2: { (Ecu.eps, 0x7a1, None): [ b'8965B33630\x00\x00\x00\x00\x00\x00', + b'8965B33650\x00\x00\x00\x00\x00\x00', ], (Ecu.abs, 0x7b0, None): [ b'F152633D00\x00\x00\x00\x00\x00\x00', + b'F152633D60\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x700, None): [ b'\x018966306Q6000\x00\x00\x00\x00', b'\x018966306Q7000\x00\x00\x00\x00', + b'\x01896633T20000\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 15): [ b'\x018821F6201200\x00\x00\x00\x00', From 56b05d55eb99657595c5bc47c39fb393fb889f64 Mon Sep 17 00:00:00 2001 From: Brandon Bennett <56660362+bbennett80@users.noreply.github.com> Date: Mon, 12 Sep 2022 22:24:11 -0700 Subject: [PATCH 077/152] Subaru: Add missing 2020 Ascent f/w (#25725) * add missing ascent fw version Ascent had recall service for transmission ecu. New values added. * Update selfdrive/car/subaru/values.py Co-authored-by: Shane Smiskol --- selfdrive/car/subaru/values.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 58fe111fbd..6c3a35307e 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -104,6 +104,7 @@ FW_VERSIONS = { b'\000\000e~\037@ \'', b'\x00\x00e@\x1f@ $', b'\x00\x00d\xb9\x00\x00\x00\x00', + b'\x00\x00e@\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [ b'\xbb,\xa0t\a', @@ -111,11 +112,13 @@ FW_VERSIONS = { b'\xf1\x82\xbb,\xa0t\a', b'\xf1\x82\xd9,\xa0@\a', b'\xf1\x82\xd1,\xa0q\x07', + b'\xd1,\xa0q\x07', ], (Ecu.transmission, 0x7e1, None): [ b'\x00\xfe\xf7\x00\x00', b'\001\xfe\xf9\000\000', b'\x01\xfe\xf7\x00\x00', + b'\x01\xfe\xfa\x00\x00', ], }, CAR.LEGACY: { From 84a3c355e5fdb7bb2f50847f925e894eecfa8918 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 13 Sep 2022 07:29:31 +0200 Subject: [PATCH 078/152] sensord: use interrupts to improve LSM6DS3 timing accuracy (#24525) * change LSM6DS3TR(-c) gyroscope and accelerometer to interrupt * add pthread for linking * add interrupt collector thread to fetch in parallel to non interrupt based sensors * change get_event interface to return true on successful read * fetch sensor interrupts via gpiochip * avoid sending empty messages (interrupt only, non interupt magn can leave a gap in the orphan block) * add verifier script to sensor interrupts (sensor_data_to_hist.py) * add/update sensord testsweet (test_sensord.py) * add poll timed out check * unexport interrupt gpio pins * gpiochip on both edges, but skip falling edge if rising edge is detected, this is handled in the sensor as the status flag is checked if new data is availble * add test to sensord to verify 100Hz interrupt frequency * add sensor shutdown/low power mode functionality on sensord exit * relax test, will be readded in the splitup PR Co-authored-by: Kurt Nistelberger --- common/gpio.cc | 39 +++- common/gpio.h | 12 + selfdrive/debug/sensor_data_to_hist.py | 121 ++++++++++ selfdrive/sensord/SConscript | 2 +- selfdrive/sensord/sensors/bmx055_accel.cc | 3 +- selfdrive/sensord/sensors/bmx055_accel.h | 3 +- selfdrive/sensord/sensors/bmx055_gyro.cc | 4 +- selfdrive/sensord/sensors/bmx055_gyro.h | 3 +- selfdrive/sensord/sensors/bmx055_magn.cc | 7 +- selfdrive/sensord/sensors/bmx055_magn.h | 3 +- selfdrive/sensord/sensors/bmx055_temp.cc | 3 +- selfdrive/sensord/sensors/bmx055_temp.h | 3 +- selfdrive/sensord/sensors/file_sensor.cc | 4 + selfdrive/sensord/sensors/file_sensor.h | 3 +- selfdrive/sensord/sensors/i2c_sensor.cc | 23 +- selfdrive/sensord/sensors/i2c_sensor.h | 14 +- selfdrive/sensord/sensors/light_sensor.cc | 4 +- selfdrive/sensord/sensors/light_sensor.h | 3 +- selfdrive/sensord/sensors/lsm6ds3_accel.cc | 58 ++++- selfdrive/sensord/sensors/lsm6ds3_accel.h | 17 +- selfdrive/sensord/sensors/lsm6ds3_gyro.cc | 59 ++++- selfdrive/sensord/sensors/lsm6ds3_gyro.h | 17 +- selfdrive/sensord/sensors/lsm6ds3_temp.cc | 3 +- selfdrive/sensord/sensors/lsm6ds3_temp.h | 3 +- selfdrive/sensord/sensors/mmc5603nj_magn.cc | 3 +- selfdrive/sensord/sensors/mmc5603nj_magn.h | 3 +- selfdrive/sensord/sensors/sensor.h | 5 +- selfdrive/sensord/sensors_qcom2.cc | 99 ++++++++- selfdrive/sensord/tests/test_sensord.py | 231 +++++++++++++++++++- system/hardware/tici/hardware.py | 11 + system/hardware/tici/pins.py | 6 + 31 files changed, 711 insertions(+), 58 deletions(-) create mode 100755 selfdrive/debug/sensor_data_to_hist.py mode change 100755 => 100644 selfdrive/sensord/tests/test_sensord.py diff --git a/common/gpio.cc b/common/gpio.cc index 73ff1b3f52..9f5c211a4b 100644 --- a/common/gpio.cc +++ b/common/gpio.cc @@ -4,11 +4,11 @@ #include #include +#include +#include #include "common/util.h" - -// We assume that all pins have already been exported on boot, -// and that we have permission to write to them. +#include "common/swaglog.h" int gpio_init(int pin_nr, bool output) { char pin_dir_path[50]; @@ -30,3 +30,36 @@ int gpio_set(int pin_nr, bool high) { } return util::write_file(pin_val_path, (void*)(high ? "1" : "0"), 1); } + +int gpiochip_get_ro_value_fd(const char* consumer_label, int gpiochiop_id, int pin_nr) { + + // Assumed that all interrupt pins are unexported and rights are given to + // read from gpiochip0. + std::string gpiochip_path = "/dev/gpiochip" + std::to_string(gpiochiop_id); + int fd = open(gpiochip_path.c_str(), O_RDONLY); + if (fd < 0) { + LOGE("Error opening gpiochip0 fd") + return -1; + } + + // Setup event + struct gpioevent_request rq; + rq.lineoffset = pin_nr; + rq.handleflags = GPIOHANDLE_REQUEST_INPUT; + + /* Requesting both edges as the data ready pulse from the lsm6ds sensor is + very short(75us) and is mostly detected as falling edge instead of rising. + So if it is detected as rising the following falling edge is skipped. */ + rq.eventflags = GPIOEVENT_REQUEST_BOTH_EDGES; + + strncpy(rq.consumer_label, consumer_label, std::size(rq.consumer_label) - 1); + int ret = ioctl(fd, GPIO_GET_LINEEVENT_IOCTL, &rq); + if (ret == -1) { + LOGE("Unable to get line event from ioctl : %s", strerror(errno)); + close(fd); + return -1; + } + + close(fd); + return rq.fd; +} diff --git a/common/gpio.h b/common/gpio.h index e030019875..b2f67f8ba3 100644 --- a/common/gpio.h +++ b/common/gpio.h @@ -8,6 +8,11 @@ #define GPIO_UBLOX_PWR_EN 34 #define GPIO_STM_RST_N 124 #define GPIO_STM_BOOT0 134 + #define GPIO_BMX_ACCEL_INT 21 + #define GPIO_BMX_GYRO_INT 23 + #define GPIO_BMX_MAGN_INT 87 + #define GPIO_LSM_INT 84 + #define GPIOCHIP_INT 0 #else #define GPIO_HUB_RST_N 0 #define GPIO_UBLOX_RST_N 0 @@ -15,7 +20,14 @@ #define GPIO_UBLOX_PWR_EN 0 #define GPIO_STM_RST_N 0 #define GPIO_STM_BOOT0 0 + #define GPIO_BMX_ACCEL_INT 0 + #define GPIO_BMX_GYRO_INT 0 + #define GPIO_BMX_MAGN_INT 0 + #define GPIO_LSM_INT 0 + #define GPIOCHIP_INT 0 #endif int gpio_init(int pin_nr, bool output); int gpio_set(int pin_nr, bool high); + +int gpiochip_get_ro_value_fd(const char* consumer_label, int gpiochiop_id, int pin_nr); diff --git a/selfdrive/debug/sensor_data_to_hist.py b/selfdrive/debug/sensor_data_to_hist.py new file mode 100755 index 0000000000..3c30b3c17c --- /dev/null +++ b/selfdrive/debug/sensor_data_to_hist.py @@ -0,0 +1,121 @@ +#!/usr/bin/env python3 +''' +printing the gap between interrupts in a histogram to check if the +frequency is what we expect, the bmx is not interrupt driven for as we +get interrupts in a 2kHz rate. +''' + +import argparse +import sys +from collections import defaultdict + +from tools.lib.logreader import LogReader +from tools.lib.route import Route + +import matplotlib.pyplot as plt + +SRC_BMX = "bmx055" +SRC_LSM = "lsm6ds3" + + +def parseEvents(log_reader): + bmx_data = defaultdict(list) + lsm_data = defaultdict(list) + + for m in log_reader: + # only sensorEvents + if m.which() != 'sensorEvents': + continue + + for se in m.sensorEvents: + # convert data to dictionary + d = se.to_dict() + + if d["timestamp"] == 0: + continue # empty event? + + if d["source"] == SRC_BMX and "acceleration" in d: + bmx_data["accel"].append(d["timestamp"] / 1e9) + + if d["source"] == SRC_BMX and "gyroUncalibrated" in d: + bmx_data["gyro"].append(d["timestamp"] / 1e9) + + if d["source"] == SRC_LSM and "acceleration" in d: + lsm_data["accel"].append(d["timestamp"] / 1e9) + + if d["source"] == SRC_LSM and "gyroUncalibrated" in d: + lsm_data["gyro"].append(d["timestamp"] / 1e9) + + return bmx_data, lsm_data + + +def cleanData(data): + if len(data) == 0: + return [], [] + + data.sort() + prev = data[0] + diffs = [] + for v in data[1:]: + diffs.append(v - prev) + prev = v + return data, diffs + + +def logAvgValues(data, sensor): + if len(data) == 0: + print(f"{sensor}: no data to average") + return + + avg = sum(data) / len(data) + hz = 1 / avg + print(f"{sensor}: data_points: {len(data)} avg [ns]: {avg} avg [Hz]: {hz}") + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("route", type=str, help="route name") + parser.add_argument("segment", type=int, help="segment number") + args = parser.parse_args() + + r = Route(args.route) + logs = r.log_paths() + + if len(logs) == 0: + print("NO data routes") + sys.exit(0) + + if args.segment >= len(logs): + print(f"RouteID: {args.segment} out of range, max: {len(logs) -1}") + sys.exit(0) + + lr = LogReader(logs[args.segment]) + bmx_data, lsm_data = parseEvents(lr) + + # sort bmx accel data, and then cal all the diffs, and to a histogram of those + bmx_accel, bmx_accel_diffs = cleanData(bmx_data["accel"]) + bmx_gyro, bmx_gyro_diffs = cleanData(bmx_data["gyro"]) + lsm_accel, lsm_accel_diffs = cleanData(lsm_data["accel"]) + lsm_gyro, lsm_gyro_diffs = cleanData(lsm_data["gyro"]) + + # get out the averages + logAvgValues(bmx_accel_diffs, "bmx accel") + logAvgValues(bmx_gyro_diffs, "bmx gyro ") + logAvgValues(lsm_accel_diffs, "lsm accel") + logAvgValues(lsm_gyro_diffs, "lsm gyro ") + + fig, axs = plt.subplots(1, 2, tight_layout=True) + axs[0].hist(bmx_accel_diffs, bins=50) + axs[0].set_title("bmx_accel") + axs[1].hist(bmx_gyro_diffs, bins=50) + axs[1].set_title("bmx_gyro") + + figl, axsl = plt.subplots(1, 2, tight_layout=True) + axsl[0].hist(lsm_accel_diffs, bins=50) + axsl[0].set_title("lsm_accel") + axsl[1].hist(lsm_gyro_diffs, bins=50) + axsl[1].set_title("lsm_gyro") + + print("check plot...") + plt.show() + diff --git a/selfdrive/sensord/SConscript b/selfdrive/sensord/SConscript index db32887e7f..8f26c00853 100644 --- a/selfdrive/sensord/SConscript +++ b/selfdrive/sensord/SConscript @@ -13,7 +13,7 @@ sensors = [ 'sensors/lsm6ds3_temp.cc', 'sensors/mmc5603nj_magn.cc', ] -libs = [common, cereal, messaging, 'capnp', 'zmq', 'kj'] +libs = [common, cereal, messaging, 'capnp', 'zmq', 'kj', 'pthread'] if arch == "larch64": libs.append('i2c') env.Program('_sensord', ['sensors_qcom2.cc'] + sensors, LIBS=libs) diff --git a/selfdrive/sensord/sensors/bmx055_accel.cc b/selfdrive/sensord/sensors/bmx055_accel.cc index d17e3fe617..e191d0d72b 100644 --- a/selfdrive/sensord/sensors/bmx055_accel.cc +++ b/selfdrive/sensord/sensors/bmx055_accel.cc @@ -43,7 +43,7 @@ fail: return ret; } -void BMX055_Accel::get_event(cereal::SensorEventData::Builder &event) { +bool BMX055_Accel::get_event(cereal::SensorEventData::Builder &event) { uint64_t start_time = nanos_since_boot(); uint8_t buffer[6]; int len = read_register(BMX055_ACCEL_I2C_REG_X_LSB, buffer, sizeof(buffer)); @@ -66,4 +66,5 @@ void BMX055_Accel::get_event(cereal::SensorEventData::Builder &event) { svec.setV(xyz); svec.setStatus(true); + return true; } diff --git a/selfdrive/sensord/sensors/bmx055_accel.h b/selfdrive/sensord/sensors/bmx055_accel.h index 86ec419cde..3b6dd536a7 100644 --- a/selfdrive/sensord/sensors/bmx055_accel.h +++ b/selfdrive/sensord/sensors/bmx055_accel.h @@ -33,5 +33,6 @@ class BMX055_Accel : public I2CSensor { public: BMX055_Accel(I2CBus *bus); int init(); - void get_event(cereal::SensorEventData::Builder &event); + bool get_event(cereal::SensorEventData::Builder &event); + int shutdown() { return 0; } }; diff --git a/selfdrive/sensord/sensors/bmx055_gyro.cc b/selfdrive/sensord/sensors/bmx055_gyro.cc index 74b22d8fef..a7ed8debad 100644 --- a/selfdrive/sensord/sensors/bmx055_gyro.cc +++ b/selfdrive/sensord/sensors/bmx055_gyro.cc @@ -54,7 +54,7 @@ fail: return ret; } -void BMX055_Gyro::get_event(cereal::SensorEventData::Builder &event) { +bool BMX055_Gyro::get_event(cereal::SensorEventData::Builder &event) { uint64_t start_time = nanos_since_boot(); uint8_t buffer[6]; int len = read_register(BMX055_GYRO_I2C_REG_RATE_X_LSB, buffer, sizeof(buffer)); @@ -76,5 +76,5 @@ void BMX055_Gyro::get_event(cereal::SensorEventData::Builder &event) { auto svec = event.initGyroUncalibrated(); svec.setV(xyz); svec.setStatus(true); - + return true; } diff --git a/selfdrive/sensord/sensors/bmx055_gyro.h b/selfdrive/sensord/sensors/bmx055_gyro.h index ed0c16ff05..fea6c3e192 100644 --- a/selfdrive/sensord/sensors/bmx055_gyro.h +++ b/selfdrive/sensord/sensors/bmx055_gyro.h @@ -33,5 +33,6 @@ class BMX055_Gyro : public I2CSensor { public: BMX055_Gyro(I2CBus *bus); int init(); - void get_event(cereal::SensorEventData::Builder &event); + bool get_event(cereal::SensorEventData::Builder &event); + int shutdown() { return 0; } }; diff --git a/selfdrive/sensord/sensors/bmx055_magn.cc b/selfdrive/sensord/sensors/bmx055_magn.cc index a2c793eff6..9ba6cebd50 100644 --- a/selfdrive/sensord/sensors/bmx055_magn.cc +++ b/selfdrive/sensord/sensors/bmx055_magn.cc @@ -213,7 +213,7 @@ bool BMX055_Magn::parse_xyz(uint8_t buffer[8], int16_t *x, int16_t *y, int16_t * } -void BMX055_Magn::get_event(cereal::SensorEventData::Builder &event) { +bool BMX055_Magn::get_event(cereal::SensorEventData::Builder &event) { uint64_t start_time = nanos_since_boot(); uint8_t buffer[8]; int16_t _x, _y, x, y, z; @@ -221,7 +221,8 @@ void BMX055_Magn::get_event(cereal::SensorEventData::Builder &event) { int len = read_register(BMX055_MAGN_I2C_REG_DATAX_LSB, buffer, sizeof(buffer)); assert(len == sizeof(buffer)); - if (parse_xyz(buffer, &_x, &_y, &z)) { + bool parsed = parse_xyz(buffer, &_x, &_y, &z); + if (parsed) { event.setSource(cereal::SensorEventData::SensorSource::BMX055); event.setVersion(2); event.setSensor(SENSOR_MAGNETOMETER_UNCALIBRATED); @@ -247,4 +248,6 @@ void BMX055_Magn::get_event(cereal::SensorEventData::Builder &event) { // at a 100 Hz. When reading the registers we have to check the ready bit // To verify the measurement was completed this cycle. set_register(BMX055_MAGN_I2C_REG_MAG, BMX055_MAGN_FORCED); + + return parsed; } diff --git a/selfdrive/sensord/sensors/bmx055_magn.h b/selfdrive/sensord/sensors/bmx055_magn.h index d60fd5515c..c762f2c3b9 100644 --- a/selfdrive/sensord/sensors/bmx055_magn.h +++ b/selfdrive/sensord/sensors/bmx055_magn.h @@ -59,5 +59,6 @@ class BMX055_Magn : public I2CSensor{ public: BMX055_Magn(I2CBus *bus); int init(); - void get_event(cereal::SensorEventData::Builder &event); + bool get_event(cereal::SensorEventData::Builder &event); + int shutdown() { return 0; } }; diff --git a/selfdrive/sensord/sensors/bmx055_temp.cc b/selfdrive/sensord/sensors/bmx055_temp.cc index 85bdea9e61..3cee34ef19 100644 --- a/selfdrive/sensord/sensors/bmx055_temp.cc +++ b/selfdrive/sensord/sensors/bmx055_temp.cc @@ -28,7 +28,7 @@ fail: return ret; } -void BMX055_Temp::get_event(cereal::SensorEventData::Builder &event) { +bool BMX055_Temp::get_event(cereal::SensorEventData::Builder &event) { uint64_t start_time = nanos_since_boot(); uint8_t buffer[1]; int len = read_register(BMX055_ACCEL_I2C_REG_TEMP, buffer, sizeof(buffer)); @@ -41,4 +41,5 @@ void BMX055_Temp::get_event(cereal::SensorEventData::Builder &event) { event.setType(SENSOR_TYPE_AMBIENT_TEMPERATURE); event.setTimestamp(start_time); event.setTemperature(temp); + return true; } diff --git a/selfdrive/sensord/sensors/bmx055_temp.h b/selfdrive/sensord/sensors/bmx055_temp.h index 5ffaa8fb6b..f5d771a29c 100644 --- a/selfdrive/sensord/sensors/bmx055_temp.h +++ b/selfdrive/sensord/sensors/bmx055_temp.h @@ -8,5 +8,6 @@ class BMX055_Temp : public I2CSensor { public: BMX055_Temp(I2CBus *bus); int init(); - void get_event(cereal::SensorEventData::Builder &event); + bool get_event(cereal::SensorEventData::Builder &event); + int shutdown() { return 0; } }; diff --git a/selfdrive/sensord/sensors/file_sensor.cc b/selfdrive/sensord/sensors/file_sensor.cc index 812a41fa8a..80e5121564 100644 --- a/selfdrive/sensord/sensors/file_sensor.cc +++ b/selfdrive/sensord/sensors/file_sensor.cc @@ -12,3 +12,7 @@ int FileSensor::init() { FileSensor::~FileSensor() { file.close(); } + +bool FileSensor::has_interrupt_enabled() { + return false; +} \ No newline at end of file diff --git a/selfdrive/sensord/sensors/file_sensor.h b/selfdrive/sensord/sensors/file_sensor.h index c5b4643e16..5bcaee66a8 100644 --- a/selfdrive/sensord/sensors/file_sensor.h +++ b/selfdrive/sensord/sensors/file_sensor.h @@ -14,5 +14,6 @@ public: FileSensor(std::string filename); ~FileSensor(); int init(); - virtual void get_event(cereal::SensorEventData::Builder &event) = 0; + bool has_interrupt_enabled(); + virtual bool get_event(cereal::SensorEventData::Builder &event) = 0; }; diff --git a/selfdrive/sensord/sensors/i2c_sensor.cc b/selfdrive/sensord/sensors/i2c_sensor.cc index 40dfa4a736..06a216478b 100644 --- a/selfdrive/sensord/sensors/i2c_sensor.cc +++ b/selfdrive/sensord/sensors/i2c_sensor.cc @@ -15,8 +15,12 @@ int32_t read_20_bit(uint8_t b2, uint8_t b1, uint8_t b0) { return int32_t(combined) / (1 << 4); } +I2CSensor::I2CSensor(I2CBus *bus, int gpio_nr, bool shared_gpio) : bus(bus), gpio_nr(gpio_nr), shared_gpio(shared_gpio) {} -I2CSensor::I2CSensor(I2CBus *bus) : bus(bus) { +I2CSensor::~I2CSensor() { + if (gpio_fd != -1) { + close(gpio_fd); + } } int I2CSensor::read_register(uint register_address, uint8_t *buffer, uint8_t len) { @@ -26,3 +30,20 @@ int I2CSensor::read_register(uint register_address, uint8_t *buffer, uint8_t len int I2CSensor::set_register(uint register_address, uint8_t data) { return bus->set_register(get_device_address(), register_address, data); } + +int I2CSensor::init_gpio() { + if (shared_gpio || gpio_nr == 0) { + return 0; + } + + gpio_fd = gpiochip_get_ro_value_fd("sensord", GPIOCHIP_INT, gpio_nr); + if (gpio_fd < 0) { + return -1; + } + + return 0; +} + +bool I2CSensor::has_interrupt_enabled() { + return gpio_nr != 0; +} diff --git a/selfdrive/sensord/sensors/i2c_sensor.h b/selfdrive/sensord/sensors/i2c_sensor.h index 7832475a98..f6820a2471 100644 --- a/selfdrive/sensord/sensors/i2c_sensor.h +++ b/selfdrive/sensord/sensors/i2c_sensor.h @@ -1,9 +1,13 @@ #pragma once #include +#include #include "cereal/gen/cpp/log.capnp.h" + #include "common/i2c.h" +#include "common/gpio.h" + #include "selfdrive/sensord/sensors/constants.h" #include "selfdrive/sensord/sensors/sensor.h" @@ -15,12 +19,18 @@ int32_t read_20_bit(uint8_t b2, uint8_t b1, uint8_t b0); class I2CSensor : public Sensor { private: I2CBus *bus; + int gpio_nr; + bool shared_gpio; virtual uint8_t get_device_address() = 0; public: - I2CSensor(I2CBus *bus); + I2CSensor(I2CBus *bus, int gpio_nr = 0, bool shared_gpio = false); + ~I2CSensor(); int read_register(uint register_address, uint8_t *buffer, uint8_t len); int set_register(uint register_address, uint8_t data); + int init_gpio(); + bool has_interrupt_enabled(); virtual int init() = 0; - virtual void get_event(cereal::SensorEventData::Builder &event) = 0; + virtual bool get_event(cereal::SensorEventData::Builder &event) = 0; + virtual int shutdown() = 0; }; diff --git a/selfdrive/sensord/sensors/light_sensor.cc b/selfdrive/sensord/sensors/light_sensor.cc index 4497343684..321ac75c7e 100644 --- a/selfdrive/sensord/sensors/light_sensor.cc +++ b/selfdrive/sensord/sensors/light_sensor.cc @@ -5,7 +5,7 @@ #include "common/timing.h" #include "selfdrive/sensord/sensors/constants.h" -void LightSensor::get_event(cereal::SensorEventData::Builder &event) { +bool LightSensor::get_event(cereal::SensorEventData::Builder &event) { uint64_t start_time = nanos_since_boot(); file.clear(); file.seekg(0); @@ -19,4 +19,6 @@ void LightSensor::get_event(cereal::SensorEventData::Builder &event) { event.setType(SENSOR_TYPE_LIGHT); event.setTimestamp(start_time); event.setLight(value); + + return true; } diff --git a/selfdrive/sensord/sensors/light_sensor.h b/selfdrive/sensord/sensors/light_sensor.h index faf901d41c..63bda74755 100644 --- a/selfdrive/sensord/sensors/light_sensor.h +++ b/selfdrive/sensord/sensors/light_sensor.h @@ -4,5 +4,6 @@ class LightSensor : public FileSensor { public: LightSensor(std::string filename) : FileSensor(filename){}; - void get_event(cereal::SensorEventData::Builder &event); + bool get_event(cereal::SensorEventData::Builder &event); + int shutdown() { return 0; } }; diff --git a/selfdrive/sensord/sensors/lsm6ds3_accel.cc b/selfdrive/sensord/sensors/lsm6ds3_accel.cc index d923986dbe..8cc89e457c 100644 --- a/selfdrive/sensord/sensors/lsm6ds3_accel.cc +++ b/selfdrive/sensord/sensors/lsm6ds3_accel.cc @@ -5,11 +5,12 @@ #include "common/swaglog.h" #include "common/timing.h" -LSM6DS3_Accel::LSM6DS3_Accel(I2CBus *bus) : I2CSensor(bus) {} +LSM6DS3_Accel::LSM6DS3_Accel(I2CBus *bus, int gpio_nr, bool shared_gpio) : I2CSensor(bus, gpio_nr, shared_gpio) {} int LSM6DS3_Accel::init() { int ret = 0; uint8_t buffer[1]; + uint8_t value = 0; ret = read_register(LSM6DS3_ACCEL_I2C_REG_ID, buffer, 1); if(ret < 0) { @@ -27,20 +28,69 @@ int LSM6DS3_Accel::init() { source = cereal::SensorEventData::SensorSource::LSM6DS3TRC; } + ret = init_gpio(); + if (ret < 0) { + goto fail; + } + // TODO: set scale and bandwidth. Default is +- 2G, 50 Hz ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, LSM6DS3_ACCEL_ODR_104HZ); if (ret < 0) { goto fail; } + ret = set_register(LSM6DS3_ACCEL_I2C_REG_DRDY_CFG, LSM6DS3_ACCEL_DRDY_PULSE_MODE); + if (ret < 0) { + goto fail; + } + + // enable data ready interrupt for accel on INT1 + // (without resetting existing interrupts) + ret = read_register(LSM6DS3_ACCEL_I2C_REG_INT1_CTRL, &value, 1); + if (ret < 0) { + goto fail; + } + + value |= LSM6DS3_ACCEL_INT1_DRDY_XL; + ret = set_register(LSM6DS3_ACCEL_I2C_REG_INT1_CTRL, value); fail: return ret; } -void LSM6DS3_Accel::get_event(cereal::SensorEventData::Builder &event) { +int LSM6DS3_Accel::shutdown() { + int ret = 0; + + // disable data ready interrupt for accel on INT1 + uint8_t value = 0; + ret = read_register(LSM6DS3_ACCEL_I2C_REG_INT1_CTRL, &value, 1); + if (ret < 0) { + goto fail; + } + + value &= ~(LSM6DS3_ACCEL_INT1_DRDY_XL); + ret = set_register(LSM6DS3_ACCEL_I2C_REG_INT1_CTRL, value); + if (ret < 0) { + goto fail; + } + return ret; + +fail: + LOGE("Could not disable lsm6ds3 acceleration interrupt!") + return ret; +} + +bool LSM6DS3_Accel::get_event(cereal::SensorEventData::Builder &event) { + + if (has_interrupt_enabled()) { + // INT1 shared with gyro, check STATUS_REG who triggered + uint8_t status_reg = 0; + read_register(LSM6DS3_ACCEL_I2C_REG_STAT_REG, &status_reg, sizeof(status_reg)); + if ((status_reg & LSM6DS3_ACCEL_DRDY_XLDA) == 0) { + return false; + } + } - uint64_t start_time = nanos_since_boot(); uint8_t buffer[6]; int len = read_register(LSM6DS3_ACCEL_I2C_REG_OUTX_L_XL, buffer, sizeof(buffer)); assert(len == sizeof(buffer)); @@ -54,11 +104,11 @@ void LSM6DS3_Accel::get_event(cereal::SensorEventData::Builder &event) { event.setVersion(1); event.setSensor(SENSOR_ACCELEROMETER); event.setType(SENSOR_TYPE_ACCELEROMETER); - event.setTimestamp(start_time); float xyz[] = {y, -x, z}; auto svec = event.initAcceleration(); svec.setV(xyz); svec.setStatus(true); + return true; } diff --git a/selfdrive/sensord/sensors/lsm6ds3_accel.h b/selfdrive/sensord/sensors/lsm6ds3_accel.h index 4a6b687445..6ed94a8f12 100644 --- a/selfdrive/sensord/sensors/lsm6ds3_accel.h +++ b/selfdrive/sensord/sensors/lsm6ds3_accel.h @@ -6,21 +6,28 @@ #define LSM6DS3_ACCEL_I2C_ADDR 0x6A // Registers of the chip +#define LSM6DS3_ACCEL_I2C_REG_DRDY_CFG 0x0B #define LSM6DS3_ACCEL_I2C_REG_ID 0x0F +#define LSM6DS3_ACCEL_I2C_REG_INT1_CTRL 0x0D #define LSM6DS3_ACCEL_I2C_REG_CTRL1_XL 0x10 +#define LSM6DS3_ACCEL_I2C_REG_STAT_REG 0x1E #define LSM6DS3_ACCEL_I2C_REG_OUTX_L_XL 0x28 // Constants -#define LSM6DS3_ACCEL_CHIP_ID 0x69 -#define LSM6DS3TRC_ACCEL_CHIP_ID 0x6A -#define LSM6DS3_ACCEL_ODR_104HZ (0b0100 << 4) +#define LSM6DS3_ACCEL_CHIP_ID 0x69 +#define LSM6DS3TRC_ACCEL_CHIP_ID 0x6A +#define LSM6DS3_ACCEL_ODR_104HZ (0b0100 << 4) +#define LSM6DS3_ACCEL_INT1_DRDY_XL 0b1 +#define LSM6DS3_ACCEL_DRDY_XLDA 0b1 +#define LSM6DS3_ACCEL_DRDY_PULSE_MODE (1 << 7) class LSM6DS3_Accel : public I2CSensor { uint8_t get_device_address() {return LSM6DS3_ACCEL_I2C_ADDR;} cereal::SensorEventData::SensorSource source = cereal::SensorEventData::SensorSource::LSM6DS3; public: - LSM6DS3_Accel(I2CBus *bus); + LSM6DS3_Accel(I2CBus *bus, int gpio_nr = 0, bool shared_gpio = false); int init(); - void get_event(cereal::SensorEventData::Builder &event); + bool get_event(cereal::SensorEventData::Builder &event); + int shutdown(); }; diff --git a/selfdrive/sensord/sensors/lsm6ds3_gyro.cc b/selfdrive/sensord/sensors/lsm6ds3_gyro.cc index c7711d34e3..a7321e8fa8 100644 --- a/selfdrive/sensord/sensors/lsm6ds3_gyro.cc +++ b/selfdrive/sensord/sensors/lsm6ds3_gyro.cc @@ -8,12 +8,12 @@ #define DEG2RAD(x) ((x) * M_PI / 180.0) - -LSM6DS3_Gyro::LSM6DS3_Gyro(I2CBus *bus) : I2CSensor(bus) {} +LSM6DS3_Gyro::LSM6DS3_Gyro(I2CBus *bus, int gpio_nr, bool shared_gpio) : I2CSensor(bus, gpio_nr, shared_gpio) {} int LSM6DS3_Gyro::init() { int ret = 0; uint8_t buffer[1]; + uint8_t value = 0; ret = read_register(LSM6DS3_GYRO_I2C_REG_ID, buffer, 1); if(ret < 0) { @@ -31,20 +31,69 @@ int LSM6DS3_Gyro::init() { source = cereal::SensorEventData::SensorSource::LSM6DS3TRC; } + ret = init_gpio(); + if (ret < 0) { + goto fail; + } + // TODO: set scale. Default is +- 250 deg/s ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL2_G, LSM6DS3_GYRO_ODR_104HZ); if (ret < 0) { goto fail; } + ret = set_register(LSM6DS3_GYRO_I2C_REG_DRDY_CFG, LSM6DS3_GYRO_DRDY_PULSE_MODE); + if (ret < 0) { + goto fail; + } + + // enable data ready interrupt for gyro on INT1 + // (without resetting existing interrupts) + ret = read_register(LSM6DS3_GYRO_I2C_REG_INT1_CTRL, &value, 1); + if (ret < 0) { + goto fail; + } + + value |= LSM6DS3_GYRO_INT1_DRDY_G; + ret = set_register(LSM6DS3_GYRO_I2C_REG_INT1_CTRL, value); + +fail: + return ret; +} + +int LSM6DS3_Gyro::shutdown() { + int ret = 0; + + // disable data ready interrupt for accel on INT1 + uint8_t value = 0; + ret = read_register(LSM6DS3_GYRO_I2C_REG_INT1_CTRL, &value, 1); + if (ret < 0) { + goto fail; + } + + value &= ~(LSM6DS3_GYRO_INT1_DRDY_G); + ret = set_register(LSM6DS3_GYRO_I2C_REG_INT1_CTRL, value); + if (ret < 0) { + goto fail; + } + return ret; fail: + LOGE("Could not disable lsm6ds3 gyroscope interrupt!") return ret; } -void LSM6DS3_Gyro::get_event(cereal::SensorEventData::Builder &event) { +bool LSM6DS3_Gyro::get_event(cereal::SensorEventData::Builder &event) { + + if (has_interrupt_enabled()) { + // INT1 shared with accel, check STATUS_REG who triggered + uint8_t status_reg = 0; + read_register(LSM6DS3_GYRO_I2C_REG_STAT_REG, &status_reg, sizeof(status_reg)); + if ((status_reg & LSM6DS3_GYRO_DRDY_GDA) == 0) { + return false; + } + } - uint64_t start_time = nanos_since_boot(); uint8_t buffer[6]; int len = read_register(LSM6DS3_GYRO_I2C_REG_OUTX_L_G, buffer, sizeof(buffer)); assert(len == sizeof(buffer)); @@ -58,11 +107,11 @@ void LSM6DS3_Gyro::get_event(cereal::SensorEventData::Builder &event) { event.setVersion(2); event.setSensor(SENSOR_GYRO_UNCALIBRATED); event.setType(SENSOR_TYPE_GYROSCOPE_UNCALIBRATED); - event.setTimestamp(start_time); float xyz[] = {y, -x, z}; auto svec = event.initGyroUncalibrated(); svec.setV(xyz); svec.setStatus(true); + return true; } diff --git a/selfdrive/sensord/sensors/lsm6ds3_gyro.h b/selfdrive/sensord/sensors/lsm6ds3_gyro.h index d7e8f0025a..c2ed5ab76e 100644 --- a/selfdrive/sensord/sensors/lsm6ds3_gyro.h +++ b/selfdrive/sensord/sensors/lsm6ds3_gyro.h @@ -6,21 +6,28 @@ #define LSM6DS3_GYRO_I2C_ADDR 0x6A // Registers of the chip +#define LSM6DS3_GYRO_I2C_REG_DRDY_CFG 0x0B #define LSM6DS3_GYRO_I2C_REG_ID 0x0F +#define LSM6DS3_GYRO_I2C_REG_INT1_CTRL 0x0D #define LSM6DS3_GYRO_I2C_REG_CTRL2_G 0x11 +#define LSM6DS3_GYRO_I2C_REG_STAT_REG 0x1E #define LSM6DS3_GYRO_I2C_REG_OUTX_L_G 0x22 // Constants -#define LSM6DS3_GYRO_CHIP_ID 0x69 -#define LSM6DS3TRC_GYRO_CHIP_ID 0x6A -#define LSM6DS3_GYRO_ODR_104HZ (0b0100 << 4) +#define LSM6DS3_GYRO_CHIP_ID 0x69 +#define LSM6DS3TRC_GYRO_CHIP_ID 0x6A +#define LSM6DS3_GYRO_ODR_104HZ (0b0100 << 4) +#define LSM6DS3_GYRO_INT1_DRDY_G 0b10 +#define LSM6DS3_GYRO_DRDY_GDA 0b10 +#define LSM6DS3_GYRO_DRDY_PULSE_MODE (1 << 7) class LSM6DS3_Gyro : public I2CSensor { uint8_t get_device_address() {return LSM6DS3_GYRO_I2C_ADDR;} cereal::SensorEventData::SensorSource source = cereal::SensorEventData::SensorSource::LSM6DS3; public: - LSM6DS3_Gyro(I2CBus *bus); + LSM6DS3_Gyro(I2CBus *bus, int gpio_nr = 0, bool shared_gpio = false); int init(); - void get_event(cereal::SensorEventData::Builder &event); + bool get_event(cereal::SensorEventData::Builder &event); + int shutdown(); }; diff --git a/selfdrive/sensord/sensors/lsm6ds3_temp.cc b/selfdrive/sensord/sensors/lsm6ds3_temp.cc index 1dd179d69e..082ffee08f 100644 --- a/selfdrive/sensord/sensors/lsm6ds3_temp.cc +++ b/selfdrive/sensord/sensors/lsm6ds3_temp.cc @@ -31,7 +31,7 @@ fail: return ret; } -void LSM6DS3_Temp::get_event(cereal::SensorEventData::Builder &event) { +bool LSM6DS3_Temp::get_event(cereal::SensorEventData::Builder &event) { uint64_t start_time = nanos_since_boot(); uint8_t buffer[2]; @@ -47,4 +47,5 @@ void LSM6DS3_Temp::get_event(cereal::SensorEventData::Builder &event) { event.setTimestamp(start_time); event.setTemperature(temp); + return true; } diff --git a/selfdrive/sensord/sensors/lsm6ds3_temp.h b/selfdrive/sensord/sensors/lsm6ds3_temp.h index 8188f46700..9d95236901 100644 --- a/selfdrive/sensord/sensors/lsm6ds3_temp.h +++ b/selfdrive/sensord/sensors/lsm6ds3_temp.h @@ -21,5 +21,6 @@ class LSM6DS3_Temp : public I2CSensor { public: LSM6DS3_Temp(I2CBus *bus); int init(); - void get_event(cereal::SensorEventData::Builder &event); + bool get_event(cereal::SensorEventData::Builder &event); + int shutdown() { return 0; } }; diff --git a/selfdrive/sensord/sensors/mmc5603nj_magn.cc b/selfdrive/sensord/sensors/mmc5603nj_magn.cc index 7c654ce7a3..2bfd887a74 100644 --- a/selfdrive/sensord/sensors/mmc5603nj_magn.cc +++ b/selfdrive/sensord/sensors/mmc5603nj_magn.cc @@ -51,7 +51,7 @@ fail: return ret; } -void MMC5603NJ_Magn::get_event(cereal::SensorEventData::Builder &event) { +bool MMC5603NJ_Magn::get_event(cereal::SensorEventData::Builder &event) { uint64_t start_time = nanos_since_boot(); uint8_t buffer[9]; @@ -74,4 +74,5 @@ void MMC5603NJ_Magn::get_event(cereal::SensorEventData::Builder &event) { svec.setV(xyz); svec.setStatus(true); + return true; } diff --git a/selfdrive/sensord/sensors/mmc5603nj_magn.h b/selfdrive/sensord/sensors/mmc5603nj_magn.h index 58840bbf27..857bd10a51 100644 --- a/selfdrive/sensord/sensors/mmc5603nj_magn.h +++ b/selfdrive/sensord/sensors/mmc5603nj_magn.h @@ -25,5 +25,6 @@ class MMC5603NJ_Magn : public I2CSensor { public: MMC5603NJ_Magn(I2CBus *bus); int init(); - void get_event(cereal::SensorEventData::Builder &event); + bool get_event(cereal::SensorEventData::Builder &event); + int shutdown() { return 0; } }; diff --git a/selfdrive/sensord/sensors/sensor.h b/selfdrive/sensord/sensors/sensor.h index 3fb58ad2ae..0bdc560275 100644 --- a/selfdrive/sensord/sensors/sensor.h +++ b/selfdrive/sensord/sensors/sensor.h @@ -4,7 +4,10 @@ class Sensor { public: + int gpio_fd = -1; virtual ~Sensor() {}; virtual int init() = 0; - virtual void get_event(cereal::SensorEventData::Builder &event) = 0; + virtual bool get_event(cereal::SensorEventData::Builder &event) = 0; + virtual bool has_interrupt_enabled() = 0; + virtual int shutdown() = 0; }; diff --git a/selfdrive/sensord/sensors_qcom2.cc b/selfdrive/sensord/sensors_qcom2.cc index 65fe43f65f..a9d6e31d3e 100644 --- a/selfdrive/sensord/sensors_qcom2.cc +++ b/selfdrive/sensord/sensors_qcom2.cc @@ -3,6 +3,8 @@ #include #include #include +#include +#include #include "cereal/messaging/messaging.h" #include "common/i2c.h" @@ -24,6 +26,79 @@ #define I2C_BUS_IMU 1 ExitHandler do_exit; +std::mutex pm_mutex; + +void interrupt_loop(int fd, std::vector& sensors, PubMaster& pm) { + struct pollfd fd_list[1] = {0}; + fd_list[0].fd = fd; + fd_list[0].events = POLLIN | POLLPRI; + + uint64_t offset = nanos_since_epoch() - nanos_since_boot(); + + while (!do_exit) { + int err = poll(fd_list, 1, 100); + if (err == -1) { + if (errno == EINTR) { + continue; + } + return; + } else if (err == 0) { + LOGE("poll timed out"); + continue; + } + + if ((fd_list[0].revents & (POLLIN | POLLPRI)) == 0) { + LOGE("no poll events set"); + continue; + } + + // Read all events + struct gpioevent_data evdata[16]; + err = read(fd, evdata, sizeof(evdata)); + if (err < 0 || err % sizeof(*evdata) != 0) { + LOGE("error reading event data %d", err); + continue; + } + + int num_events = err / sizeof(*evdata); + uint64_t ts = evdata[num_events - 1].timestamp - offset; + + MessageBuilder msg; + auto orphanage = msg.getOrphanage(); + std::vector> collected_events; + collected_events.reserve(sensors.size()); + + for (Sensor *sensor : sensors) { + auto orphan = orphanage.newOrphan(); + auto event = orphan.get(); + if (!sensor->get_event(event)) { + continue; + } + + event.setTimestamp(ts); + collected_events.push_back(kj::mv(orphan)); + } + + if (collected_events.size() == 0) { + continue; + } + + auto events = msg.initEvent().initSensorEvents(collected_events.size()); + for (int i = 0; i < collected_events.size(); ++i) { + events.adoptWithCaveats(i, kj::mv(collected_events[i])); + } + + { + std::lock_guard lock(pm_mutex); + pm.send("sensorEvents", msg); + } + } + + // poweroff sensors, disable interrupts + for (Sensor *sensor : sensors) { + sensor->shutdown(); + } +} int sensor_loop() { I2CBus *i2c_bus_imu; @@ -40,8 +115,8 @@ int sensor_loop() { BMX055_Magn bmx055_magn(i2c_bus_imu); BMX055_Temp bmx055_temp(i2c_bus_imu); - LSM6DS3_Accel lsm6ds3_accel(i2c_bus_imu); - LSM6DS3_Gyro lsm6ds3_gyro(i2c_bus_imu); + LSM6DS3_Accel lsm6ds3_accel(i2c_bus_imu, GPIO_LSM_INT); + LSM6DS3_Gyro lsm6ds3_gyro(i2c_bus_imu, GPIO_LSM_INT, true); // GPIO shared with accel LSM6DS3_Temp lsm6ds3_temp(i2c_bus_imu); MMC5603NJ_Magn mmc5603nj_magn(i2c_bus_imu); @@ -73,23 +148,33 @@ int sensor_loop() { // Fail on required sensors if (sensor.second) { LOGE("Error initializing sensors"); + delete i2c_bus_imu; return -1; } } else { if (sensor.first == &bmx055_magn || sensor.first == &mmc5603nj_magn) { has_magnetometer = true; } - sensors.push_back(sensor.first); + + if (!sensor.first->has_interrupt_enabled()) { + sensors.push_back(sensor.first); + } } } if (!has_magnetometer) { LOGE("No magnetometer present"); + delete i2c_bus_imu; return -1; } PubMaster pm({"sensorEvents"}); + // thread for reading events via interrupts + std::vector lsm_interrupt_sensors = {&lsm6ds3_accel, &lsm6ds3_gyro}; + std::thread lsm_interrupt_thread(&interrupt_loop, lsm6ds3_accel.gpio_fd, std::ref(lsm_interrupt_sensors), std::ref(pm)); + + // polling loop for non interrupt handled sensors while (!do_exit) { std::chrono::steady_clock::time_point begin = std::chrono::steady_clock::now(); @@ -102,11 +187,17 @@ int sensor_loop() { sensors[i]->get_event(event); } - pm.send("sensorEvents", msg); + { + std::lock_guard lock(pm_mutex); + pm.send("sensorEvents", msg); + } std::chrono::steady_clock::time_point end = std::chrono::steady_clock::now(); std::this_thread::sleep_for(std::chrono::milliseconds(10) - (end - begin)); } + + lsm_interrupt_thread.join(); + delete i2c_bus_imu; return 0; } diff --git a/selfdrive/sensord/tests/test_sensord.py b/selfdrive/sensord/tests/test_sensord.py old mode 100755 new mode 100644 index 9fd918c971..7abaf9ca35 --- a/selfdrive/sensord/tests/test_sensord.py +++ b/selfdrive/sensord/tests/test_sensord.py @@ -2,12 +2,15 @@ import time import unittest +import numpy as np +from collections import namedtuple +from smbus2 import SMBus import cereal.messaging as messaging +from cereal import log from system.hardware import TICI from selfdrive.test.helpers import with_processes - -TEST_TIMESPAN = 10 +from selfdrive.manager.process_config import managed_processes SENSOR_CONFIGURATIONS = ( { @@ -46,6 +49,63 @@ SENSOR_CONFIGURATIONS = ( }, ) +Sensor = log.SensorEventData.SensorSource +SensorConfig = namedtuple('SensorConfig', ['type', 'min_samples', 'sanity_min', 'sanity_max']) +ALL_SENSORS = { + Sensor.rpr0521: { + SensorConfig("light", 100, 0, 150), + }, + + Sensor.lsm6ds3: { + SensorConfig("acceleration", 100, 5, 15), + SensorConfig("gyroUncalibrated", 100, 0, .2), + SensorConfig("temperature", 100, 0, 60), + }, + + Sensor.lsm6ds3trc: { + SensorConfig("acceleration", 100, 5, 15), + SensorConfig("gyroUncalibrated", 100, 0, .2), + SensorConfig("temperature", 100, 0, 60), + }, + + Sensor.bmx055: { + SensorConfig("acceleration", 100, 5, 15), + SensorConfig("gyroUncalibrated", 100, 0, .2), + SensorConfig("magneticUncalibrated", 100, 0, 300), + SensorConfig("temperature", 100, 0, 60), + }, + + Sensor.mmc5603nj: { + SensorConfig("magneticUncalibrated", 100, 0, 300), + } +} + +SENSOR_BUS = 1 +I2C_ADDR_LSM = 0x6A +LSM_INT_GPIO = 84 + +def read_sensor_events(duration_sec): + sensor_events = messaging.sub_sock("sensorEvents", timeout=0.1) + start_time_sec = time.monotonic() + events = [] + while time.monotonic() - start_time_sec < duration_sec: + events += messaging.drain_sock(sensor_events) + time.sleep(0.01) + + assert len(events) != 0, "No sensor events collected" + return events + +def get_proc_interrupts(int_pin): + + with open("/proc/interrupts") as f: + lines = f.read().split("\n") + + for line in lines: + if f" {int_pin} " in line: + return ''.join(list(filter(lambda e: e != '', line.split(' ')))[1:6]) + + return "" + class TestSensord(unittest.TestCase): @classmethod @@ -55,24 +115,175 @@ class TestSensord(unittest.TestCase): @with_processes(['sensord']) def test_sensors_present(self): - sensor_events = messaging.sub_sock("sensorEvents", timeout=0.1) - - start_time_sec = time.time() - events = [] - while time.time() - start_time_sec < TEST_TIMESPAN: - events += messaging.drain_sock(sensor_events) - time.sleep(0.01) + # verify correct sensors configuration + events = read_sensor_events(10) seen = set() for event in events: for measurement in event.sensorEvents: - # Filter out unset events + # filter unset events (bmx magn) if measurement.version == 0: continue seen.add((str(measurement.source), measurement.which())) self.assertIn(seen, SENSOR_CONFIGURATIONS) + @with_processes(['sensord']) + def test_lsm6ds3_100Hz(self): + # verify measurements are sampled and published at a 100Hz rate + events = read_sensor_events(3) # 3sec (about 300 measurements) + + data_points = set() + for event in events: + for measurement in event.sensorEvents: + + # skip lsm6ds3 temperature measurements + if measurement.which() == 'temperature': + continue + + if str(measurement.source).startswith("lsm6ds3"): + data_points.add(measurement.timestamp) + + assert len(data_points) != 0, "No lsm6ds3 sensor events" + + data_list = list(data_points) + data_list.sort() + tdiffs = np.diff(data_list) + + high_delay_diffs = set(filter(lambda d: d >= 10.1*10**6, tdiffs)) + assert len(high_delay_diffs) < 10, f"Too many high delay packages: {high_delay_diffs}" + + avg_diff = sum(tdiffs)/len(tdiffs) + assert avg_diff > 9.6*10**6, f"avg difference {avg_diff}, below threshold" + + stddev = np.std(tdiffs) + assert stddev < 1.5*10**6, f"Standard-dev to big {stddev}" + + @with_processes(['sensord']) + def test_events_check(self): + # verify if all sensors produce events + events = read_sensor_events(3) + + sensor_events = dict() + for event in events: + for measurement in event.sensorEvents: + + # filter unset events (bmx magn) + if measurement.version == 0: + continue + + if measurement.type in sensor_events: + sensor_events[measurement.type] += 1 + else: + sensor_events[measurement.type] = 1 + + for s in sensor_events: + err_msg = f"Sensor {s}: 200 < {sensor_events[s]}" + assert sensor_events[s] > 200, err_msg + + @with_processes(['sensord']) + def test_logmonottime_timestamp_diff(self): + # ensure diff between the message logMonotime and sample timestamp is small + events = read_sensor_events(3) + + tdiffs = list() + for event in events: + for measurement in event.sensorEvents: + + # filter unset events (bmx magn) + if measurement.version == 0: + continue + + # check if gyro and accel timestamps are before logMonoTime + if str(measurement.source).startswith("lsm6ds3"): + if measurement.which() != 'temperature': + err_msg = f"Timestamp after logMonoTime: {measurement.timestamp} > {event.logMonoTime}" + assert measurement.timestamp < event.logMonoTime, err_msg + + # negative values might occur, as non interrupt packages created + # before the sensor is read + tdiffs.append(abs(event.logMonoTime - measurement.timestamp)) + + high_delay_diffs = set(filter(lambda d: d >= 10*10**6, tdiffs)) + assert len(high_delay_diffs) < 15, f"Too many high delay packages: {high_delay_diffs}" + + avg_diff = round(sum(tdiffs)/len(tdiffs), 4) + assert avg_diff < 4*10**6, f"Avg packet diff: {avg_diff:.1f}ns" + + stddev = np.std(tdiffs) + assert stddev < 2*10**6, f"Timing diffs have to high stddev: {stddev}" + + @with_processes(['sensord']) + def test_sensor_values_sanity_check(self): + + events = read_sensor_events(2) + + sensor_values = dict() + for event in events: + for m in event.sensorEvents: + + # filter unset events (bmx magn) + if m.version == 0: + continue + + key = (m.source.raw, m.which()) + values = getattr(m, m.which()) + if hasattr(values, 'v'): + values = values.v + values = np.atleast_1d(values) + + if key in sensor_values: + sensor_values[key].append(values) + else: + sensor_values[key] = [values] + + # Sanity check sensor values and counts + for sensor, stype in sensor_values: + + for s in ALL_SENSORS[sensor]: + if s.type != stype: + continue + + key = (sensor, s.type) + val_cnt = len(sensor_values[key]) + err_msg = f"Sensor {sensor} {s.type} got {val_cnt} measurements, expected {s.min_samples}" + assert val_cnt > s.min_samples, err_msg + + mean_norm = np.mean(np.linalg.norm(sensor_values[key], axis=1)) + err_msg = f"Sensor '{sensor} {s.type}' failed sanity checks {mean_norm} is not between {s.sanity_min} and {s.sanity_max}" + assert s.sanity_min <= mean_norm <= s.sanity_max, err_msg + + def test_sensor_verify_no_interrupts_after_stop(self): + + managed_processes["sensord"].start() + time.sleep(1) + + # check if the interrupts are enableds + with SMBus(SENSOR_BUS, force=True) as bus: + int1_ctrl_reg = bus.read_byte_data(I2C_ADDR_LSM, 0x0D) + assert int1_ctrl_reg == 3, "Interrupts not enabled!" + + # read /proc/interrupts to verify interrupts are received + state_one = get_proc_interrupts(LSM_INT_GPIO) + time.sleep(1) + state_two = get_proc_interrupts(LSM_INT_GPIO) + + assert state_one != state_two, "no Interrupts received after sensord start!" + + managed_processes["sensord"].stop() + + # check if the interrupts got disabled + with SMBus(SENSOR_BUS, force=True) as bus: + int1_ctrl_reg = bus.read_byte_data(I2C_ADDR_LSM, 0x0D) + assert int1_ctrl_reg == 0, "Interrupts not disabled!" + + # read /proc/interrupts to verify no more interrupts are received + state_one = get_proc_interrupts(LSM_INT_GPIO) + time.sleep(1) + state_two = get_proc_interrupts(LSM_INT_GPIO) + assert state_one == state_two, "Interrupts received after sensord stop!" + if __name__ == "__main__": unittest.main() + diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py index 340093b604..dd6b79e123 100644 --- a/system/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -462,6 +462,17 @@ class Tici(HardwareBase): sudo_write("N", "/sys/kernel/debug/msm_vidc/clock_scaling") sudo_write("Y", "/sys/kernel/debug/msm_vidc/disable_thermal_mitigation") + # *** unexport GPIO for sensors *** + # remove from /userspace/usr/comma/gpio.sh + sudo_write(str(GPIO.BMX055_ACCEL_INT), "/sys/class/gpio/unexport") + sudo_write(str(GPIO.BMX055_GYRO_INT), "/sys/class/gpio/unexport") + sudo_write(str(GPIO.BMX055_MAGN_INT), "/sys/class/gpio/unexport") + sudo_write(str(GPIO.LSM_INT), "/sys/class/gpio/unexport") + + # *** set /dev/gpiochip0 rights to make accessible by sensord + os.system("sudo chmod +r /dev/gpiochip0") + + def configure_modem(self): sim_id = self.get_sim_info().get('sim_id', '') diff --git a/system/hardware/tici/pins.py b/system/hardware/tici/pins.py index 61e528d304..fe31b9311d 100644 --- a/system/hardware/tici/pins.py +++ b/system/hardware/tici/pins.py @@ -19,3 +19,9 @@ class GPIO: CAM0_RSTN = 9 CAM1_RSTN = 7 CAM2_RSTN = 12 + + # Sensor interrupts + BMX055_ACCEL_INT = 21 + BMX055_GYRO_INT = 23 + BMX055_MAGN_INT = 87 + LSM_INT = 84 From ef767f633287445f7861eb5b82c5a17ab6325664 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 13 Sep 2022 13:54:33 +0800 Subject: [PATCH 079/152] MapPanel: refresh only when visible and destination changes (#25739) rebuild widgets only when mappanel is visible --- selfdrive/ui/qt/maps/map_settings.cc | 16 ++++++++++++---- selfdrive/ui/qt/maps/map_settings.h | 2 ++ 2 files changed, 14 insertions(+), 4 deletions(-) diff --git a/selfdrive/ui/qt/maps/map_settings.cc b/selfdrive/ui/qt/maps/map_settings.cc index d143b44e70..dd2ad04a7d 100644 --- a/selfdrive/ui/qt/maps/map_settings.cc +++ b/selfdrive/ui/qt/maps/map_settings.cc @@ -156,6 +156,7 @@ MapPanel::MapPanel(QWidget* parent) : QWidget(parent) { void MapPanel::showEvent(QShowEvent *event) { updateCurrentRoute(); + refresh(); } void MapPanel::clear() { @@ -184,18 +185,25 @@ void MapPanel::updateCurrentRoute() { } void MapPanel::parseResponse(const QString &response, bool success) { - stack->setCurrentIndex((uiState()->prime_type || success) ? 0 : 1); + if (!success) return; - if (!success) { - return; + cur_destinations = response; + if (isVisible()) { + refresh(); } +} + +void MapPanel::refresh() { + stack->setCurrentIndex(uiState()->prime_type ? 0 : 1); + if (cur_destinations == prev_destinations) return; - QJsonDocument doc = QJsonDocument::fromJson(response.trimmed().toUtf8()); + QJsonDocument doc = QJsonDocument::fromJson(cur_destinations.trimmed().toUtf8()); if (doc.isNull()) { qDebug() << "JSON Parse failed on navigation locations"; return; } + prev_destinations = cur_destinations; clear(); bool has_recents = false; diff --git a/selfdrive/ui/qt/maps/map_settings.h b/selfdrive/ui/qt/maps/map_settings.h index 962d127679..165673b7c1 100644 --- a/selfdrive/ui/qt/maps/map_settings.h +++ b/selfdrive/ui/qt/maps/map_settings.h @@ -23,8 +23,10 @@ public: private: void showEvent(QShowEvent *event) override; + void refresh(); Params params; + QString prev_destinations, cur_destinations; QStackedWidget *stack; QPushButton *home_button, *work_button; QLabel *home_address, *work_address; From 4d351427c5a46dab100078b7e9d0737bce046e40 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 13 Sep 2022 00:22:58 -0700 Subject: [PATCH 080/152] Consider regen properly in test_models (#25409) * Consider regen properly in test_models * bump panda * bump panda * can use the more interesting segment now * rm --- panda | 2 +- selfdrive/car/tests/routes.py | 2 +- selfdrive/car/tests/test_models.py | 3 ++- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/panda b/panda index 15eda6a7c9..788e0b5ac9 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 15eda6a7c9cf4b0c7b5a7bbde25fcab3ff0a98fc +Subproject commit 788e0b5ac944858fd9b3d2ea98e4049df0adb51b diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 635f43cc8d..9207859340 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -48,7 +48,7 @@ routes = [ CarTestRoute("aa20e335f61ba898|2019-02-05--16-59-04", GM.BUICK_REGAL), CarTestRoute("46460f0da08e621e|2021-10-26--07-21-46", GM.ESCALADE_ESV), CarTestRoute("c950e28c26b5b168|2018-05-30--22-03-41", GM.VOLT), - CarTestRoute("f08912a233c1584f|2022-08-11--18-02-41", GM.BOLT_EUV), + CarTestRoute("f08912a233c1584f|2022-08-11--18-02-41", GM.BOLT_EUV, segment=1), CarTestRoute("38aa7da107d5d252|2022-08-15--16-01-12", GM.SILVERADO), CarTestRoute("0e7a2ba168465df5|2020-10-18--14-14-22", HONDA.ACURA_RDX_3G), diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index fa07db92db..997a9bbec2 100755 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -243,7 +243,8 @@ class TestCarModelBase(unittest.TestCase): if CS.brakePressed and not self.safety.get_brake_pressed_prev(): if self.CP.carFingerprint in (HONDA.PILOT, HONDA.PASSPORT, HONDA.RIDGELINE) and CS.brake > 0.05: brake_pressed = False - checks['brakePressed'] += brake_pressed != self.safety.get_brake_pressed_prev() + safety_brake_pressed = self.safety.get_brake_pressed_prev() or self.safety.get_regen_braking_prev() + checks['brakePressed'] += brake_pressed != safety_brake_pressed if self.CP.pcmCruise: # On most pcmCruise cars, openpilot's state is always tied to the PCM's cruise state. From 7a6ab188bd1a27f2eefadac98d43731ae3ca30c4 Mon Sep 17 00:00:00 2001 From: Julian Pieles Date: Tue, 13 Sep 2022 10:06:11 +0200 Subject: [PATCH 081/152] Kia: add missing EU EV6 FW versions (#25709) * added fingerprint for european EV6 * missing version Co-authored-by: julian.pieles Co-authored-by: Shane Smiskol --- selfdrive/car/hyundai/values.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 4225826c1d..7fb8363a67 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1296,6 +1296,7 @@ FW_VERSIONS = { }, CAR.KIA_EV6: { (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00CV IEB \x03 101!\x10\x18 58520-CV100', b'\xf1\x8758520CV100\xf1\x00CV IEB \x02 101!\x10\x18 58520-CV100', ], (Ecu.eps, 0x7d4, None): [ @@ -1307,6 +1308,7 @@ FW_VERSIONS = { ], (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.05 99210-CV000 211027', + b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.05 99210-CV000 211027', ], }, CAR.IONIQ_5: { From 852af4d1f84ca17bb9ec0d0fe376077acf07b841 Mon Sep 17 00:00:00 2001 From: Robbe Derks Date: Tue, 13 Sep 2022 11:47:16 +0200 Subject: [PATCH 082/152] Update Tesla AP2 fingerprint (#25763) update fingerprint for v11 software Co-authored-by: Comma Device --- selfdrive/car/tesla/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/tesla/values.py b/selfdrive/car/tesla/values.py index 296169587a..030a368a11 100644 --- a/selfdrive/car/tesla/values.py +++ b/selfdrive/car/tesla/values.py @@ -22,7 +22,7 @@ CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { FINGERPRINTS = { CAR.AP2_MODELS: [ { - 1: 8, 3: 8, 14: 8, 21: 4, 69: 8, 109: 4, 257: 3, 264: 8, 277: 6, 280: 6, 293: 4, 296: 4, 309: 5, 325: 8, 328: 5, 336: 8, 341: 8, 360: 7, 373: 8, 389: 8, 415: 8, 513: 5, 516: 8, 518: 8, 520: 4, 522: 8, 524: 8, 526: 8, 532: 3, 536: 8, 537: 3, 538: 8, 542: 8, 551: 5, 552: 2, 556: 8, 558: 8, 568: 8, 569: 8, 574: 8, 576: 3, 577: 8, 582: 5, 583: 8, 584: 4, 585: 8, 590: 8, 601: 8, 606: 8, 608: 1, 622: 8, 627: 6, 638: 8, 641: 8, 643: 8, 692: 8, 693: 8, 695: 8, 696: 8, 697: 8, 699: 8, 700: 8, 701: 8, 702: 8, 703: 8, 704: 8, 708: 8, 709: 8, 710: 8, 711: 8, 712: 8, 728: 8, 744: 8, 760: 8, 772: 8, 775: 8, 776: 8, 777: 8, 778: 8, 782: 8, 788: 8, 791: 8, 792: 8, 796: 2, 797: 8, 798: 6, 799: 8, 804: 8, 805: 8, 807: 8, 808: 1, 811: 8, 812: 8, 813: 8, 814: 5, 815: 8, 820: 8, 823: 8, 824: 8, 829: 8, 830: 5, 836: 8, 840: 8, 845: 8, 846: 5, 848: 8, 852: 8, 853: 8, 856: 4, 857: 6, 861: 8, 862: 5, 872: 8, 876: 8, 877: 8, 879: 8, 880: 8, 882: 8, 884: 8, 888: 8, 893: 8, 894: 8, 901: 6, 904: 3, 905: 8, 906: 8, 908: 2, 909: 8, 910: 8, 912: 8, 920: 8, 921: 8, 925: 4, 926: 6, 936: 8, 941: 8, 949: 8, 952: 8, 953: 6, 968: 8, 969: 6, 970: 8, 971: 8, 977: 8, 984: 8, 987: 8, 990: 8, 1000: 8, 1001: 8, 1006: 8, 1007: 8, 1008: 8, 1010: 6, 1014: 1, 1015: 8, 1016: 8, 1017: 8, 1018: 8, 1020: 8, 1026: 8, 1028: 8, 1029: 8, 1030: 8, 1032: 1, 1033: 1, 1034: 8, 1048: 1, 1049: 8, 1061: 8, 1064: 8, 1065: 8, 1070: 8, 1080: 8, 1081: 8, 1097: 8, 1113: 8, 1129: 8, 1145: 8, 1160: 4, 1177: 8, 1281: 8, 1328: 8, 1329: 8, 1332: 8, 1335: 8, 1337: 8, 1353: 8, 1368: 8, 1412: 8, 1436: 8, 1476: 8, 1481: 8, 1497: 8, 1513: 8, 1519: 8, 1601: 8, 1605: 8, 1617: 8, 1621: 8, 1625: 8, 1665: 8, 1800: 4, 1804: 8, 1812: 8, 1815: 8, 1816: 8, 1824: 8, 1828: 8, 1831: 8, 1832: 8, 1840: 8, 1848: 8, 1864: 8, 1880: 8, 1892: 8, 1896: 8, 1912: 8, 1960: 8, 1992: 8, 2008: 3, 2015: 8, 2043: 5, 2045: 4 + 1: 8, 3: 8, 14: 8, 21: 4, 69: 8, 109: 4, 257: 3, 264: 8, 277: 6, 280: 6, 293: 4, 296: 4, 309: 5, 325: 8, 328: 5, 336: 8, 341: 8, 360: 7, 373: 8, 389: 8, 415: 8, 513: 5, 516: 8, 518: 8, 520: 4, 522: 8, 524: 8, 526: 8, 532: 3, 536: 8, 537: 3, 538: 8, 542: 8, 551: 5, 552: 2, 556: 8, 558: 8, 568: 8, 569: 8, 574: 8, 576: 3, 577: 8, 582: 5, 583: 8, 584: 4, 585: 8, 590: 8, 601: 8, 606: 8, 608: 1, 622: 8, 627: 6, 638: 8, 641: 8, 643: 8, 692: 8, 693: 8, 695: 8, 696: 8, 697: 8, 699: 8, 700: 8, 701: 8, 702: 8, 703: 8, 704: 8, 708: 8, 709: 8, 710: 8, 711: 8, 712: 8, 728: 8, 744: 8, 760: 8, 772: 8, 775: 8, 776: 8, 777: 8, 778: 8, 782: 8, 788: 8, 791: 8, 792: 8, 796: 2, 797: 8, 798: 6, 799: 8, 804: 8, 805: 8, 807: 8, 808: 1, 811: 8, 812: 8, 813: 8, 814: 5, 815: 8, 820: 8, 823: 8, 824: 8, 829: 8, 830: 5, 836: 8, 840: 8, 845: 8, 846: 5, 848: 8, 852: 8, 853: 8, 856: 4, 857: 6, 861: 8, 862: 5, 872: 8, 876: 8, 877: 8, 879: 8, 880: 8, 882: 8, 884: 8, 888: 8, 893: 8, 894: 8, 901: 6, 904: 3, 905: 8, 906: 8, 908: 2, 909: 8, 910: 8, 912: 8, 920: 8, 921: 8, 925: 4, 926: 6, 936: 8, 941: 8, 949: 8, 952: 8, 953: 6, 968: 8, 969: 7, 970: 8, 971: 8, 977: 8, 984: 8, 987: 8, 990: 8, 1000: 8, 1001: 8, 1006: 8, 1007: 8, 1008: 8, 1010: 6, 1014: 1, 1015: 8, 1016: 8, 1017: 8, 1018: 8, 1020: 8, 1026: 8, 1028: 8, 1029: 8, 1030: 8, 1032: 1, 1033: 1, 1034: 8, 1048: 1, 1049: 8, 1061: 8, 1064: 8, 1065: 8, 1070: 8, 1080: 8, 1081: 8, 1097: 8, 1113: 8, 1129: 8, 1145: 8, 1160: 4, 1177: 8, 1281: 8, 1328: 8, 1329: 8, 1332: 8, 1335: 8, 1337: 8, 1353: 8, 1368: 8, 1412: 8, 1436: 8, 1476: 8, 1481: 8, 1497: 8, 1513: 8, 1519: 8, 1601: 8, 1605: 8, 1617: 8, 1621: 8, 1625: 8, 1665: 8, 1792: 8, 1798: 8, 1800: 4, 1804: 8, 1812: 8, 1815: 8, 1816: 8, 1824: 8, 1825: 8, 1828: 8, 1831: 8, 1832: 8, 1840: 8, 1842: 8, 1848: 8, 1864: 8, 1872: 8, 1880: 8, 1888: 8, 1892: 8, 1896: 8, 1912: 8, 1937: 8, 1953: 8, 1960: 8, 1968: 8, 1992: 8, 2001: 8, 2008: 3, 2015: 8, 2016: 8, 2043: 5, 2045: 4 }, ], CAR.AP1_MODELS: [ From 27e1ec8fd31192696cef70e4c6a98cbe7c3ba15a Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 13 Sep 2022 18:02:13 +0800 Subject: [PATCH 083/152] ui: multilang date (#25741) * multilang date * update translations * add language to uistate * update translations * use it here too Co-authored-by: sshane --- selfdrive/ui/qt/home.cc | 4 +++- selfdrive/ui/qt/offroad/settings.cc | 3 +-- selfdrive/ui/translations/main_ja.ts | 4 ++-- selfdrive/ui/translations/main_ko.ts | 4 ++-- selfdrive/ui/translations/main_pt-BR.ts | 4 ++-- selfdrive/ui/translations/main_zh-CHS.ts | 4 ++-- selfdrive/ui/translations/main_zh-CHT.ts | 4 ++-- selfdrive/ui/ui.cc | 1 + selfdrive/ui/ui.h | 1 + 9 files changed, 16 insertions(+), 13 deletions(-) diff --git a/selfdrive/ui/qt/home.cc b/selfdrive/ui/qt/home.cc index 0edeb252b7..435ba9056a 100644 --- a/selfdrive/ui/qt/home.cc +++ b/selfdrive/ui/qt/home.cc @@ -183,7 +183,9 @@ void OffroadHome::hideEvent(QHideEvent *event) { } void OffroadHome::refresh() { - date->setText(QDateTime::currentDateTime().toString("dddd, MMMM d")); + QString locale_name = QString(uiState()->language).replace("main_", ""); + QString dateString = QLocale(locale_name).toString(QDateTime::currentDateTime(), "dddd, MMMM d"); + date->setText(dateString); bool updateAvailable = update_widget->refresh(); int alerts = alerts_widget->refresh(); diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index e5e5634545..7a5a40c193 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -189,8 +189,7 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { auto translateBtn = new ButtonControl(tr("Change Language"), tr("CHANGE"), ""); connect(translateBtn, &ButtonControl::clicked, [=]() { QMap langs = getSupportedLanguages(); - QString currentLang = QString::fromStdString(Params().get("LanguageSetting")); - QString selection = MultiOptionDialog::getSelection(tr("Select a language"), langs.keys(), langs.key(currentLang), this); + QString selection = MultiOptionDialog::getSelection(tr("Select a language"), langs.keys(), langs.key(uiState()->language), this); if (!selection.isEmpty()) { // put language setting, exit Qt UI, and trigger fast restart Params().put("LanguageSetting", langs[selection].toStdString()); diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index a0b2a99866..9be6658d19 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -526,7 +526,7 @@ location set 更新 - + ALERTS 警告 @@ -539,7 +539,7 @@ location set PairingPopup - + Pair your device to your comma account デバイスと comma アカウントを連携する diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 5d7df2162e..3e329a72ab 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -526,7 +526,7 @@ location set 업데이트 - + ALERTS 알림 @@ -539,7 +539,7 @@ location set PairingPopup - + Pair your device to your comma account 장치를 콤마 계정과 페어링합니다 diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 2b3acb369f..b729678a2c 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -527,7 +527,7 @@ trabalho definido ATUALIZAÇÃO - + ALERTS ALERTAS @@ -540,7 +540,7 @@ trabalho definido PairingPopup - + Pair your device to your comma account Pareie seu dispositivo à sua conta comma diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index a00bf28303..606e70726f 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -524,7 +524,7 @@ location set 更新 - + ALERTS 警报 @@ -537,7 +537,7 @@ location set PairingPopup - + Pair your device to your comma account 将您的设备与comma账号配对 diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 52bd301364..b5b737ca25 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -526,7 +526,7 @@ location set 更新 - + ALERTS 提醒 @@ -539,7 +539,7 @@ location set PairingPopup - + Pair your device to your comma account 將設備與您的 comma 帳號配對 diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index b208945fe2..2722b68f17 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -236,6 +236,7 @@ UIState::UIState(QObject *parent) : QObject(parent) { Params params; wide_camera = params.getBool("WideCameraOnly"); prime_type = std::atoi(params.get("PrimeType").c_str()); + language = QString::fromStdString(params.get("LanguageSetting")); // update timer timer = new QTimer(this); diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index 08ae16ab24..b4ec900eef 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -127,6 +127,7 @@ public: bool awake; int prime_type = 0; + QString language; QTransform car_space_transform; bool wide_camera; From 13d9a77b93e083d3a35d7f4f2ea755b880e4a1ed Mon Sep 17 00:00:00 2001 From: Robbe Derks Date: Tue, 13 Sep 2022 15:54:15 +0200 Subject: [PATCH 084/152] Add option to disable fan control (#25690) add option for external fan control Co-authored-by: Comma Device --- selfdrive/boardd/boardd.cc | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 47bff1c5b6..5ff6d56e69 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -468,7 +468,7 @@ void panda_state_thread(PubMaster *pm, std::vector pandas, bool spoofin } -void peripheral_control_thread(Panda *panda) { +void peripheral_control_thread(Panda *panda, bool no_fan_control) { util::set_thread_name("boardd_peripheral_control"); SubMaster sm({"deviceState", "driverCameraState"}); @@ -488,7 +488,7 @@ void peripheral_control_thread(Panda *panda) { // Other pandas don't have fan/IR to control if (panda->hw_type != cereal::PandaState::PandaType::UNO && panda->hw_type != cereal::PandaState::PandaType::DOS) continue; - if (sm.updated("deviceState")) { + if (sm.updated("deviceState") && !no_fan_control) { // Fan speed uint16_t fan_speed = sm["deviceState"].getDeviceState().getFanSpeedPercentDesired(); if (fan_speed != prev_fan_speed || cnt % 100 == 0) { @@ -496,6 +496,7 @@ void peripheral_control_thread(Panda *panda) { prev_fan_speed = fan_speed; } } + if (sm.updated("driverCameraState")) { auto event = sm["driverCameraState"]; int cur_integ_lines = event.getDriverCameraState().getIntegLines(); @@ -568,7 +569,7 @@ void boardd_main_thread(std::vector serials) { std::vector threads; threads.emplace_back(panda_state_thread, &pm, pandas, getenv("STARTED") != nullptr); - threads.emplace_back(peripheral_control_thread, peripheral_panda); + threads.emplace_back(peripheral_control_thread, peripheral_panda, getenv("NO_FAN_CONTROL") != nullptr); threads.emplace_back(can_send_thread, pandas, getenv("FAKESEND") != nullptr); threads.emplace_back(can_recv_thread, pandas); From aac84e09adc4b2d6ede6c0da69487e2a5154fc5b Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Tue, 13 Sep 2022 15:04:47 -0500 Subject: [PATCH 085/152] VW MQB: Add FW for 2016 Audi S3 (#25764) --- selfdrive/car/volkswagen/values.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 05994c0100..7c55736362 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -773,6 +773,7 @@ FW_VERSIONS = { b'\xf1\x875G0906259L \xf1\x890002', b'\xf1\x875G0906259Q \xf1\x890002', b'\xf1\x878V0906259F \xf1\x890002', + b'\xf1\x878V0906259J \xf1\x890002', b'\xf1\x878V0906259K \xf1\x890001', b'\xf1\x878V0906264B \xf1\x890003', b'\xf1\x878V0907115B \xf1\x890007', @@ -791,6 +792,7 @@ FW_VERSIONS = { b'\xf1\x870DD300046F \xf1\x891602', b'\xf1\x870DD300046G \xf1\x891601', b'\xf1\x870DL300012E \xf1\x892012', + b'\xf1\x870GC300011 \xf1\x890403', b'\xf1\x870GC300013M \xf1\x892402', b'\xf1\x870GC300042J \xf1\x891402', ], @@ -798,6 +800,7 @@ FW_VERSIONS = { b'\xf1\x875Q0959655AB\xf1\x890388\xf1\x82\0211111001111111206110412111321139114', b'\xf1\x875Q0959655AM\xf1\x890315\xf1\x82\x1311111111111111311411011231129321212100', b'\xf1\x875Q0959655AM\xf1\x890318\xf1\x82\x1311111111111112311411011531159321212100', + b'\xf1\x875Q0959655AR\xf1\x890315\xf1\x82\x1311110011131115311211012331239321212100', b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1311110011131100311111011731179321342100', b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--241115141112221291163221', b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\023111112111111--171115141112221291163221', @@ -808,6 +811,7 @@ FW_VERSIONS = { ], (Ecu.eps, 0x712, None): [ b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\00566G0HA14A1', + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G01A16A1', b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0HA16A1', b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571G0JA14A1', b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521G0G809A1', From d3795c12272848ca5de8585162856e0db449ea8c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 13 Sep 2022 14:14:22 -0700 Subject: [PATCH 086/152] Chrysler: match panda standstill check (#25762) * bump panda * bump panda to master * flip this around * don't forget the body! --- panda | 2 +- selfdrive/car/tests/test_models.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/panda b/panda index 788e0b5ac9..19983f13b3 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 788e0b5ac944858fd9b3d2ea98e4049df0adb51b +Subproject commit 19983f13b37518298a3c282d5069c090b68f6864 diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 997a9bbec2..50370f0797 100755 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -234,7 +234,7 @@ class TestCarModelBase(unittest.TestCase): checks['gasPressed'] += CS.gasPressed != self.safety.get_gas_pressed_prev() checks['cruiseState'] += CS.cruiseState.enabled and not CS.cruiseState.available - if self.CP.carName in ("honda", "toyota"): + if self.CP.carName not in ("hyundai", "volkswagen", "subaru", "gm", "body"): # TODO: fix standstill mismatches for other makes checks['standstill'] += CS.standstill == self.safety.get_vehicle_moving() From 4effa35ef5fdc7dde8777b695e8f3546c559a974 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 13 Sep 2022 14:38:06 -0700 Subject: [PATCH 087/152] Chrysler: query FW versions on bus 0 (#25760) * try bus 0! * remove the whitelists * no gateway --- selfdrive/car/chrysler/values.py | 15 ++++----------- 1 file changed, 4 insertions(+), 11 deletions(-) diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 3b3fc6e558..d4ac9f6f00 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -149,18 +149,21 @@ FW_QUERY_CONFIG = FwQueryConfig( Request( [CHRYSLER_VERSION_REQUEST], [CHRYSLER_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.srs, Ecu.gateway, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter], + whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.srs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter], rx_offset=CHRYSLER_RX_OFFSET, + bus=0, ), Request( [CHRYSLER_VERSION_REQUEST], [CHRYSLER_VERSION_RESPONSE], whitelist_ecus=[Ecu.abs, Ecu.hcp, Ecu.engine, Ecu.transmission], + bus=0, ), Request( [CHRYSLER_SOFTWARE_VERSION_REQUEST], [CHRYSLER_SOFTWARE_VERSION_RESPONSE], whitelist_ecus=[Ecu.engine, Ecu.transmission], + bus=0, ), ], ) @@ -223,12 +226,6 @@ FW_VERSIONS = { b'68540431AB', b'68484467AC', ], - (Ecu.gateway, 0x18DACBF1, None): [ - b'68402660AB', - b'68445283AB', - b'68533631AB', - b'68500483AB', - ], }, CAR.RAM_HD: { @@ -260,10 +257,6 @@ FW_VERSIONS = { b'M2370131MB', b'M2421132MB', ], - (Ecu.gateway, 0x18DACBF1, None): [ - b'68488419AB', - b'68535476AB', - ], }, } From c64230c4a8681d0ba2d8b18128f42cbd76d85091 Mon Sep 17 00:00:00 2001 From: Kurt Nistelberger Date: Tue, 13 Sep 2022 16:15:33 -0700 Subject: [PATCH 088/152] make test_sensord executeable --- selfdrive/sensord/tests/test_sensord.py | 0 1 file changed, 0 insertions(+), 0 deletions(-) mode change 100644 => 100755 selfdrive/sensord/tests/test_sensord.py diff --git a/selfdrive/sensord/tests/test_sensord.py b/selfdrive/sensord/tests/test_sensord.py old mode 100644 new mode 100755 From 467bbffa0fe50587eb8fb8d98cfe2df93461ef1d Mon Sep 17 00:00:00 2001 From: Kurt Nistelberger Date: Tue, 13 Sep 2022 16:45:12 -0700 Subject: [PATCH 089/152] add hardware init to sensor tests --- selfdrive/sensord/tests/test_sensord.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/sensord/tests/test_sensord.py b/selfdrive/sensord/tests/test_sensord.py index 7abaf9ca35..6cb2fa9e68 100755 --- a/selfdrive/sensord/tests/test_sensord.py +++ b/selfdrive/sensord/tests/test_sensord.py @@ -8,7 +8,7 @@ from smbus2 import SMBus import cereal.messaging as messaging from cereal import log -from system.hardware import TICI +from system.hardware import TICI, HARDWARE from selfdrive.test.helpers import with_processes from selfdrive.manager.process_config import managed_processes @@ -113,6 +113,9 @@ class TestSensord(unittest.TestCase): if not TICI: raise unittest.SkipTest + # make sure gpiochip0 is readable + HARDWARE.initialize_hardware() + @with_processes(['sensord']) def test_sensors_present(self): # verify correct sensors configuration From 3f34a7082afce611391369f881756fabc6a7e1e7 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 13 Sep 2022 20:35:16 -0700 Subject: [PATCH 090/152] controlsd: fix regen init for multi-panda setups --- selfdrive/controls/controlsd.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 3054b020e1..569c12e3d6 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -215,7 +215,7 @@ class Controls: controls_state = log.ControlsState.from_bytes(controls_state) self.v_cruise_kph = controls_state.vCruise - if self.sm['pandaStates'][0].controlsAllowed: + if any(ps.controlsAllowed for ps in self.sm['pandaStates']): self.state = State.enabled def update_events(self, CS): From 98c843bfb425bb1dd44f99715f81fa7d327a77e7 Mon Sep 17 00:00:00 2001 From: Kurt Nistelberger Date: Tue, 13 Sep 2022 22:28:00 -0700 Subject: [PATCH 091/152] sensord: increase cpu usage in onroad test (#25773) Co-authored-by: Kurt Nistelberger --- selfdrive/test/test_onroad.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index c5fc0395d3..55e1ef161a 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -29,7 +29,7 @@ PROCS = { "selfdrive.controls.plannerd": 11.7, "./_ui": 19.2, "selfdrive.locationd.paramsd": 9.0, - "./_sensord": 6.17, + "./_sensord": 12.0, "selfdrive.controls.radard": 4.5, "./_modeld": 4.48, "./boardd": 3.63, From 3058437dd15896e328f8ddf8386683479a1f9493 Mon Sep 17 00:00:00 2001 From: Kurt Nistelberger Date: Tue, 13 Sep 2022 22:29:55 -0700 Subject: [PATCH 092/152] Sensor tests speedup (#25776) * speed up sensor test * remove sensord dependency * address comments Co-authored-by: Kurt Nistelberger --- selfdrive/sensord/tests/test_sensord.py | 22 +++++++++------------- 1 file changed, 9 insertions(+), 13 deletions(-) diff --git a/selfdrive/sensord/tests/test_sensord.py b/selfdrive/sensord/tests/test_sensord.py index 6cb2fa9e68..84582518fd 100755 --- a/selfdrive/sensord/tests/test_sensord.py +++ b/selfdrive/sensord/tests/test_sensord.py @@ -116,13 +116,16 @@ class TestSensord(unittest.TestCase): # make sure gpiochip0 is readable HARDWARE.initialize_hardware() - @with_processes(['sensord']) + # read initial sensor values every test case can use + managed_processes["sensord"].start() + cls.events = read_sensor_events(5) + managed_processes["sensord"].stop() + def test_sensors_present(self): # verify correct sensors configuration - events = read_sensor_events(10) seen = set() - for event in events: + for event in self.events: for measurement in event.sensorEvents: # filter unset events (bmx magn) if measurement.version == 0: @@ -131,13 +134,11 @@ class TestSensord(unittest.TestCase): self.assertIn(seen, SENSOR_CONFIGURATIONS) - @with_processes(['sensord']) def test_lsm6ds3_100Hz(self): # verify measurements are sampled and published at a 100Hz rate - events = read_sensor_events(3) # 3sec (about 300 measurements) data_points = set() - for event in events: + for event in self.events: for measurement in event.sensorEvents: # skip lsm6ds3 temperature measurements @@ -162,13 +163,11 @@ class TestSensord(unittest.TestCase): stddev = np.std(tdiffs) assert stddev < 1.5*10**6, f"Standard-dev to big {stddev}" - @with_processes(['sensord']) def test_events_check(self): # verify if all sensors produce events - events = read_sensor_events(3) sensor_events = dict() - for event in events: + for event in self.events: for measurement in event.sensorEvents: # filter unset events (bmx magn) @@ -184,13 +183,11 @@ class TestSensord(unittest.TestCase): err_msg = f"Sensor {s}: 200 < {sensor_events[s]}" assert sensor_events[s] > 200, err_msg - @with_processes(['sensord']) def test_logmonottime_timestamp_diff(self): # ensure diff between the message logMonotime and sample timestamp is small - events = read_sensor_events(3) tdiffs = list() - for event in events: + for event in self.events: for measurement in event.sensorEvents: # filter unset events (bmx magn) @@ -289,4 +286,3 @@ class TestSensord(unittest.TestCase): if __name__ == "__main__": unittest.main() - From 992707c1724ab0047ddd6e230b82e47ae51b25ed Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 13 Sep 2022 23:20:45 -0700 Subject: [PATCH 093/152] controls: enter overriding state for steering override (#25617) * lateral overriding is overriding * Update test * remove * also could do something like this and only have one OVERRIDE ET * Revert "also could do something like this and only have one OVERRIDE ET" This reverts commit 5c381641c08961676a56a9718fbdaa84989ac249. * full names * bump cereal * test every event type * update refs --- cereal | 2 +- selfdrive/car/interfaces.py | 2 + selfdrive/controls/controlsd.py | 12 ++--- selfdrive/controls/lib/events.py | 13 ++++- .../controls/tests/test_state_machine.py | 50 ++++++++++--------- selfdrive/test/process_replay/ref_commit | 2 +- 6 files changed, 48 insertions(+), 33 deletions(-) diff --git a/cereal b/cereal index 2335f98bbe..f363cc13c6 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 2335f98bbe628ec6fde92c8d929ecaf373b125af +Subproject commit f363cc13c67d286f87606f35f91952927d1c2d4d diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index a33560cd0e..1614003e87 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -215,6 +215,8 @@ class CarInterfaceBase(ABC): events.add(EventName.parkBrake) if cs_out.accFaulted: events.add(EventName.accFaulted) + if cs_out.steeringPressed: + events.add(EventName.steerOverride) # Handle button presses events.events.extend(create_button_enable_events(cs_out.buttonEvents, pcm_cruise=self.CP.pcmCruise)) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 569c12e3d6..3087535291 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -508,9 +508,9 @@ class Controls: self.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) self.current_alert_types.append(ET.SOFT_DISABLE) - elif self.events.any(ET.OVERRIDE): + elif self.events.any(ET.OVERRIDE_LATERAL) or self.events.any(ET.OVERRIDE_LONGITUDINAL): self.state = State.overriding - self.current_alert_types.append(ET.OVERRIDE) + self.current_alert_types += [ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL] # SOFT DISABLING elif self.state == State.softDisabling: @@ -540,10 +540,10 @@ class Controls: self.state = State.softDisabling self.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) self.current_alert_types.append(ET.SOFT_DISABLE) - elif not self.events.any(ET.OVERRIDE): + elif not (self.events.any(ET.OVERRIDE_LATERAL) or self.events.any(ET.OVERRIDE_LONGITUDINAL)): self.state = State.enabled else: - self.current_alert_types.append(ET.OVERRIDE) + self.current_alert_types += [ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL] # DISABLED elif self.state == State.disabled: @@ -554,7 +554,7 @@ class Controls: else: if self.events.any(ET.PRE_ENABLE): self.state = State.preEnabled - elif self.events.any(ET.OVERRIDE): + elif self.events.any(ET.OVERRIDE_LATERAL) or self.events.any(ET.OVERRIDE_LONGITUDINAL): self.state = State.overriding else: self.state = State.enabled @@ -586,7 +586,7 @@ class Controls: # Check which actuators can be enabled CC.latActive = self.active and not CS.steerFaultTemporary and not CS.steerFaultPermanent and \ CS.vEgo > self.CP.minSteerSpeed and not CS.standstill - CC.longActive = self.active and not self.events.any(ET.OVERRIDE) and self.CP.openpilotLongitudinalControl + CC.longActive = self.active and not self.events.any(ET.OVERRIDE_LONGITUDINAL) and self.CP.openpilotLongitudinalControl actuators = CC.actuators actuators.longControlState = self.LoC.long_control_state diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 5139ead84b..91f1748ecb 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -31,7 +31,8 @@ class Priority(IntEnum): class ET: ENABLE = 'enable' PRE_ENABLE = 'preEnable' - OVERRIDE = 'override' + OVERRIDE_LATERAL = 'overrideLateral' + OVERRIDE_LONGITUDINAL = 'overrideLongitudinal' NO_ENTRY = 'noEntry' WARNING = 'warning' USER_DISABLE = 'userDisable' @@ -623,7 +624,15 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { }, EventName.gasPressedOverride: { - ET.OVERRIDE: Alert( + ET.OVERRIDE_LONGITUDINAL: Alert( + "", + "", + AlertStatus.normal, AlertSize.none, + Priority.LOWEST, VisualAlert.none, AudibleAlert.none, .1), + }, + + EventName.steerOverride: { + ET.OVERRIDE_LATERAL: Alert( "", "", AlertStatus.normal, AlertSize.none, diff --git a/selfdrive/controls/tests/test_state_machine.py b/selfdrive/controls/tests/test_state_machine.py index 244c56687c..36535dfdaf 100755 --- a/selfdrive/controls/tests/test_state_machine.py +++ b/selfdrive/controls/tests/test_state_machine.py @@ -11,11 +11,11 @@ from selfdrive.controls.lib.events import Events, ET, Alert, Priority, AlertSize State = log.ControlsState.OpenpilotState # The event types that maintain the current state -MAINTAIN_STATES = {State.enabled: None, State.disabled: None, State.softDisabling: ET.SOFT_DISABLE, - State.preEnabled: ET.PRE_ENABLE, State.overriding: ET.OVERRIDE} +MAINTAIN_STATES = {State.enabled: (None,), State.disabled: (None,), State.softDisabling: (ET.SOFT_DISABLE,), + State.preEnabled: (ET.PRE_ENABLE,), State.overriding: (ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL)} ALL_STATES = tuple(State.schema.enumerants.values()) # The event types checked in DISABLED section of state machine -ENABLE_EVENT_TYPES = (ET.ENABLE, ET.PRE_ENABLE, ET.OVERRIDE) +ENABLE_EVENT_TYPES = (ET.ENABLE, ET.PRE_ENABLE, ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL) def make_event(event_types): @@ -41,29 +41,32 @@ class TestStateMachine(unittest.TestCase): def test_immediate_disable(self): for state in ALL_STATES: - self.controlsd.events.add(make_event([MAINTAIN_STATES[state], ET.IMMEDIATE_DISABLE])) - self.controlsd.state = state - self.controlsd.state_transition(self.CS) - self.assertEqual(State.disabled, self.controlsd.state) - self.controlsd.events.clear() + for et in MAINTAIN_STATES[state]: + self.controlsd.events.add(make_event([et, ET.IMMEDIATE_DISABLE])) + self.controlsd.state = state + self.controlsd.state_transition(self.CS) + self.assertEqual(State.disabled, self.controlsd.state) + self.controlsd.events.clear() def test_user_disable(self): for state in ALL_STATES: - self.controlsd.events.add(make_event([MAINTAIN_STATES[state], ET.USER_DISABLE])) - self.controlsd.state = state - self.controlsd.state_transition(self.CS) - self.assertEqual(State.disabled, self.controlsd.state) - self.controlsd.events.clear() + for et in MAINTAIN_STATES[state]: + self.controlsd.events.add(make_event([et, ET.USER_DISABLE])) + self.controlsd.state = state + self.controlsd.state_transition(self.CS) + self.assertEqual(State.disabled, self.controlsd.state) + self.controlsd.events.clear() def test_soft_disable(self): for state in ALL_STATES: if state == State.preEnabled: # preEnabled considers NO_ENTRY instead continue - self.controlsd.events.add(make_event([MAINTAIN_STATES[state], ET.SOFT_DISABLE])) - self.controlsd.state = state - self.controlsd.state_transition(self.CS) - self.assertEqual(self.controlsd.state, State.disabled if state == State.disabled else State.softDisabling) - self.controlsd.events.clear() + for et in MAINTAIN_STATES[state]: + self.controlsd.events.add(make_event([et, ET.SOFT_DISABLE])) + self.controlsd.state = state + self.controlsd.state_transition(self.CS) + self.assertEqual(self.controlsd.state, State.disabled if state == State.disabled else State.softDisabling) + self.controlsd.events.clear() def test_soft_disable_timer(self): self.controlsd.state = State.enabled @@ -93,11 +96,12 @@ class TestStateMachine(unittest.TestCase): def test_maintain_states(self): # Given current state's event type, we should maintain state for state in ALL_STATES: - self.controlsd.state = state - self.controlsd.events.add(make_event([MAINTAIN_STATES[state]])) - self.controlsd.state_transition(self.CS) - self.assertEqual(self.controlsd.state, state) - self.controlsd.events.clear() + for et in MAINTAIN_STATES[state]: + self.controlsd.state = state + self.controlsd.events.add(make_event([et])) + self.controlsd.state_transition(self.CS) + self.assertEqual(self.controlsd.state, state) + self.controlsd.events.clear() if __name__ == "__main__": diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index f46f39dd27..00a6789eaf 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -48db2dee177706285226d1287912e191f1699865 +260bd1a7240221e75a20d547f68e8d1217f9f29e \ No newline at end of file From ef26abcf658b9fe13f939c43a31f57bd6ae25232 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 13 Sep 2022 23:34:51 -0700 Subject: [PATCH 094/152] ui: support ego speed hysteresis (#25702) * toyota: match set speed from dash * Use unit bit * Use RSA2 * flip this * Universal unit signal, set vEgoCluster * remove this and bump opendbc * detect if car interface sets cluster fields * revert * needs to be cp * UI_SPEED is actually always in kph? * forgot to actually convert it * same in onroad * try conv factor only for imperial * Seems like UI_SPEED is not the UI speed at all * the dash might floor it * same openpilot behavior * bump * ego speed factor is dynamic across speeds, handle Lexus exceptions with diff msg * remove test, bump opendbc * secret formula * secret formula v2 * 1.03 is sufficient * try short press * bump opendbc * surely this can be cleaned up surely this can be cleaned up * use filter * redo factors * try UI_SPEED again with a factor try UI_SPEED again with a factor * dash applies hysteresis to speed. this matches pretty well, but not exactly * make hysteresis generic * clean up * revert this * try this * read from fake params * should be mostly good for imperial now * revert * revert * remove toyota stuff * common function for everyone * rm line * fix * an example with Toyota * use CS.out * one mph * 1 kph * cmt * remove cmt * abs it Co-authored-by: Willem Melching --- selfdrive/car/__init__.py | 8 ++++++++ selfdrive/car/interfaces.py | 10 +++++++++- 2 files changed, 17 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py index f2d198338d..8ff39ceaeb 100644 --- a/selfdrive/car/__init__.py +++ b/selfdrive/car/__init__.py @@ -12,6 +12,14 @@ ButtonType = car.CarState.ButtonEvent.Type EventName = car.CarEvent.EventName +def apply_hysteresis(val: float, val_steady: float, hyst_gap: float) -> float: + if val > val_steady + hyst_gap: + val_steady = val - hyst_gap + elif val < val_steady - hyst_gap: + val_steady = val + hyst_gap + return val_steady + + def create_button_event(cur_but: int, prev_but: int, buttons_dict: Dict[int, capnp.lib.capnp._EnumModule], unpressed: int = 0) -> capnp.lib.capnp._DynamicStructBuilder: if cur_but != unpressed: diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 1614003e87..bc6c31e12c 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -9,7 +9,7 @@ from common.basedir import BASEDIR from common.conversions import Conversions as CV from common.kalman.simple_kalman import KF1D from common.realtime import DT_CTRL -from selfdrive.car import create_button_enable_events, gen_empty_fingerprint +from selfdrive.car import apply_hysteresis, create_button_enable_events, gen_empty_fingerprint from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX from selfdrive.controls.lib.events import Events from selfdrive.controls.lib.vehicle_model import VehicleModel @@ -171,6 +171,12 @@ class CarInterfaceBase(ABC): else: self.v_ego_cluster_seen = True + # Many cars apply hysteresis to the ego dash speed + if self.CS is not None: + ret.vEgoCluster = apply_hysteresis(ret.vEgoCluster, self.CS.out.vEgoCluster, self.CS.cluster_speed_hyst_gap) + if abs(ret.vEgo) < self.CS.cluster_min_speed: + ret.vEgoCluster = 0.0 + if ret.cruiseState.speedCluster == 0: ret.cruiseState.speedCluster = ret.cruiseState.speed @@ -272,6 +278,8 @@ class CarStateBase(ABC): self.right_blinker_cnt = 0 self.left_blinker_prev = False self.right_blinker_prev = False + self.cluster_speed_hyst_gap = 0.0 + self.cluster_min_speed = 0.0 # min speed before dropping to 0 # Q = np.matrix([[0.0, 0.0], [0.0, 100.0]]) # R = 0.3 From 1b0f202d7b2be6a4c1f8a18499207170b0fd78ed Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 14 Sep 2022 16:58:10 +0800 Subject: [PATCH 095/152] ui: prev_frame_id should be uint32_t (#25781) uint32_t --- selfdrive/ui/qt/widgets/cameraview.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index 016522b05c..081483b649 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -78,7 +78,7 @@ protected: std::deque> frames; uint32_t draw_frame_id = 0; - int prev_frame_id = 0; + uint32_t prev_frame_id = 0; protected slots: void vipcConnected(VisionIpcClient *vipc_client); From 05e80cf4fbbccd602c0f3feb43927ae86ba550c9 Mon Sep 17 00:00:00 2001 From: Robbe Derks Date: Wed, 14 Sep 2022 17:35:48 +0200 Subject: [PATCH 096/152] Tesla AP2 fingerprint update: forgot one message (#25783) --- selfdrive/car/tesla/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/tesla/values.py b/selfdrive/car/tesla/values.py index 030a368a11..7648a4a504 100644 --- a/selfdrive/car/tesla/values.py +++ b/selfdrive/car/tesla/values.py @@ -22,7 +22,7 @@ CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { FINGERPRINTS = { CAR.AP2_MODELS: [ { - 1: 8, 3: 8, 14: 8, 21: 4, 69: 8, 109: 4, 257: 3, 264: 8, 277: 6, 280: 6, 293: 4, 296: 4, 309: 5, 325: 8, 328: 5, 336: 8, 341: 8, 360: 7, 373: 8, 389: 8, 415: 8, 513: 5, 516: 8, 518: 8, 520: 4, 522: 8, 524: 8, 526: 8, 532: 3, 536: 8, 537: 3, 538: 8, 542: 8, 551: 5, 552: 2, 556: 8, 558: 8, 568: 8, 569: 8, 574: 8, 576: 3, 577: 8, 582: 5, 583: 8, 584: 4, 585: 8, 590: 8, 601: 8, 606: 8, 608: 1, 622: 8, 627: 6, 638: 8, 641: 8, 643: 8, 692: 8, 693: 8, 695: 8, 696: 8, 697: 8, 699: 8, 700: 8, 701: 8, 702: 8, 703: 8, 704: 8, 708: 8, 709: 8, 710: 8, 711: 8, 712: 8, 728: 8, 744: 8, 760: 8, 772: 8, 775: 8, 776: 8, 777: 8, 778: 8, 782: 8, 788: 8, 791: 8, 792: 8, 796: 2, 797: 8, 798: 6, 799: 8, 804: 8, 805: 8, 807: 8, 808: 1, 811: 8, 812: 8, 813: 8, 814: 5, 815: 8, 820: 8, 823: 8, 824: 8, 829: 8, 830: 5, 836: 8, 840: 8, 845: 8, 846: 5, 848: 8, 852: 8, 853: 8, 856: 4, 857: 6, 861: 8, 862: 5, 872: 8, 876: 8, 877: 8, 879: 8, 880: 8, 882: 8, 884: 8, 888: 8, 893: 8, 894: 8, 901: 6, 904: 3, 905: 8, 906: 8, 908: 2, 909: 8, 910: 8, 912: 8, 920: 8, 921: 8, 925: 4, 926: 6, 936: 8, 941: 8, 949: 8, 952: 8, 953: 6, 968: 8, 969: 7, 970: 8, 971: 8, 977: 8, 984: 8, 987: 8, 990: 8, 1000: 8, 1001: 8, 1006: 8, 1007: 8, 1008: 8, 1010: 6, 1014: 1, 1015: 8, 1016: 8, 1017: 8, 1018: 8, 1020: 8, 1026: 8, 1028: 8, 1029: 8, 1030: 8, 1032: 1, 1033: 1, 1034: 8, 1048: 1, 1049: 8, 1061: 8, 1064: 8, 1065: 8, 1070: 8, 1080: 8, 1081: 8, 1097: 8, 1113: 8, 1129: 8, 1145: 8, 1160: 4, 1177: 8, 1281: 8, 1328: 8, 1329: 8, 1332: 8, 1335: 8, 1337: 8, 1353: 8, 1368: 8, 1412: 8, 1436: 8, 1476: 8, 1481: 8, 1497: 8, 1513: 8, 1519: 8, 1601: 8, 1605: 8, 1617: 8, 1621: 8, 1625: 8, 1665: 8, 1792: 8, 1798: 8, 1800: 4, 1804: 8, 1812: 8, 1815: 8, 1816: 8, 1824: 8, 1825: 8, 1828: 8, 1831: 8, 1832: 8, 1840: 8, 1842: 8, 1848: 8, 1864: 8, 1872: 8, 1880: 8, 1888: 8, 1892: 8, 1896: 8, 1912: 8, 1937: 8, 1953: 8, 1960: 8, 1968: 8, 1992: 8, 2001: 8, 2008: 3, 2015: 8, 2016: 8, 2043: 5, 2045: 4 + 1: 8, 3: 8, 14: 8, 21: 4, 69: 8, 109: 4, 257: 3, 264: 8, 277: 6, 280: 6, 293: 4, 296: 4, 309: 5, 325: 8, 328: 5, 336: 8, 341: 8, 360: 7, 373: 8, 389: 8, 415: 8, 513: 5, 516: 8, 518: 8, 520: 4, 522: 8, 524: 8, 526: 8, 532: 3, 536: 8, 537: 3, 538: 8, 542: 8, 551: 5, 552: 2, 556: 8, 558: 8, 568: 8, 569: 8, 574: 8, 576: 3, 577: 8, 582: 5, 583: 8, 584: 4, 585: 8, 590: 8, 601: 8, 606: 8, 608: 1, 622: 8, 627: 6, 638: 8, 641: 8, 643: 8, 692: 8, 693: 8, 695: 8, 696: 8, 697: 8, 699: 8, 700: 8, 701: 8, 702: 8, 703: 8, 704: 8, 708: 8, 709: 8, 710: 8, 711: 8, 712: 8, 728: 8, 744: 8, 760: 8, 772: 8, 775: 8, 776: 8, 777: 8, 778: 8, 782: 8, 788: 8, 791: 8, 792: 8, 796: 2, 797: 8, 798: 6, 799: 8, 804: 8, 805: 8, 807: 8, 808: 1, 811: 8, 812: 8, 813: 8, 814: 5, 815: 8, 820: 8, 823: 8, 824: 8, 829: 8, 830: 5, 836: 8, 840: 8, 845: 8, 846: 5, 848: 8, 852: 8, 853: 8, 856: 4, 857: 6, 861: 8, 862: 5, 872: 8, 876: 8, 877: 8, 879: 8, 880: 8, 882: 8, 884: 8, 888: 8, 893: 8, 894: 8, 901: 6, 904: 3, 905: 8, 906: 8, 908: 2, 909: 8, 910: 8, 912: 8, 920: 8, 921: 8, 925: 4, 926: 6, 936: 8, 941: 8, 949: 8, 952: 8, 953: 6, 968: 8, 969: 7, 970: 8, 971: 8, 977: 8, 984: 8, 986: 8, 987: 8, 990: 8, 1000: 8, 1001: 8, 1006: 8, 1007: 8, 1008: 8, 1010: 6, 1014: 1, 1015: 8, 1016: 8, 1017: 8, 1018: 8, 1020: 8, 1026: 8, 1028: 8, 1029: 8, 1030: 8, 1032: 1, 1033: 1, 1034: 8, 1048: 1, 1049: 8, 1061: 8, 1064: 8, 1065: 8, 1070: 8, 1080: 8, 1081: 8, 1097: 8, 1113: 8, 1129: 8, 1145: 8, 1160: 4, 1177: 8, 1281: 8, 1328: 8, 1329: 8, 1332: 8, 1335: 8, 1337: 8, 1353: 8, 1368: 8, 1412: 8, 1436: 8, 1476: 8, 1481: 8, 1497: 8, 1513: 8, 1519: 8, 1601: 8, 1605: 8, 1617: 8, 1621: 8, 1625: 8, 1665: 8, 1792: 8, 1798: 8, 1800: 4, 1804: 8, 1812: 8, 1815: 8, 1816: 8, 1824: 8, 1825: 8, 1828: 8, 1831: 8, 1832: 8, 1840: 8, 1842: 8, 1848: 8, 1864: 8, 1872: 8, 1880: 8, 1888: 8, 1892: 8, 1896: 8, 1912: 8, 1937: 8, 1953: 8, 1960: 8, 1968: 8, 1992: 8, 2001: 8, 2008: 3, 2015: 8, 2016: 8, 2043: 5, 2045: 4 }, ], CAR.AP1_MODELS: [ From 578b8fba1a853da2f3b0d44605abfdd019bedd2f Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 15 Sep 2022 03:33:56 +0800 Subject: [PATCH 097/152] networking: create scanning label once (#25782) * create scanning label only once * rename * fix Co-authored-by: Shane Smiskol --- selfdrive/ui/qt/offroad/networking.cc | 25 +++++++++++++------------ selfdrive/ui/qt/offroad/networking.h | 2 ++ 2 files changed, 15 insertions(+), 12 deletions(-) diff --git a/selfdrive/ui/qt/offroad/networking.cc b/selfdrive/ui/qt/offroad/networking.cc index c7341d1987..7ec8691feb 100644 --- a/selfdrive/ui/qt/offroad/networking.cc +++ b/selfdrive/ui/qt/offroad/networking.cc @@ -207,9 +207,12 @@ WifiUI::WifiUI(QWidget *parent, WifiManager* wifi) : QWidget(parent), wifi(wifi) checkmark = QPixmap(ASSET_PATH + "offroad/icon_checkmark.svg").scaledToWidth(49, Qt::SmoothTransformation); circled_slash = QPixmap(ASSET_PATH + "img_circled_slash.svg").scaledToWidth(49, Qt::SmoothTransformation); - QLabel *scanning = new QLabel(tr("Scanning for networks...")); - scanning->setStyleSheet("font-size: 65px;"); - main_layout->addWidget(scanning, 0, Qt::AlignCenter); + scanningLabel = new QLabel(tr("Scanning for networks...")); + scanningLabel->setStyleSheet("font-size: 65px;"); + main_layout->addWidget(scanningLabel, 0, Qt::AlignCenter); + + list_layout = new QVBoxLayout; + main_layout->addLayout(list_layout); setStyleSheet(R"( QScrollBar::handle:vertical { @@ -257,14 +260,12 @@ WifiUI::WifiUI(QWidget *parent, WifiManager* wifi) : QWidget(parent), wifi(wifi) void WifiUI::refresh() { // TODO: don't rebuild this every time - clearLayout(main_layout); + clearLayout(list_layout); + + bool is_empty = wifi->seenNetworks.isEmpty(); + scanningLabel->setVisible(is_empty); + if (is_empty) return; - if (wifi->seenNetworks.size() == 0) { - QLabel *scanning = new QLabel(tr("Scanning for networks...")); - scanning->setStyleSheet("font-size: 65px;"); - main_layout->addWidget(scanning, 0, Qt::AlignCenter); - return; - } QList sortedNetworks = wifi->seenNetworks.values(); std::sort(sortedNetworks.begin(), sortedNetworks.end(), compare_by_strength); @@ -327,6 +328,6 @@ void WifiUI::refresh() { list->addItem(hlayout); } - main_layout->addWidget(list); - main_layout->addStretch(1); + list_layout->addWidget(list); + list_layout->addStretch(1); } diff --git a/selfdrive/ui/qt/offroad/networking.h b/selfdrive/ui/qt/offroad/networking.h index e78d65ef0f..4fc9a53d93 100644 --- a/selfdrive/ui/qt/offroad/networking.h +++ b/selfdrive/ui/qt/offroad/networking.h @@ -17,6 +17,8 @@ public: private: WifiManager *wifi = nullptr; + QVBoxLayout *list_layout = nullptr; + QLabel *scanningLabel = nullptr; QVBoxLayout* main_layout; QPixmap lock; QPixmap checkmark; From 7352e6d9409dcec6719717dcb805b97565648533 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 14 Sep 2022 15:40:29 -0700 Subject: [PATCH 098/152] camerad: log image sensor in camera states (#25786) * camerad: log image sensor in camera states * for all cams * bump cereal * revert that Co-authored-by: Comma Device --- cereal | 2 +- system/camerad/cameras/camera_common.cc | 8 +++++++- system/camerad/cameras/camera_common.h | 2 +- system/camerad/cameras/camera_qcom2.cc | 4 ++-- 4 files changed, 11 insertions(+), 5 deletions(-) diff --git a/cereal b/cereal index f363cc13c6..bd2f7fa567 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit f363cc13c67d286f87606f35f91952927d1c2d4d +Subproject commit bd2f7fa56706bcec3c9906bd57c2ec46f0666ac5 diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index d033d8e6b4..3dbe97596d 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -159,7 +159,7 @@ void CameraBuf::queue(size_t buf_idx) { // common functions -void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data) { +void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data, CameraState *c) { framed.setFrameId(frame_data.frame_id); framed.setTimestampEof(frame_data.timestamp_eof); framed.setTimestampSof(frame_data.timestamp_sof); @@ -173,6 +173,12 @@ void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &fr framed.setLensErr(frame_data.lens_err); framed.setLensTruePos(frame_data.lens_true_pos); framed.setProcessingTime(frame_data.processing_time); + + if (c->camera_id == CAMERA_ID_AR0231) { + framed.setSensor(cereal::FrameData::ImageSensor::AR0321); + } else if (c->camera_id == CAMERA_ID_OX03C10) { + framed.setSensor(cereal::FrameData::ImageSensor::OX03C10); + } } kj::Array get_raw_frame_image(const CameraBuf *b) { diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index 7bbb13c75f..bb6de9c8fb 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -113,7 +113,7 @@ public: typedef void (*process_thread_cb)(MultiCameraState *s, CameraState *c, int cnt); -void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data); +void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data, CameraState *c); kj::Array get_raw_frame_image(const CameraBuf *b); float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip); std::thread start_process_thread(MultiCameraState *cameras, CameraState *cs, process_thread_cb callback); diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index b2432bdd72..9bdd71b5d7 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -1208,7 +1208,7 @@ static void process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) MessageBuilder msg; auto framed = msg.initEvent().initDriverCameraState(); framed.setFrameType(cereal::FrameData::FrameType::FRONT); - fill_frame_data(framed, c->buf.cur_frame_data); + fill_frame_data(framed, c->buf.cur_frame_data, c); if (c->camera_id == CAMERA_ID_AR0231) { ar0231_process_registers(s, c, framed); @@ -1221,7 +1221,7 @@ void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { MessageBuilder msg; auto framed = c == &s->road_cam ? msg.initEvent().initRoadCameraState() : msg.initEvent().initWideRoadCameraState(); - fill_frame_data(framed, b->cur_frame_data); + fill_frame_data(framed, b->cur_frame_data, c); if (env_log_raw_frames && c == &s->road_cam && cnt % 100 == 5) { // no overlap with qlog decimation framed.setImage(get_raw_frame_image(b)); } From e699b0994ce418eca68f48557475118d3190dd0e Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 15 Sep 2022 00:40:36 +0200 Subject: [PATCH 099/152] Honda: match current speed on dash (#25232) * Honda Bosch: match speed on dash * present on all cars * all honda * more explicit switching * hyst * hyst * clean up * Update ref_commit * no bitwise no bitwise Co-authored-by: Shane Smiskol --- selfdrive/car/honda/carstate.py | 14 ++++++++++++-- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 13 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 4696bec82e..a37667fd3a 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -24,6 +24,7 @@ def get_can_signals(CP, gearbox_msg, main_on_sig_msg): ("MOTOR_TORQUE", "STEER_MOTOR_TORQUE"), ("STEER_TORQUE_SENSOR", "STEER_STATUS"), ("IMPERIAL_UNIT", "CAR_SPEED"), + ("ROUGH_CAR_SPEED_2", "CAR_SPEED"), ("LEFT_BLINKER", "SCM_FEEDBACK"), ("RIGHT_BLINKER", "SCM_FEEDBACK"), ("SEATBELT_DRIVER_LAMP", "SEATBELT_STATUS"), @@ -150,6 +151,10 @@ class CarState(CarStateBase): self.cruise_setting = 0 self.v_cruise_pcm_prev = 0 + # When available we use cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] to populate vEgoCluster + # However, on cars without a digital speedometer this is not always present (HRV, FIT, CRV 2016, ILX and RDX) + self.dash_speed_seen = False + def update(self, cp, cp_cam, cp_body): ret = car.CarState.new_message() @@ -203,6 +208,11 @@ class CarState(CarStateBase): ret.vEgoRaw = (1. - v_weight) * cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] * CV.KPH_TO_MS * self.CP.wheelSpeedFactor + v_weight * v_wheel ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + self.dash_speed_seen = self.dash_speed_seen or cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] > 1e-3 + if self.dash_speed_seen: + conversion = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS + ret.vEgoCluster = cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] * conversion + ret.steeringAngleDeg = cp.vl["STEERING_SENSORS"]["STEER_ANGLE"] ret.steeringRateDeg = cp.vl["STEERING_SENSORS"]["STEER_ANGLE_RATE"] @@ -237,9 +247,9 @@ class CarState(CarStateBase): ret.cruiseState.standstill = acc_hud["CRUISE_SPEED"] == 252. # on certain cars, CRUISE_SPEED changes to imperial with car's unit setting - conversion_factor = CV.MPH_TO_MS if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS and not self.is_metric else CV.KPH_TO_MS + conversion = CV.MPH_TO_MS if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS and not self.is_metric else CV.KPH_TO_MS # On set, cruise set speed pulses between 254~255 and the set speed prev is set to avoid this. - ret.cruiseState.speed = self.v_cruise_pcm_prev if acc_hud["CRUISE_SPEED"] > 160.0 else acc_hud["CRUISE_SPEED"] * conversion_factor + ret.cruiseState.speed = self.v_cruise_pcm_prev if acc_hud["CRUISE_SPEED"] > 160.0 else acc_hud["CRUISE_SPEED"] * conversion self.v_cruise_pcm_prev = ret.cruiseState.speed else: ret.cruiseState.speed = cp.vl["CRUISE"]["CRUISE_SPEED_PCM"] * CV.KPH_TO_MS diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 00a6789eaf..d0c769a0b0 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -260bd1a7240221e75a20d547f68e8d1217f9f29e \ No newline at end of file +3ad478bf44f50815d05acc5b12ff2f01a6cb42ff From 4c9f8d2df87582c4b56a08d9492ee55203d1a0bd Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Wed, 14 Sep 2022 19:04:28 -0500 Subject: [PATCH 100/152] VW: Prep for MQB longitudinal (#25777) * VW: Prep for MQB longitudinal * fine, be that way * temporarily pacify the docs generator --- selfdrive/car/volkswagen/carcontroller.py | 9 ++++-- selfdrive/car/volkswagen/carstate.py | 1 + selfdrive/car/volkswagen/interface.py | 15 ++++----- selfdrive/car/volkswagen/pqcan.py | 38 +++++++++++++---------- selfdrive/car/volkswagen/values.py | 3 +- 5 files changed, 39 insertions(+), 27 deletions(-) diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py index 5624c3dd5f..816933f2f0 100644 --- a/selfdrive/car/volkswagen/carcontroller.py +++ b/selfdrive/car/volkswagen/carcontroller.py @@ -7,6 +7,7 @@ from selfdrive.car.volkswagen import mqbcan, pqcan from selfdrive.car.volkswagen.values import CANBUS, PQ_CARS, CarControllerParams VisualAlert = car.CarControl.HUDControl.VisualAlert +LongCtrlState = car.CarControl.Actuators.LongControlState class CarController: @@ -25,7 +26,6 @@ class CarController: def update(self, CC, CS, ext_bus): actuators = CC.actuators hud_control = CC.hudControl - can_sends = [] # **** Steering Controls ************************************************ # @@ -71,9 +71,12 @@ class CarController: # **** Acceleration Controls ******************************************** # if self.frame % self.CCP.ACC_CONTROL_STEP == 0 and self.CP.openpilotLongitudinalControl: - tsk_status = self.CCS.tsk_status_value(CS.out.cruiseState.available, CS.out.accFaulted, CC.longActive) + acc_control = self.CCS.acc_control_value(CS.out.cruiseState.available, CS.out.accFaulted, CC.longActive) accel = clip(actuators.accel, self.CCP.ACCEL_MIN, self.CCP.ACCEL_MAX) if CC.longActive else 0 - can_sends.extend(self.CCS.create_acc_accel_control(self.packer_pt, CANBUS.pt, tsk_status, accel)) + stopping = actuators.longControlState == LongCtrlState.stopping + starting = actuators.longControlState == LongCtrlState.starting + can_sends.extend(self.CCS.create_acc_accel_control(self.packer_pt, CANBUS.pt, CS.acc_type, CC.longActive, accel, + acc_control, stopping, starting, CS.out.cruiseState.standstill)) # **** HUD Controls ***************************************************** # diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py index facc740a15..cf4a252b65 100644 --- a/selfdrive/car/volkswagen/carstate.py +++ b/selfdrive/car/volkswagen/carstate.py @@ -215,6 +215,7 @@ class CarState(CarStateBase): ret.stockAeb = False # Update ACC radar status. + self.acc_type = 0 # TODO: this is ACC "basic" with nonzero min speed, support FtS (1) later ret.cruiseState.available = bool(pt_cp.vl["Motor_5"]["GRA_Hauptschalter"]) ret.cruiseState.enabled = bool(pt_cp.vl["Motor_2"]["GRA_Status"]) if self.CP.pcmCruise: diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 3ed7a6244d..821eef44c7 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -38,6 +38,7 @@ class CarInterface(CarInterfaceBase): if any(msg in fingerprint[1] for msg in (0x1A0, 0xC2)): # Bremse_1, Lenkwinkel_1 ret.networkLocation = NetworkLocation.gateway + ret.experimentalLongitudinalAvailable = True else: ret.networkLocation = NetworkLocation.fwdCamera @@ -49,13 +50,6 @@ class CarInterface(CarInterfaceBase): # Panda ALLOW_DEBUG firmware required. ret.dashcamOnly = True - if experimental_long and ret.networkLocation == NetworkLocation.gateway: - # Proof-of-concept, prep for E2E only. No radar points available. Follow-to-stop not yet supported, but should - # be simple to add when a suitable test car becomes available. Panda ALLOW_DEBUG firmware required. - ret.experimentalLongitudinalAvailable = True - ret.openpilotLongitudinalControl = True - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_VOLKSWAGEN_LONG_CONTROL - else: # Set global MQB parameters ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.volkswagen)] @@ -87,6 +81,13 @@ class CarInterface(CarInterfaceBase): # Global longitudinal tuning defaults, can be overridden per-vehicle + if experimental_long and candidate in PQ_CARS: + # Proof-of-concept, prep for E2E only. No radar points available. Panda ALLOW_DEBUG firmware required. + ret.openpilotLongitudinalControl = True + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_VOLKSWAGEN_LONG_CONTROL + if ret.transmissionType == TransmissionType.manual: + ret.minEnableSpeed = 4.5 + ret.pcmCruise = not ret.openpilotLongitudinalControl ret.longitudinalActuatorDelayUpperBound = 0.5 # s ret.longitudinalTuning.kpV = [0.1] diff --git a/selfdrive/car/volkswagen/pqcan.py b/selfdrive/car/volkswagen/pqcan.py index e64bb2246e..30f3fcf62d 100644 --- a/selfdrive/car/volkswagen/pqcan.py +++ b/selfdrive/car/volkswagen/pqcan.py @@ -35,15 +35,15 @@ def create_acc_buttons_control(packer, bus, gra_stock_values, counter, cancel=Fa return packer.make_can_msg("GRA_Neu", bus, values) -def tsk_status_value(main_switch_on, acc_faulted, long_active): +def acc_control_value(main_switch_on, acc_faulted, long_active): if long_active: - tsk_status = 1 + acc_control = 1 elif main_switch_on: - tsk_status = 2 + acc_control = 2 else: - tsk_status = 0 + acc_control = 0 - return tsk_status + return acc_control def acc_hud_status_value(main_switch_on, acc_faulted, long_active): @@ -59,26 +59,32 @@ def acc_hud_status_value(main_switch_on, acc_faulted, long_active): return hud_status -def create_acc_accel_control(packer, bus, adr_status, accel): +def create_acc_accel_control(packer, bus, acc_type, enabled, accel, acc_control, stopping, starting, standstill): + commands = [] + values = { - "ACS_Sta_ADR": adr_status, - "ACS_StSt_Info": adr_status != 1, - "ACS_Typ_ACC": 0, # TODO: this is ACC "basic", find a way to detect FtS support (1) - "ACS_Sollbeschl": accel if adr_status == 1 else 3.01, - "ACS_zul_Regelabw": 0.2 if adr_status == 1 else 1.27, - "ACS_max_AendGrad": 3.0 if adr_status == 1 else 5.08, + "ACS_Sta_ADR": acc_control, + "ACS_StSt_Info": acc_control != 1, + "ACS_Typ_ACC": acc_type, + "ACS_Sollbeschl": accel if acc_control == 1 else 3.01, + "ACS_zul_Regelabw": 0.2 if acc_control == 1 else 1.27, + "ACS_max_AendGrad": 3.0 if acc_control == 1 else 5.08, } - return packer.make_can_msg("ACC_System", bus, values) + commands.append(packer.make_can_msg("ACC_System", bus, values)) + + return commands -def create_acc_hud_control(packer, bus, acc_status, set_speed, lead_visible): +def create_acc_hud_control(packer, bus, acc_hud_status, set_speed, lead_visible): values = { - "ACA_StaACC": acc_status, + "ACA_StaACC": acc_hud_status, "ACA_Zeitluecke": 2, "ACA_V_Wunsch": set_speed, "ACA_gemZeitl": 8 if lead_visible else 0, + # TODO: ACA_ID_StaACC, ACA_AnzDisplay, ACA_kmh_mph, ACA_PrioDisp, ACA_Aend_Zeitluecke + # display/display-prio handling probably needed to stop confusing the instrument cluster + # kmh_mph handling probably needed to resolve rounding errors in displayed setpoint } - # TODO: ACA_ID_StaACC, ACA_AnzDisplay, ACA_kmh_mph, ACA_PrioDisp, ACA_Aend_Zeitluecke return packer.make_can_msg("ACC_GRA_Anziege", bus, values) diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 7c55736362..6425cd60be 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -20,7 +20,6 @@ Button = namedtuple('Button', ['event_type', 'can_addr', 'can_msg', 'values']) class CarControllerParams: HCA_STEP = 2 # HCA_01/HCA_1 message frequency 50Hz ACC_CONTROL_STEP = 2 # ACC_06/ACC_07/ACC_System frequency 50Hz - ACC_HUD_STEP = 4 # ACC_GRA_Anziege frequency 25Hz ACCEL_MAX = 2.0 # 2.0 m/s max acceleration ACCEL_MIN = -3.5 # 3.5 m/s max deceleration @@ -37,6 +36,7 @@ class CarControllerParams: if CP.carFingerprint in PQ_CARS: self.LDW_STEP = 5 # LDW_1 message frequency 20Hz + self.ACC_HUD_STEP = 4 # ACC_GRA_Anziege frequency 25Hz self.STEER_DRIVER_ALLOWANCE = 80 # Driver intervention threshold 0.8 Nm self.STEER_DELTA_UP = 6 # Max HCA reached in 1.00s (STEER_MAX / (50Hz * 1.00)) self.STEER_DELTA_DOWN = 10 # Min HCA reached in 0.60s (STEER_MAX / (50Hz * 0.60)) @@ -65,6 +65,7 @@ class CarControllerParams: else: self.LDW_STEP = 10 # LDW_02 message frequency 10Hz + self.ACC_HUD_STEP = 6 # ACC_02 message frequency 16Hz self.STEER_DRIVER_ALLOWANCE = 80 # Driver intervention threshold 0.8 Nm self.STEER_DELTA_UP = 4 # Max HCA reached in 1.50s (STEER_MAX / (50Hz * 1.50)) self.STEER_DELTA_DOWN = 10 # Min HCA reached in 0.60s (STEER_MAX / (50Hz * 0.60)) From e8c8bd902d6c21173e4067b348e2762e5aefc4ab Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 14 Sep 2022 18:02:06 -0700 Subject: [PATCH 101/152] updated: prevent blocking on git (#25788) * updated: prevent blocking on git * remove that --- selfdrive/manager/test/test_manager.py | 2 +- selfdrive/updated.py | 48 +++++++------------------- 2 files changed, 14 insertions(+), 36 deletions(-) diff --git a/selfdrive/manager/test/test_manager.py b/selfdrive/manager/test/test_manager.py index f2e5319e8e..7ac2c5f506 100755 --- a/selfdrive/manager/test/test_manager.py +++ b/selfdrive/manager/test/test_manager.py @@ -12,7 +12,7 @@ from system.hardware import HARDWARE os.environ['FAKEUPLOAD'] = "1" MAX_STARTUP_TIME = 3 -ALL_PROCESSES = [p.name for p in managed_processes.values() if (type(p) is not DaemonProcess) and p.enabled and (p.name not in ['updated', 'pandad'])] +ALL_PROCESSES = [p.name for p in managed_processes.values() if (type(p) is not DaemonProcess) and p.enabled and (p.name not in ['pandad', ])] class TestManager(unittest.TestCase): diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 403ea2172b..2a36094768 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -57,24 +57,8 @@ class WaitTimeHelper: def __init__(self, proc): self.proc = proc self.ready_event = threading.Event() - self.shutdown = False - signal.signal(signal.SIGTERM, self.graceful_shutdown) - signal.signal(signal.SIGINT, self.graceful_shutdown) signal.signal(signal.SIGHUP, self.update_now) - def graceful_shutdown(self, signum: int, frame) -> None: - # umount -f doesn't appear effective in avoiding "device busy" on NEOS, - # so don't actually die until the next convenient opportunity in main(). - cloudlog.info("caught SIGINT/SIGTERM, dismounting overlay at next opportunity") - - # forward the signal to all our child processes - child_procs = self.proc.children(recursive=True) - for p in child_procs: - p.send_signal(signum) - - self.shutdown = True - self.ready_event.set() - def update_now(self, signum: int, frame) -> None: cloudlog.info("caught SIGHUP, running update check immediately") self.ready_event.set() @@ -233,7 +217,7 @@ def init_overlay() -> None: cloudlog.info(f"git diff output:\n{git_diff}") -def finalize_update(wait_helper: WaitTimeHelper) -> None: +def finalize_update() -> None: """Take the current OverlayFS merged view and finalize a copy outside of OverlayFS, ready to be swapped-in at BASEDIR. Copy using shutil.copytree""" @@ -258,14 +242,11 @@ def finalize_update(wait_helper: WaitTimeHelper) -> None: except subprocess.CalledProcessError: cloudlog.exception(f"Failed git cleanup, took {time.monotonic() - t:.3f} s") - if wait_helper.shutdown: - cloudlog.info("got interrupted finalizing overlay") - else: - set_consistent_flag(True) - cloudlog.info("done finalizing overlay") + set_consistent_flag(True) + cloudlog.info("done finalizing overlay") -def handle_agnos_update(wait_helper: WaitTimeHelper) -> None: +def handle_agnos_update() -> None: from system.hardware.tici.agnos import flash_agnos_update, get_target_slot_number cur_version = HARDWARE.get_os_version() @@ -302,7 +283,7 @@ def check_for_update() -> Tuple[bool, bool]: return False, False -def fetch_update(wait_helper: WaitTimeHelper) -> bool: +def fetch_update() -> bool: cloudlog.info("attempting git fetch inside staging overlay") setup_git_options(OVERLAY_MERGED) @@ -338,10 +319,10 @@ def fetch_update(wait_helper: WaitTimeHelper) -> bool: cloudlog.info("git reset success: %s", '\n'.join(r)) if AGNOS: - handle_agnos_update(wait_helper) + handle_agnos_update() # Create the finalized, ready-to-swap update - finalize_update(wait_helper) + finalize_update() cloudlog.info("openpilot update successful!") else: cloudlog.info("nothing new from git at this time") @@ -382,7 +363,7 @@ def main() -> None: wait_helper = WaitTimeHelper(proc) # Run the update loop - while not wait_helper.shutdown: + while True: wait_helper.ready_event.clear() # Attempt an update @@ -400,7 +381,7 @@ def main() -> None: # Fetch update if internet_ok: - new_version = fetch_update(wait_helper) + new_version = fetch_update() update_failed_count = 0 except subprocess.CalledProcessError as e: cloudlog.event( @@ -416,17 +397,14 @@ def main() -> None: exception = str(e) overlay_init.unlink(missing_ok=True) - if not wait_helper.shutdown: - try: - set_params(new_version, update_failed_count, exception) - except Exception: - cloudlog.exception("uncaught updated exception while setting params, shouldn't happen") + try: + set_params(new_version, update_failed_count, exception) + except Exception: + cloudlog.exception("uncaught updated exception while setting params, shouldn't happen") # infrequent attempts if we successfully updated recently wait_helper.sleep(5*60 if update_failed_count > 0 else 90*60) - dismount_overlay() - if __name__ == "__main__": main() From 86062fee6bbe5c38be77f8f995e9dd19dc2f2f54 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 14 Sep 2022 19:11:49 -0700 Subject: [PATCH 102/152] Subaru: match panda standstill (#25789) * subaru: match panda standstill * subaru: match panda standstill * actually test standstill * bump panda to master --- panda | 2 +- selfdrive/car/subaru/carstate.py | 7 +++---- selfdrive/car/tests/routes.py | 2 +- selfdrive/car/tests/test_models.py | 2 +- 4 files changed, 6 insertions(+), 7 deletions(-) diff --git a/panda b/panda index 19983f13b3..f120999e19 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 19983f13b37518298a3c282d5069c090b68f6864 +Subproject commit f120999e19fed7208534ae74b542b5cca6bafeaa diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py index 7fc5456d98..128e4245b2 100644 --- a/selfdrive/car/subaru/carstate.py +++ b/selfdrive/car/subaru/carstate.py @@ -32,9 +32,8 @@ class CarState(CarStateBase): cp_wheels.vl["Wheel_Speeds"]["RR"], ) ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - # Kalman filter, even though Subaru raw wheel speed is heaviliy filtered by default ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.vEgoRaw < 0.01 + ret.standstill = ret.vEgoRaw == 0 # continuous blinker signals for assisted lane change ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(50, cp.vl["Dashlights"]["LEFT_BLINKER"], @@ -50,7 +49,7 @@ class CarState(CarStateBase): ret.steeringAngleDeg = cp.vl["Steering_Torque"]["Steering_Angle"] ret.steeringTorque = cp.vl["Steering_Torque"]["Steer_Torque_Sensor"] ret.steeringTorqueEps = cp.vl["Steering_Torque"]["Steer_Torque_Output"] - + steer_threshold = 75 if self.CP.carFingerprint in PREGLOBAL_CARS else 80 ret.steeringPressed = abs(ret.steeringTorque) > steer_threshold @@ -313,4 +312,4 @@ class CarState(CarStateBase): checks += CarState.get_global_es_distance_signals()[1] return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 1) - return None \ No newline at end of file + return None diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 9207859340..1f5d3edaf0 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -194,7 +194,7 @@ routes = [ CarTestRoute("c321c6b697c5a5ff|2020-06-23--11-04-33", SUBARU.FORESTER), CarTestRoute("791340bc01ed993d|2019-03-10--16-28-08", SUBARU.IMPREZA), CarTestRoute("8bf7e79a3ce64055|2021-05-24--09-36-27", SUBARU.IMPREZA_2020), - CarTestRoute("1bbe6bf2d62f58a8|2022-07-14--17-11-43", SUBARU.OUTBACK, segment=3), + CarTestRoute("1bbe6bf2d62f58a8|2022-07-14--17-11-43", SUBARU.OUTBACK, segment=10), CarTestRoute("c56e69bbc74b8fad|2022-08-18--09-43-51", SUBARU.LEGACY, segment=3), # Pre-global, dashcam CarTestRoute("95441c38ae8c130e|2020-06-08--12-10-17", SUBARU.FORESTER_PREGLOBAL), diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 50370f0797..bab9f859e6 100755 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -234,7 +234,7 @@ class TestCarModelBase(unittest.TestCase): checks['gasPressed'] += CS.gasPressed != self.safety.get_gas_pressed_prev() checks['cruiseState'] += CS.cruiseState.enabled and not CS.cruiseState.available - if self.CP.carName not in ("hyundai", "volkswagen", "subaru", "gm", "body"): + if self.CP.carName not in ("hyundai", "volkswagen", "gm", "body"): # TODO: fix standstill mismatches for other makes checks['standstill'] += CS.standstill == self.safety.get_vehicle_moving() From 96ef9b1f0c15ecc0695401ca4e5c103d52fb088f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 14 Sep 2022 20:06:19 -0700 Subject: [PATCH 103/152] updated: remove niceness (#25791) --- selfdrive/updated.py | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 2a36094768..65f8425201 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -67,9 +67,7 @@ class WaitTimeHelper: self.ready_event.wait(timeout=t) -def run(cmd: List[str], cwd: Optional[str] = None, low_priority: bool = False): - if low_priority: - cmd = ["nice", "-n", "19"] + cmd +def run(cmd: List[str], cwd: Optional[str] = None): return subprocess.check_output(cmd, cwd=cwd, stderr=subprocess.STDOUT, encoding='utf8') @@ -212,7 +210,7 @@ def init_overlay() -> None: run(["sudo"] + mount_cmd) run(["sudo", "chmod", "755", os.path.join(OVERLAY_METADATA, "work")]) - git_diff = run(["git", "diff"], OVERLAY_MERGED, low_priority=True) + git_diff = run(["git", "diff"], OVERLAY_MERGED) params.put("GitDiff", git_diff) cloudlog.info(f"git diff output:\n{git_diff}") @@ -277,7 +275,7 @@ def check_git_fetch_result(fetch_txt: str) -> bool: def check_for_update() -> Tuple[bool, bool]: setup_git_options(OVERLAY_MERGED) try: - git_fetch_output = run(["git", "fetch", "--dry-run"], OVERLAY_MERGED, low_priority=True) + git_fetch_output = run(["git", "fetch", "--dry-run"], OVERLAY_MERGED) return True, check_git_fetch_result(git_fetch_output) except subprocess.CalledProcessError: return False, False @@ -288,7 +286,7 @@ def fetch_update() -> bool: setup_git_options(OVERLAY_MERGED) - git_fetch_output = run(["git", "fetch"], OVERLAY_MERGED, low_priority=True) + git_fetch_output = run(["git", "fetch"], OVERLAY_MERGED) cloudlog.info("git fetch success: %s", git_fetch_output) cur_hash = run(["git", "rev-parse", "HEAD"], OVERLAY_MERGED).rstrip() @@ -315,7 +313,7 @@ def fetch_update() -> bool: if new_branch is not None: cloudlog.info(f"switching to branch {repr(new_branch)}") cmds.insert(0, ["git", "checkout", "-f", new_branch]) - r = [run(cmd, OVERLAY_MERGED, low_priority=True) for cmd in cmds] + r = [run(cmd, OVERLAY_MERGED) for cmd in cmds] cloudlog.info("git reset success: %s", '\n'.join(r)) if AGNOS: From 03314b3ddf48fff9b5bfc82e5f6a65fc32dea78f Mon Sep 17 00:00:00 2001 From: Kurt Nistelberger Date: Wed, 14 Sep 2022 20:57:23 -0700 Subject: [PATCH 104/152] sensord test: stop sensord if interrupts not enabled (#25792) * stop sensord if interrupts not enabled * move to tearDown Co-authored-by: Kurt Nistelberger --- selfdrive/sensord/tests/test_sensord.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/selfdrive/sensord/tests/test_sensord.py b/selfdrive/sensord/tests/test_sensord.py index 84582518fd..837fe88833 100755 --- a/selfdrive/sensord/tests/test_sensord.py +++ b/selfdrive/sensord/tests/test_sensord.py @@ -121,6 +121,10 @@ class TestSensord(unittest.TestCase): cls.events = read_sensor_events(5) managed_processes["sensord"].stop() + def tearDown(self): + # interrupt check might leave sensord running + managed_processes["sensord"].stop() + def test_sensors_present(self): # verify correct sensors configuration From d57e07eec0c3848755e856ea8a2cf14559fcc895 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 15 Sep 2022 11:28:49 -0700 Subject: [PATCH 105/152] HKG: lower torque rate limits for CAN-FD cars (#25770) * Change ramp limits to 2/2 for CANFD cars * Only the high torque CANFD cars * comment * Update selfdrive/car/hyundai/values.py * Better to do 2/3 and for all cars * bump to master * update refs --- panda | 2 +- selfdrive/car/hyundai/values.py | 2 ++ selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/panda b/panda index f120999e19..38257a93e4 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit f120999e19fed7208534ae74b542b5cca6bafeaa +Subproject commit 38257a93e4733819a109a4ef52efed1bbeb45cc4 diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 7fb8363a67..b816614879 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -29,6 +29,8 @@ class CarControllerParams: self.STEER_DRIVER_ALLOWANCE = 250 self.STEER_DRIVER_MULTIPLIER = 2 self.STEER_THRESHOLD = 250 + self.STEER_DELTA_UP = 2 + self.STEER_DELTA_DOWN = 3 # To determine the limit for your car, find the maximum value that the stock LKAS will request. # If the max stock LKAS request is <384, add your car to this list. diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index d0c769a0b0..b25e2fecfc 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -3ad478bf44f50815d05acc5b12ff2f01a6cb42ff +dac3c51684e101672bc27df13e76577103531e30 \ No newline at end of file From ef5395e5f36550d2b485216eee5406bf6062e9c9 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 15 Sep 2022 13:28:24 -0700 Subject: [PATCH 106/152] update ev6 max lat accel --- selfdrive/car/torque_data/override.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index fcc762c2b8..20fb5f7a64 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -21,7 +21,7 @@ FORD FOCUS 4TH GEN: [.nan, 1.5, .nan] COMMA BODY: [.nan, 1000, .nan] # Totally new cars -KIA EV6 2022: [3.5, 2.5, 0.0] +KIA EV6 2022: [3.5, 3.0, 0.0] RAM 1500 5TH GEN: [2.0, 2.0, 0.0] RAM HD 5TH GEN: [1.4, 1.4, 0.0] SUBARU OUTBACK 6TH GEN: [2.3, 2.3, 0.11] From a9f88503fe132401e73531f8213923ba53b2c19f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 15 Sep 2022 13:55:36 -0700 Subject: [PATCH 107/152] update refs --- selfdrive/test/process_replay/ref_commit | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index b25e2fecfc..7390610252 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -dac3c51684e101672bc27df13e76577103531e30 \ No newline at end of file +ef5395e5f36550d2b485216eee5406bf6062e9c9 \ No newline at end of file From c7a0f23b45603fb8e7718234f92284854866924e Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Thu, 15 Sep 2022 15:06:43 -0700 Subject: [PATCH 108/152] better OX03C10 settings (#25796) * ev has different scales * fix initial gradient * fix highlight weirdness * try smooth set of gains * delay * add gain idx * oops * set different min dc Co-authored-by: Comma Device --- system/camerad/cameras/camera_qcom2.cc | 61 ++++++++++++++++---------- system/camerad/cameras/camera_qcom2.h | 4 +- system/camerad/cameras/sensor2_i2c.h | 6 +-- 3 files changed, 44 insertions(+), 27 deletions(-) diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 9bdd71b5d7..544d653676 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -61,39 +61,48 @@ const float DC_GAIN_OX03C10 = 7.32; const float DC_GAIN_ON_GREY_AR0231= 0.2; const float DC_GAIN_OFF_GREY_AR0231 = 0.3; -const float DC_GAIN_ON_GREY_OX03C10= 0.3; -const float DC_GAIN_OFF_GREY_OX03C10 = 0.375; +const float DC_GAIN_ON_GREY_OX03C10= 0.25; +const float DC_GAIN_OFF_GREY_OX03C10 = 0.35; -const int DC_GAIN_MIN_WEIGHT = 0; +const int DC_GAIN_MIN_WEIGHT_AR0231 = 0; const int DC_GAIN_MAX_WEIGHT_AR0231 = 1; +const int DC_GAIN_MIN_WEIGHT_OX03C10 = 16; const int DC_GAIN_MAX_WEIGHT_OX03C10 = 32; +const float TARGET_GREY_FACTOR_AR0231 = 1.0; +const float TARGET_GREY_FACTOR_OX03C10 = 0.02; + const float sensor_analog_gains_AR0231[] = { 1.0/8.0, 2.0/8.0, 2.0/7.0, 3.0/7.0, // 0, 1, 2, 3 3.0/6.0, 4.0/6.0, 4.0/5.0, 5.0/5.0, // 4, 5, 6, 7 5.0/4.0, 6.0/4.0, 6.0/3.0, 7.0/3.0, // 8, 9, 10, 11 7.0/2.0, 8.0/2.0, 8.0/1.0}; // 12, 13, 14, 15 = bypass -// similar gain curve to AR const float sensor_analog_gains_OX03C10[] = { - 1.0, 1.25, 1.3125, 1.5625, - 1.6875, 2.0, 2.25, 2.625, - 3.125, 3.625, 4.5, 5.0, - 7.25, 8.5, 12.0, 15.5}; + 1.0, 1.125, 1.25, 1.3125, 1.5625, + 1.6875, 2.0, 2.25, 2.625, 3.125, + 3.625, 4.0, 4.5, 5.0, 5.5, + 6.0, 6.5, 7.0, 7.5, 8.0, + 8.5, 9.0, 9.5, 10.0, 10.5, + 11.0, 11.5, 12.0, 12.5, 13.0, + 13.5, 14.0, 14.5, 15.0, 15.5}; const uint32_t ox03c10_analog_gains_reg[] = { - 0x100, 0x140, 0x150, 0x190, - 0x1B0, 0x200, 0x240, 0x2A0, - 0x320, 0x3A0, 0x480, 0x500, - 0x740, 0x880, 0xC00, 0xF80}; + 0x100, 0x120, 0x140, 0x150, 0x190, + 0x1B0, 0x200, 0x240, 0x2A0, 0x320, + 0x3A0, 0x400, 0x480, 0x500, 0x580, + 0x600, 0x680, 0x700, 0x780, 0x800, + 0x880, 0x900, 0x980, 0xA00, 0xA80, + 0xB00, 0xB80, 0xC00, 0xC80, 0xD00, + 0xD80, 0xE00, 0xE80, 0xF00, 0xF80}; const int ANALOG_GAIN_MIN_IDX_AR0231 = 0x1; // 0.25x const int ANALOG_GAIN_REC_IDX_AR0231 = 0x6; // 0.8x const int ANALOG_GAIN_MAX_IDX_AR0231 = 0xD; // 4.0x const int ANALOG_GAIN_MIN_IDX_OX03C10 = 0x0; -const int ANALOG_GAIN_REC_IDX_OX03C10 = 0x5; // 2x -const int ANALOG_GAIN_MAX_IDX_OX03C10 = 0xF; +const int ANALOG_GAIN_REC_IDX_OX03C10 = 0x6; // 2x +const int ANALOG_GAIN_MAX_IDX_OX03C10 = 0x22; const int EXPOSURE_TIME_MIN_AR0231 = 2; // with HDR, fastest ss const int EXPOSURE_TIME_MAX_AR0231 = 0x0855; // with HDR, slowest ss, 40ms @@ -517,6 +526,7 @@ void CameraState::enqueue_req_multi(int start, int n, bool dp) { void CameraState::camera_set_parameters() { if (camera_id == CAMERA_ID_AR0231) { dc_gain_factor = DC_GAIN_AR0231; + dc_gain_min_weight = DC_GAIN_MIN_WEIGHT_AR0231; dc_gain_max_weight = DC_GAIN_MAX_WEIGHT_AR0231; dc_gain_on_grey = DC_GAIN_ON_GREY_AR0231; dc_gain_off_grey = DC_GAIN_OFF_GREY_AR0231; @@ -529,8 +539,10 @@ void CameraState::camera_set_parameters() { sensor_analog_gains[i] = sensor_analog_gains_AR0231[i]; } min_ev = exposure_time_min * sensor_analog_gains[analog_gain_min_idx]; + target_grey_factor = TARGET_GREY_FACTOR_AR0231; } else if (camera_id == CAMERA_ID_OX03C10) { dc_gain_factor = DC_GAIN_OX03C10; + dc_gain_min_weight = DC_GAIN_MIN_WEIGHT_OX03C10; dc_gain_max_weight = DC_GAIN_MAX_WEIGHT_OX03C10; dc_gain_on_grey = DC_GAIN_ON_GREY_OX03C10; dc_gain_off_grey = DC_GAIN_OFF_GREY_OX03C10; @@ -543,6 +555,7 @@ void CameraState::camera_set_parameters() { sensor_analog_gains[i] = sensor_analog_gains_OX03C10[i]; } min_ev = (exposure_time_min + VS_TIME_MIN_OX03C10) * sensor_analog_gains[analog_gain_min_idx]; + target_grey_factor = TARGET_GREY_FACTOR_OX03C10; } else { assert(false); } @@ -551,7 +564,7 @@ void CameraState::camera_set_parameters() { target_grey_fraction = 0.3; dc_gain_enabled = false; - dc_gain_weight = DC_GAIN_MIN_WEIGHT; + dc_gain_weight = dc_gain_min_weight; gain_idx = analog_gain_rec_idx; exposure_time = 5; cur_ev[0] = cur_ev[1] = cur_ev[2] = (1 + dc_gain_weight * (dc_gain_factor-1) / dc_gain_max_weight) * sensor_analog_gains[gain_idx] * exposure_time; @@ -1037,7 +1050,7 @@ void CameraState::set_camera_exposure(float grey_frac) { const float cur_ev_ = cur_ev[buf.cur_frame_data.frame_id % 3]; // Scale target grey between 0.1 and 0.4 depending on lighting conditions - float new_target_grey = std::clamp(0.4 - 0.3 * log2(1.0 + cur_ev_) / log2(6000.0), 0.1, 0.4); + float new_target_grey = std::clamp(0.4 - 0.3 * log2(1.0 + target_grey_factor*cur_ev_) / log2(6000.0), 0.1, 0.4); float target_grey = (1.0 - k_grey) * target_grey_fraction + k_grey * new_target_grey; float desired_ev = std::clamp(cur_ev_ * target_grey / grey_frac, min_ev, max_ev); @@ -1053,14 +1066,14 @@ void CameraState::set_camera_exposure(float grey_frac) { bool enable_dc_gain = dc_gain_enabled; if (!enable_dc_gain && target_grey < dc_gain_on_grey) { enable_dc_gain = true; - dc_gain_weight = DC_GAIN_MIN_WEIGHT; + dc_gain_weight = dc_gain_min_weight; } else if (enable_dc_gain && target_grey > dc_gain_off_grey) { enable_dc_gain = false; dc_gain_weight = dc_gain_max_weight; } if (enable_dc_gain && dc_gain_weight < dc_gain_max_weight) {dc_gain_weight += 1;} - if (!enable_dc_gain && dc_gain_weight > DC_GAIN_MIN_WEIGHT) {dc_gain_weight -= 1;} + if (!enable_dc_gain && dc_gain_weight > dc_gain_min_weight) {dc_gain_weight -= 1;} std::string gain_bytes, time_bytes; if (env_ctrl_exp_from_params) { @@ -1145,10 +1158,12 @@ void CameraState::set_camera_exposure(float grey_frac) { // t_HCG + t_LCG + t_VS on LPD, t_SPD on SPD uint32_t hcg_time = std::max((dc_gain_weight * exposure_time / dc_gain_max_weight), 0); uint32_t lcg_time = std::max(((dc_gain_max_weight - dc_gain_weight) * exposure_time / dc_gain_max_weight), 0); - uint32_t spd_time = std::max(hcg_time / 16, (uint32_t)exposure_time_min); - uint32_t vs_time = std::min(std::max(hcg_time / 64, VS_TIME_MIN_OX03C10), VS_TIME_MAX_OX03C10); + // uint32_t spd_time = std::max(hcg_time / 16, (uint32_t)exposure_time_min); + uint32_t vs_time = std::min(std::max((uint32_t)exposure_time / 128, VS_TIME_MIN_OX03C10), VS_TIME_MAX_OX03C10); + uint32_t spd_time = vs_time; uint32_t real_gain = ox03c10_analog_gains_reg[new_g]; + uint32_t min_gain = ox03c10_analog_gains_reg[0]; struct i2c_random_wr_payload exp_reg_array[] = { {0x3501, hcg_time>>8}, {0x3502, hcg_time&0xFF}, @@ -1157,9 +1172,9 @@ void CameraState::set_camera_exposure(float grey_frac) { {0x35c1, vs_time>>8}, {0x35c2, vs_time&0xFF}, {0x3508, real_gain>>8}, {0x3509, real_gain&0xFF}, - {0x3588, real_gain>>8}, {0x3589, real_gain&0xFF}, - {0x3548, real_gain>>8}, {0x3549, real_gain&0xFF}, - {0x35c8, real_gain>>8}, {0x35c9, real_gain&0xFF}, + {0x3588, min_gain>>8}, {0x3589, min_gain&0xFF}, + {0x3548, min_gain>>8}, {0x3549, min_gain&0xFF}, + {0x35c8, min_gain>>8}, {0x35c9, min_gain&0xFF}, }; sensors_i2c(exp_reg_array, sizeof(exp_reg_array)/sizeof(struct i2c_random_wr_payload), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false); } diff --git a/system/camerad/cameras/camera_qcom2.h b/system/camerad/cameras/camera_qcom2.h index 1b792e7e96..5023c82458 100644 --- a/system/camerad/cameras/camera_qcom2.h +++ b/system/camerad/cameras/camera_qcom2.h @@ -31,11 +31,12 @@ public: int exposure_time_max; float dc_gain_factor; + int dc_gain_min_weight; int dc_gain_max_weight; float dc_gain_on_grey; float dc_gain_off_grey; - float sensor_analog_gains[16]; + float sensor_analog_gains[35]; int analog_gain_min_idx; int analog_gain_max_idx; int analog_gain_rec_idx; @@ -45,6 +46,7 @@ public: float measured_grey_fraction; float target_grey_fraction; + float target_grey_factor; unique_fd sensor_fd; unique_fd csiphy_fd; diff --git a/system/camerad/cameras/sensor2_i2c.h b/system/camerad/cameras/sensor2_i2c.h index 9df99552e1..209e2d76d2 100644 --- a/system/camerad/cameras/sensor2_i2c.h +++ b/system/camerad/cameras/sensor2_i2c.h @@ -129,13 +129,13 @@ struct i2c_random_wr_payload init_array_ox03c10[] = { {0x350a, 0x04}, {0x350b, 0x00}, {0x350c, 0x00}, // hcg digital gain {0x3586, 0x40}, {0x3587, 0x00}, // lcg fine exposure - {0x358a, 0x04}, {0x358b, 0x00}, {0x358c, 0x00}, // lcg digital gain + {0x358a, 0x01}, {0x358b, 0x00}, {0x358c, 0x00}, // lcg digital gain {0x3546, 0x20}, {0x3547, 0x00}, // spd fine exposure - {0x354a, 0x04}, {0x354b, 0x00}, {0x354c, 0x00}, // spd digital gain + {0x354a, 0x01}, {0x354b, 0x00}, {0x354c, 0x00}, // spd digital gain {0x35c6, 0xb0}, {0x35c7, 0x00}, // vs fine exposure - {0x35ca, 0x04}, {0x35cb, 0x00}, {0x35cc, 0x00}, // vs digital gain + {0x35ca, 0x01}, {0x35cb, 0x00}, {0x35cc, 0x00}, // vs digital gain // also RSVD {0x3600, 0x8f}, {0x3605, 0x16}, {0x3609, 0xf0}, {0x360a, 0x01}, From c4e63d14ab158118efc6eadd0e20d8d533f9e046 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 15 Sep 2022 15:12:36 -0700 Subject: [PATCH 109/152] good updater experience (#25724) * good updater experience * set params on startup * no fetch on first loop * little type hinting * little more * update translations * always set params with valid overlay * wrap check * use the param * more wrapping * vanish * cleanup * remove that --- common/params.cc | 10 +- selfdrive/ui/.gitignore | 2 + selfdrive/ui/SConscript | 3 +- selfdrive/ui/qt/offroad/settings.cc | 81 +---- selfdrive/ui/qt/offroad/settings.h | 13 +- selfdrive/ui/qt/offroad/software_settings.cc | 156 ++++++++++ selfdrive/ui/qt/widgets/controls.cc | 8 +- selfdrive/ui/qt/widgets/controls.h | 14 +- selfdrive/ui/qt/widgets/offroad_alerts.cc | 2 +- selfdrive/ui/qt/widgets/ssh_keys.cc | 8 +- selfdrive/ui/qt/widgets/ssh_keys.h | 2 - selfdrive/ui/tests/cycle_offroad_alerts.py | 2 +- selfdrive/ui/translations/main_ja.ts | 91 ++---- selfdrive/ui/translations/main_ko.ts | 91 ++---- selfdrive/ui/translations/main_pt-BR.ts | 91 ++---- selfdrive/ui/translations/main_zh-CHS.ts | 91 ++---- selfdrive/ui/translations/main_zh-CHT.ts | 91 ++---- selfdrive/updated.py | 306 ++++++++++++------- 18 files changed, 550 insertions(+), 512 deletions(-) create mode 100644 selfdrive/ui/qt/offroad/software_settings.cc diff --git a/common/params.cc b/common/params.cc index 5c8c94be53..8ff5fc539d 100644 --- a/common/params.cc +++ b/common/params.cc @@ -154,18 +154,24 @@ std::unordered_map keys = { {"PrimeType", PERSISTENT}, {"RecordFront", PERSISTENT}, {"RecordFrontLock", PERSISTENT}, // for the internal fleet - {"ReleaseNotes", PERSISTENT}, {"ReplayControlsState", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"ShouldDoUpdate", CLEAR_ON_MANAGER_START}, {"SnoozeUpdate", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF}, {"SshEnabled", PERSISTENT}, {"SubscriberInfo", PERSISTENT}, - {"SwitchToBranch", CLEAR_ON_MANAGER_START}, {"TermsVersion", PERSISTENT}, {"Timezone", PERSISTENT}, {"TrainingVersion", PERSISTENT}, {"UpdateAvailable", CLEAR_ON_MANAGER_START}, {"UpdateFailedCount", CLEAR_ON_MANAGER_START}, + {"UpdaterState", CLEAR_ON_MANAGER_START}, + {"UpdaterFetchAvailable", CLEAR_ON_MANAGER_START}, + {"UpdaterTargetBranch", CLEAR_ON_MANAGER_START}, + {"UpdaterAvailableBranches", CLEAR_ON_MANAGER_START}, + {"UpdaterCurrentDescription", CLEAR_ON_MANAGER_START}, + {"UpdaterCurrentReleaseNotes", CLEAR_ON_MANAGER_START}, + {"UpdaterNewDescription", CLEAR_ON_MANAGER_START}, + {"UpdaterNewReleaseNotes", CLEAR_ON_MANAGER_START}, {"Version", PERSISTENT}, {"VisionRadarToggle", PERSISTENT}, {"WideCameraOnly", PERSISTENT}, diff --git a/selfdrive/ui/.gitignore b/selfdrive/ui/.gitignore index e5b27adce5..60eb4b43c7 100644 --- a/selfdrive/ui/.gitignore +++ b/selfdrive/ui/.gitignore @@ -1,6 +1,8 @@ moc_* *.moc +translations/main_test_en.* + _mui watch3 installer/installers/* diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index c62a6b19d9..92f6578dfc 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -56,7 +56,8 @@ qt_env.Program("qt/spinner", ["qt/spinner.cc"], LIBS=qt_libs) # build main UI qt_src = ["main.cc", "qt/sidebar.cc", "qt/onroad.cc", "qt/body.cc", "qt/window.cc", "qt/home.cc", "qt/offroad/settings.cc", - "qt/offroad/onboarding.cc", "qt/offroad/driverview.cc"] + "qt/offroad/software_settings.cc", "qt/offroad/onboarding.cc", + "qt/offroad/driverview.cc"] qt_env.Program("_ui", qt_src + [asset_obj], LIBS=qt_libs) if GetOption('test'): qt_src.remove("main.cc") # replaced by test_runner diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 7a5a40c193..52df247a25 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -159,7 +159,7 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { addItem(dcamBtn); auto resetCalibBtn = new ButtonControl(tr("Reset Calibration"), tr("RESET"), ""); - connect(resetCalibBtn, &ButtonControl::showDescription, this, &DevicePanel::updateCalibDescription); + connect(resetCalibBtn, &ButtonControl::showDescriptionEvent, this, &DevicePanel::updateCalibDescription); connect(resetCalibBtn, &ButtonControl::clicked, [&]() { if (ConfirmationDialog::confirm(tr("Are you sure you want to reset calibration?"), this)) { params.remove("CalibrationParams"); @@ -282,85 +282,6 @@ void DevicePanel::poweroff() { } } -SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) { - gitBranchLbl = new LabelControl(tr("Git Branch")); - gitCommitLbl = new LabelControl(tr("Git Commit")); - osVersionLbl = new LabelControl(tr("OS Version")); - versionLbl = new LabelControl(tr("Version"), "", QString::fromStdString(params.get("ReleaseNotes")).trimmed()); - lastUpdateLbl = new LabelControl(tr("Last Update Check"), "", tr("The last time openpilot successfully checked for an update. The updater only runs while the car is off.")); - updateBtn = new ButtonControl(tr("Check for Update"), ""); - connect(updateBtn, &ButtonControl::clicked, [=]() { - if (params.getBool("IsOffroad")) { - fs_watch->addPath(QString::fromStdString(params.getParamPath("LastUpdateTime"))); - fs_watch->addPath(QString::fromStdString(params.getParamPath("UpdateFailedCount"))); - updateBtn->setText(tr("CHECKING")); - updateBtn->setEnabled(false); - } - std::system("pkill -1 -f selfdrive.updated"); - }); - connect(uiState(), &UIState::offroadTransition, updateBtn, &QPushButton::setEnabled); - - branchSwitcherBtn = new ButtonControl(tr("Switch Branch"), tr("ENTER"), tr("The new branch will be pulled the next time the updater runs.")); - connect(branchSwitcherBtn, &ButtonControl::clicked, [=]() { - QString branch = InputDialog::getText(tr("Enter branch name"), this, tr("The new branch will be pulled the next time the updater runs."), - false, -1, QString::fromStdString(params.get("SwitchToBranch"))); - if (branch.isEmpty()) { - params.remove("SwitchToBranch"); - } else { - params.put("SwitchToBranch", branch.toStdString()); - } - std::system("pkill -1 -f selfdrive.updated"); - }); - connect(uiState(), &UIState::offroadTransition, branchSwitcherBtn, &QPushButton::setEnabled); - - auto uninstallBtn = new ButtonControl(tr("Uninstall %1").arg(getBrand()), tr("UNINSTALL")); - connect(uninstallBtn, &ButtonControl::clicked, [&]() { - if (ConfirmationDialog::confirm(tr("Are you sure you want to uninstall?"), this)) { - params.putBool("DoUninstall", true); - } - }); - connect(uiState(), &UIState::offroadTransition, uninstallBtn, &QPushButton::setEnabled); - - QWidget *widgets[] = {versionLbl, lastUpdateLbl, updateBtn, branchSwitcherBtn, gitBranchLbl, gitCommitLbl, osVersionLbl, uninstallBtn}; - for (QWidget* w : widgets) { - if (w == branchSwitcherBtn && params.getBool("IsTestedBranch")) { - continue; - } - addItem(w); - } - - fs_watch = new QFileSystemWatcher(this); - QObject::connect(fs_watch, &QFileSystemWatcher::fileChanged, [=](const QString path) { - if (path.contains("UpdateFailedCount") && std::atoi(params.get("UpdateFailedCount").c_str()) > 0) { - lastUpdateLbl->setText(tr("failed to fetch update")); - updateBtn->setText(tr("CHECK")); - updateBtn->setEnabled(true); - } else if (path.contains("LastUpdateTime")) { - updateLabels(); - } - }); -} - -void SoftwarePanel::showEvent(QShowEvent *event) { - updateLabels(); -} - -void SoftwarePanel::updateLabels() { - QString lastUpdate = ""; - auto tm = params.get("LastUpdateTime"); - if (!tm.empty()) { - lastUpdate = timeAgo(QDateTime::fromString(QString::fromStdString(tm + "Z"), Qt::ISODate)); - } - - versionLbl->setText(getBrandVersion()); - lastUpdateLbl->setText(lastUpdate); - updateBtn->setText(tr("CHECK")); - updateBtn->setEnabled(true); - gitBranchLbl->setText(QString::fromStdString(params.get("GitBranch"))); - gitCommitLbl->setText(QString::fromStdString(params.get("GitCommit")).left(10)); - osVersionLbl->setText(QString::fromStdString(Hardware::get_os_version()).trimmed()); -} - void SettingsWindow::showEvent(QShowEvent *event) { panel_widget->setCurrentIndex(0); nav_btns->buttons()[0]->setChecked(true); diff --git a/selfdrive/ui/qt/offroad/settings.h b/selfdrive/ui/qt/offroad/settings.h index 1f823851f1..4177f28cf4 100644 --- a/selfdrive/ui/qt/offroad/settings.h +++ b/selfdrive/ui/qt/offroad/settings.h @@ -71,14 +71,15 @@ public: private: void showEvent(QShowEvent *event) override; void updateLabels(); + void checkForUpdates(); - LabelControl *gitBranchLbl; - LabelControl *gitCommitLbl; - LabelControl *osVersionLbl; + bool is_onroad = false; + + QLabel *onroadLbl; LabelControl *versionLbl; - LabelControl *lastUpdateLbl; - ButtonControl *updateBtn; - ButtonControl *branchSwitcherBtn; + ButtonControl *installBtn; + ButtonControl *downloadBtn; + ButtonControl *targetBranchBtn; Params params; QFileSystemWatcher *fs_watch; diff --git a/selfdrive/ui/qt/offroad/software_settings.cc b/selfdrive/ui/qt/offroad/software_settings.cc new file mode 100644 index 0000000000..c9deef2ec4 --- /dev/null +++ b/selfdrive/ui/qt/offroad/software_settings.cc @@ -0,0 +1,156 @@ +#include "selfdrive/ui/qt/offroad/settings.h" + +#include +#include +#include + +#include +#include + +#include "common/params.h" +#include "common/util.h" +#include "selfdrive/ui/ui.h" +#include "selfdrive/ui/qt/util.h" +#include "selfdrive/ui/qt/widgets/controls.h" +#include "selfdrive/ui/qt/widgets/input.h" +#include "system/hardware/hw.h" + + +void SoftwarePanel::checkForUpdates() { + std::system("pkill -SIGUSR1 -f selfdrive.updated"); +} + +SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) { + onroadLbl = new QLabel(tr("Updates are only downloaded while the car is off.")); + onroadLbl->setStyleSheet("font-size: 50px; font-weight: 400; text-align: left; padding-top: 30px; padding-bottom: 30px;"); + addItem(onroadLbl); + + // current version + versionLbl = new LabelControl(tr("Current Version"), ""); + addItem(versionLbl); + + // download update btn + downloadBtn = new ButtonControl(tr("Download"), tr("CHECK")); + connect(downloadBtn, &ButtonControl::clicked, [=]() { + downloadBtn->setEnabled(false); + if (downloadBtn->text() == tr("CHECK")) { + checkForUpdates(); + } else { + std::system("pkill -SIGHUP -f selfdrive.updated"); + } + }); + addItem(downloadBtn); + + // install update btn + installBtn = new ButtonControl(tr("Install Update"), tr("INSTALL")); + connect(installBtn, &ButtonControl::clicked, [=]() { + installBtn->setEnabled(false); + params.putBool("DoShutdown", true); + }); + addItem(installBtn); + + // branch selecting + targetBranchBtn = new ButtonControl(tr("Target Branch"), tr("SELECT")); + connect(targetBranchBtn, &ButtonControl::clicked, [=]() { + auto current = params.get("GitBranch"); + QStringList branches = QString::fromStdString(params.get("UpdaterAvailableBranches")).split(","); + for (QString b : {current.c_str(), "devel-staging", "devel", "master-ci", "master"}) { + auto i = branches.indexOf(b); + if (i >= 0) { + branches.removeAt(i); + branches.insert(0, b); + } + } + + QString cur = QString::fromStdString(params.get("UpdaterTargetBranch")); + QString selection = MultiOptionDialog::getSelection(tr("Select a branch"), branches, cur, this); + if (!selection.isEmpty()) { + params.put("UpdaterTargetBranch", selection.toStdString()); + targetBranchBtn->setValue(QString::fromStdString(params.get("UpdaterTargetBranch"))); + checkForUpdates(); + } + }); + if (!params.getBool("IsTestedBranch")) { + addItem(targetBranchBtn); + } + + // uninstall button + auto uninstallBtn = new ButtonControl(tr("Uninstall %1").arg(getBrand()), tr("UNINSTALL")); + connect(uninstallBtn, &ButtonControl::clicked, [&]() { + if (ConfirmationDialog::confirm(tr("Are you sure you want to uninstall?"), this)) { + params.putBool("DoUninstall", true); + } + }); + addItem(uninstallBtn); + + fs_watch = new QFileSystemWatcher(this); + QObject::connect(fs_watch, &QFileSystemWatcher::fileChanged, [=](const QString path) { + updateLabels(); + }); + + connect(uiState(), &UIState::offroadTransition, [=](bool offroad) { + is_onroad = !offroad; + updateLabels(); + }); + + updateLabels(); +} + +void SoftwarePanel::showEvent(QShowEvent *event) { + // nice for testing on PC + installBtn->setEnabled(true); + + updateLabels(); +} + +void SoftwarePanel::updateLabels() { + // add these back in case the files got removed + fs_watch->addPath(QString::fromStdString(params.getParamPath("LastUpdateTime"))); + fs_watch->addPath(QString::fromStdString(params.getParamPath("UpdateFailedCount"))); + fs_watch->addPath(QString::fromStdString(params.getParamPath("UpdaterState"))); + fs_watch->addPath(QString::fromStdString(params.getParamPath("UpdateAvailable"))); + + if (!isVisible()) { + return; + } + + // updater only runs offroad + onroadLbl->setVisible(is_onroad); + downloadBtn->setVisible(!is_onroad); + + // download update + QString updater_state = QString::fromStdString(params.get("UpdaterState")); + bool failed = std::atoi(params.get("UpdateFailedCount").c_str()) > 0; + if (updater_state != "idle") { + downloadBtn->setEnabled(false); + downloadBtn->setValue(updater_state); + } else { + if (failed) { + downloadBtn->setText("CHECK"); + downloadBtn->setValue("failed to check for update"); + } else if (params.getBool("UpdaterFetchAvailable")) { + downloadBtn->setText("DOWNLOAD"); + downloadBtn->setValue("update available"); + } else { + QString lastUpdate = "never"; + auto tm = params.get("LastUpdateTime"); + if (!tm.empty()) { + lastUpdate = timeAgo(QDateTime::fromString(QString::fromStdString(tm + "Z"), Qt::ISODate)); + } + downloadBtn->setText("CHECK"); + downloadBtn->setValue("up to date, last checked " + lastUpdate); + } + downloadBtn->setEnabled(true); + } + targetBranchBtn->setValue(QString::fromStdString(params.get("UpdaterTargetBranch"))); + + // current + new versions + versionLbl->setText(QString::fromStdString(params.get("UpdaterCurrentDescription")).left(40)); + versionLbl->setDescription(QString::fromStdString(params.get("UpdaterCurrentReleaseNotes"))); + + installBtn->setVisible(!is_onroad && params.getBool("UpdateAvailable")); + installBtn->setValue(QString::fromStdString(params.get("UpdaterNewDescription")).left(35)); + installBtn->setDescription(QString::fromStdString(params.get("UpdaterNewReleaseNotes"))); + + update(); +} diff --git a/selfdrive/ui/qt/widgets/controls.cc b/selfdrive/ui/qt/widgets/controls.cc index 3264fd3aac..b5f646c379 100644 --- a/selfdrive/ui/qt/widgets/controls.cc +++ b/selfdrive/ui/qt/widgets/controls.cc @@ -42,6 +42,12 @@ AbstractControl::AbstractControl(const QString &title, const QString &desc, cons title_label->setStyleSheet("font-size: 50px; font-weight: 400; text-align: left"); hlayout->addWidget(title_label); + // value next to control button + value = new QLabel(); + value->setAlignment(Qt::AlignRight | Qt::AlignVCenter); + value->setStyleSheet("color: #aaaaaa"); + hlayout->addWidget(value); + main_layout->addLayout(hlayout); // description @@ -54,7 +60,7 @@ AbstractControl::AbstractControl(const QString &title, const QString &desc, cons connect(title_label, &QPushButton::clicked, [=]() { if (!description->isVisible()) { - emit showDescription(); + emit showDescriptionEvent(); } if (!description->text().isEmpty()) { diff --git a/selfdrive/ui/qt/widgets/controls.h b/selfdrive/ui/qt/widgets/controls.h index d8546bb3b5..c42716828f 100644 --- a/selfdrive/ui/qt/widgets/controls.h +++ b/selfdrive/ui/qt/widgets/controls.h @@ -45,8 +45,17 @@ public: title_label->setText(title); } + void setValue(const QString &val) { + value->setText(val); + } + +public slots: + void showDescription() { + description->setVisible(true); + }; + signals: - void showDescription(); + void showDescriptionEvent(); protected: AbstractControl(const QString &title, const QString &desc = "", const QString &icon = "", QWidget *parent = nullptr); @@ -54,6 +63,9 @@ protected: QHBoxLayout *hlayout; QPushButton *title_label; + +private: + QLabel *value; QLabel *description = nullptr; }; diff --git a/selfdrive/ui/qt/widgets/offroad_alerts.cc b/selfdrive/ui/qt/widgets/offroad_alerts.cc index 937ea02f86..ceb823fb2b 100644 --- a/selfdrive/ui/qt/widgets/offroad_alerts.cc +++ b/selfdrive/ui/qt/widgets/offroad_alerts.cc @@ -112,7 +112,7 @@ UpdateAlert::UpdateAlert(QWidget *parent) : AbstractAlert(true, parent) { bool UpdateAlert::refresh() { bool updateAvailable = params.getBool("UpdateAvailable"); if (updateAvailable) { - releaseNotes->setText(params.get("ReleaseNotes").c_str()); + releaseNotes->setText(params.get("UpdaterNewReleaseNotes").c_str()); } return updateAvailable; } diff --git a/selfdrive/ui/qt/widgets/ssh_keys.cc b/selfdrive/ui/qt/widgets/ssh_keys.cc index f17604b3e5..1097a89268 100644 --- a/selfdrive/ui/qt/widgets/ssh_keys.cc +++ b/selfdrive/ui/qt/widgets/ssh_keys.cc @@ -5,10 +5,6 @@ #include "selfdrive/ui/qt/widgets/input.h" SshControl::SshControl() : ButtonControl(tr("SSH Keys"), "", tr("Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username.")) { - username_label.setAlignment(Qt::AlignRight | Qt::AlignVCenter); - username_label.setStyleSheet("color: #aaaaaa"); - hlayout->insertWidget(1, &username_label); - QObject::connect(this, &ButtonControl::clicked, [=]() { if (text() == tr("ADD")) { QString username = InputDialog::getText(tr("Enter your GitHub username"), this); @@ -30,10 +26,10 @@ SshControl::SshControl() : ButtonControl(tr("SSH Keys"), "", tr("Warning: This g void SshControl::refresh() { QString param = QString::fromStdString(params.get("GithubSshKeys")); if (param.length()) { - username_label.setText(QString::fromStdString(params.get("GithubUsername"))); + setValue(QString::fromStdString(params.get("GithubUsername"))); setText(tr("REMOVE")); } else { - username_label.setText(""); + setValue(""); setText(tr("ADD")); } setEnabled(true); diff --git a/selfdrive/ui/qt/widgets/ssh_keys.h b/selfdrive/ui/qt/widgets/ssh_keys.h index 01e2ab83ce..920bd651e2 100644 --- a/selfdrive/ui/qt/widgets/ssh_keys.h +++ b/selfdrive/ui/qt/widgets/ssh_keys.h @@ -27,8 +27,6 @@ public: private: Params params; - QLabel username_label; - void refresh(); void getUserKeys(const QString &username); }; diff --git a/selfdrive/ui/tests/cycle_offroad_alerts.py b/selfdrive/ui/tests/cycle_offroad_alerts.py index 6b6aea4477..8a3d9ec45a 100755 --- a/selfdrive/ui/tests/cycle_offroad_alerts.py +++ b/selfdrive/ui/tests/cycle_offroad_alerts.py @@ -20,7 +20,7 @@ if __name__ == "__main__": params.put_bool("UpdateAvailable", True) r = open(os.path.join(BASEDIR, "RELEASES.md")).read() r = r[:r.find('\n\n')] # Slice latest release notes - params.put("ReleaseNotes", r + "\n") + params.put("UpdaterNewReleaseNotes", r + "\n") time.sleep(t) params.put_bool("UpdateAvailable", False) diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 9be6658d19..4262473fb2 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -193,7 +193,7 @@ 変更 - + Select a language 言語を選択 @@ -418,7 +418,7 @@ prime subscription. Sign up now: https://connect.comma.ai 詳しくはこちら:https://connect.comma.ai - + No home location set 自宅の住所はまだ @@ -432,7 +432,7 @@ location set 設定されていません - + no recent destinations 最近の目的地履歴がありません @@ -718,7 +718,7 @@ location set SettingsWindow - + × × @@ -983,68 +983,47 @@ location set SoftwarePanel - - Git Branch - Git ブランチ + + Updates are only downloaded while the car is off. + - - Git Commit - Git コミット - - - - OS Version - OS バージョン + + Current Version + - - Version - バージョン + + Download + - - Last Update Check - 最終更新確認 + + Install Update + - The last time openpilot successfully checked for an update. The updater only runs while the car is off. - openpilotが最後にアップデートの確認に成功してからの時間です。アップデート処理は、車の電源が切れているときのみ実行されます。 - - - - Check for Update - 更新プログラムをチェック - - - - CHECKING - 確認中 + INSTALL + - - Switch Branch - ブランチの切り替え + + Target Branch + - ENTER - 切替 + SELECT + - - - The new branch will be pulled the next time the updater runs. - updater を実行する時にブランチを切り替えます。 - - - - Enter branch name - ブランチ名を入力 + + Select a branch + - + UNINSTALL アンインストール @@ -1059,13 +1038,8 @@ location set アンインストールしてもよろしいですか? - - failed to fetch update - 更新のダウンロードにエラーが発生しました - - - - + + CHECK 確認 @@ -1083,7 +1057,7 @@ location set 警告: これは、GitHub の設定にあるすべての公開鍵への SSH アクセスを許可するものです。自分以外の GitHub のユーザー名を入力しないでください。コンマのスタッフが GitHub のユーザー名を追加するようお願いすることはありません。 - + ADD 追加 @@ -1153,7 +1127,7 @@ location set TogglesPanel - + Enable openpilot openpilot を有効化 @@ -1290,12 +1264,11 @@ location set WifiUI - Scanning for networks... ネットワークをスキャン中... - + CONNECTING... 接続中... diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 3e329a72ab..b517c8320e 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -193,7 +193,7 @@ 변경 - + Select a language 언어를 선택하세요 @@ -418,7 +418,7 @@ prime subscription. Sign up now: https://connect.comma.ai 등록:https://connect.comma.ai - + No home location set 집 @@ -432,7 +432,7 @@ location set 설정되지않음 - + no recent destinations 최근 목적지 없음 @@ -718,7 +718,7 @@ location set SettingsWindow - + × × @@ -983,68 +983,47 @@ location set SoftwarePanel - - Git Branch - Git 브렌치 + + Updates are only downloaded while the car is off. + - - Git Commit - Git 커밋 - - - - OS Version - OS 버전 + + Current Version + - - Version - 버전 + + Download + - - Last Update Check - 최신 업데이트 검사 + + Install Update + - The last time openpilot successfully checked for an update. The updater only runs while the car is off. - 최근에 openpilot이 업데이트를 성공적으로 확인했습니다. 업데이트 프로그램은 차량 연결이 해제되었을때만 작동합니다. - - - - Check for Update - 업데이트 확인 - - - - CHECKING - 확인중 + INSTALL + - - Switch Branch - 브랜치 변경 + + Target Branch + - ENTER - 입력하세요 + SELECT + - - - The new branch will be pulled the next time the updater runs. - 다음 업데이트 프로그램이 실행될 때 새 브랜치가 적용됩니다. - - - - Enter branch name - 브랜치명 입력 + + Select a branch + - + UNINSTALL 제거 @@ -1059,13 +1038,8 @@ location set 제거하시겠습니까? - - failed to fetch update - 업데이트를 가져올수없습니다 - - - - + + CHECK 확인 @@ -1083,7 +1057,7 @@ location set 경고: 허용으로 설정하면 GitHub 설정의 모든 공용 키에 대한 SSH 액세스 권한이 부여됩니다. GitHub 사용자 ID 이외에는 입력하지 마십시오. comma에서는 GitHub ID를 추가하라는 요청을 하지 않습니다. - + ADD 추가 @@ -1153,7 +1127,7 @@ location set TogglesPanel - + Enable openpilot openpilot 사용 @@ -1290,12 +1264,11 @@ location set WifiUI - Scanning for networks... 네트워크 검색 중... - + CONNECTING... 연결중... diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index b729678a2c..91ffabc625 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -193,7 +193,7 @@ ALTERAR - + Select a language Selecione o Idioma @@ -419,7 +419,7 @@ prime subscription. Sign up now: https://connect.comma.ai uma assinatura prime Inscreva-se agora: https://connect.comma.ai - + No home location set Sem local @@ -433,7 +433,7 @@ location set trabalho definido - + no recent destinations sem destinos recentes @@ -722,7 +722,7 @@ trabalho definido SettingsWindow - + × × @@ -987,68 +987,47 @@ trabalho definido SoftwarePanel - - Git Branch - Git Branch - - - - Git Commit - Último Commit + + Updates are only downloaded while the car is off. + - - OS Version - Versão do Sistema + + Current Version + - - Version - Versão + + Download + - - Last Update Check - Verificação da última atualização + + Install Update + - The last time openpilot successfully checked for an update. The updater only runs while the car is off. - A última vez que o openpilot verificou com sucesso uma atualização. O atualizador só funciona com o carro desligado. - - - - Check for Update - Verifique atualizações - - - - CHECKING - VERIFICANDO - - - - Switch Branch - Alterar Branch + INSTALL + - - ENTER - INSERIR + + Target Branch + - - The new branch will be pulled the next time the updater runs. - A nova branch será aplicada ao verificar atualizações. + SELECT + - - Enter branch name - Inserir o nome da branch + + Select a branch + - + UNINSTALL DESINSTALAR @@ -1063,13 +1042,8 @@ trabalho definido Tem certeza que quer desinstalar? - - failed to fetch update - falha ao buscar atualização - - - - + + CHECK VERIFICAR @@ -1087,7 +1061,7 @@ trabalho definido Aviso: isso concede acesso SSH a todas as chaves públicas nas configurações do GitHub. Nunca insira um nome de usuário do GitHub que não seja o seu. Um funcionário da comma NUNCA pedirá que você adicione seu nome de usuário do GitHub. - + ADD ADICIONAR @@ -1157,7 +1131,7 @@ trabalho definido TogglesPanel - + Enable openpilot Ativar openpilot @@ -1294,12 +1268,11 @@ trabalho definido WifiUI - Scanning for networks... Procurando redes... - + CONNECTING... CONECTANDO... diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 606e70726f..8fce4e01a7 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -193,7 +193,7 @@ 切换 - + Select a language 选择语言 @@ -418,7 +418,7 @@ prime subscription. Sign up now: https://connect.comma.ai 立即注册:https://connect.comma.ai - + No home location set 家:未设定 @@ -430,7 +430,7 @@ location set 工作:未设定 - + no recent destinations 无最近目的地 @@ -716,7 +716,7 @@ location set SettingsWindow - + × × @@ -981,68 +981,47 @@ location set SoftwarePanel - - Git Branch - Git Branch - - - - Git Commit - Git Commit + + Updates are only downloaded while the car is off. + - - OS Version - 系统版本 + + Current Version + - - Version - 软件版本 + + Download + - - Last Update Check - 上次检查更新 + + Install Update + - The last time openpilot successfully checked for an update. The updater only runs while the car is off. - 上一次成功检查更新的时间。更新程序仅在汽车熄火时运行。 - - - - Check for Update - 检查更新 - - - - CHECKING - 正在检查更新 - - - - Switch Branch - 切换分支 + INSTALL + - - ENTER - 输入 + + Target Branch + - - The new branch will be pulled the next time the updater runs. - 分支将在更新服务下次启动时自动切换。 + SELECT + - - Enter branch name - 输入分支名称 + + Select a branch + - + UNINSTALL 卸载 @@ -1057,13 +1036,8 @@ location set 您确定要卸载吗? - - failed to fetch update - 获取更新失败 - - - - + + CHECK 查看 @@ -1081,7 +1055,7 @@ location set 警告:这将授予SSH访问权限给您GitHub设置中的所有公钥。切勿输入您自己以外的GitHub用户名。comma员工永远不会要求您添加他们的GitHub用户名。 - + ADD 添加 @@ -1151,7 +1125,7 @@ location set TogglesPanel - + Enable openpilot 启用openpilot @@ -1288,12 +1262,11 @@ location set WifiUI - Scanning for networks... 正在扫描网络…… - + CONNECTING... 正在连接…… diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index b5b737ca25..022d41be81 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -193,7 +193,7 @@ 更改 - + Select a language 選擇語言 @@ -418,7 +418,7 @@ prime subscription. Sign up now: https://connect.comma.ai 立即註冊:https://connect.comma.ai - + No home location set 未設定 @@ -432,7 +432,7 @@ location set 工作位置 - + no recent destinations 沒有最近的導航記錄 @@ -718,7 +718,7 @@ location set SettingsWindow - + × × @@ -983,68 +983,47 @@ location set SoftwarePanel - - Git Branch - Git 分支 - - - - Git Commit - Git 提交 + + Updates are only downloaded while the car is off. + - - OS Version - 系統版本 + + Current Version + - - Version - 版本 + + Download + - - Last Update Check - 上次檢查時間 + + Install Update + - The last time openpilot successfully checked for an update. The updater only runs while the car is off. - 上次成功檢查更新的時間。更新系統只會在車子熄火時執行。 - - - - Check for Update - 檢查更新 - - - - CHECKING - 檢查中 - - - - Switch Branch - 切換分支 + INSTALL + - - ENTER - 切換 + + Target Branch + - - The new branch will be pulled the next time the updater runs. - 新的分支將會在下次檢查更新時切換過去。 + SELECT + - - Enter branch name - 輸入分支名稱 + + Select a branch + - + UNINSTALL 卸載 @@ -1059,13 +1038,8 @@ location set 您確定您要卸載嗎? - - failed to fetch update - 下載更新失敗 - - - - + + CHECK 檢查 @@ -1083,7 +1057,7 @@ location set 警告:這將授權給 GitHub 帳號中所有公鑰 SSH 訪問權限。切勿輸入非您自己的 GitHub 用戶名。comma 員工「永遠不會」要求您添加他們的 GitHub 用戶名。 - + ADD 新增 @@ -1153,7 +1127,7 @@ location set TogglesPanel - + Enable openpilot 啟用 openpilot @@ -1290,12 +1264,11 @@ location set WifiUI - Scanning for networks... 掃描無線網路中... - + CONNECTING... 連線中... diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 65f8425201..79b759a906 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -23,6 +23,7 @@ # disable this service. import os +import re import datetime import subprocess import psutil @@ -31,8 +32,9 @@ import signal import fcntl import time import threading +from collections import defaultdict from pathlib import Path -from typing import List, Tuple, Optional +from typing import List, Union, Optional from markdown_it import MarkdownIt from common.basedir import BASEDIR @@ -54,20 +56,27 @@ DAYS_NO_CONNECTIVITY_MAX = 14 # do not allow to engage after this many days DAYS_NO_CONNECTIVITY_PROMPT = 10 # send an offroad prompt after this many days class WaitTimeHelper: - def __init__(self, proc): - self.proc = proc + def __init__(self): self.ready_event = threading.Event() + self.only_check_for_update = False signal.signal(signal.SIGHUP, self.update_now) + signal.signal(signal.SIGUSR1, self.check_now) def update_now(self, signum: int, frame) -> None: - cloudlog.info("caught SIGHUP, running update check immediately") + cloudlog.info("caught SIGHUP, attempting to downloading update") + self.only_check_for_update = False + self.ready_event.set() + + def check_now(self, signum: int, frame) -> None: + cloudlog.info("caught SIGUSR1, checking for updates") + self.only_check_for_update = True self.ready_event.set() def sleep(self, t: float) -> None: self.ready_event.wait(timeout=t) -def run(cmd: List[str], cwd: Optional[str] = None): +def run(cmd: List[str], cwd: Optional[str] = None) -> str: return subprocess.check_output(cmd, cwd=cwd, stderr=subprocess.STDOUT, encoding='utf8') @@ -80,59 +89,19 @@ def set_consistent_flag(consistent: bool) -> None: consistent_file.unlink(missing_ok=True) os.sync() - -def set_params(new_version: bool, failed_count: int, exception: Optional[str]) -> None: - params = Params() - - params.put("UpdateFailedCount", str(failed_count)) - - last_update = datetime.datetime.utcnow() - if failed_count == 0: - t = last_update.isoformat() - params.put("LastUpdateTime", t.encode('utf8')) - else: - try: - t = params.get("LastUpdateTime", encoding='utf8') - last_update = datetime.datetime.fromisoformat(t) - except (TypeError, ValueError): - pass - - if exception is None: - params.remove("LastUpdateException") - else: - params.put("LastUpdateException", exception) - - # Write out release notes for new versions - if new_version: +def parse_release_notes(basedir: str) -> bytes: + try: + with open(os.path.join(basedir, "RELEASES.md"), "rb") as f: + r = f.read().split(b'\n\n', 1)[0] # Slice latest release notes try: - with open(os.path.join(FINALIZED, "RELEASES.md"), "rb") as f: - r = f.read().split(b'\n\n', 1)[0] # Slice latest release notes - try: - params.put("ReleaseNotes", MarkdownIt().render(r.decode("utf-8"))) - except Exception: - params.put("ReleaseNotes", r + b"\n") + return bytes(MarkdownIt().render(r.decode("utf-8")), encoding="utf-8") except Exception: - params.put("ReleaseNotes", "") - params.put_bool("UpdateAvailable", True) - - # Handle user prompt - for alert in ("Offroad_UpdateFailed", "Offroad_ConnectivityNeeded", "Offroad_ConnectivityNeededPrompt"): - set_offroad_alert(alert, False) - - now = datetime.datetime.utcnow() - dt = now - last_update - if failed_count > 15 and exception is not None: - if is_tested_branch(): - extra_text = "Ensure the software is correctly installed" - else: - extra_text = exception - set_offroad_alert("Offroad_UpdateFailed", True, extra_text=extra_text) - elif dt.days > DAYS_NO_CONNECTIVITY_MAX and failed_count > 1: - set_offroad_alert("Offroad_ConnectivityNeeded", True) - elif dt.days > DAYS_NO_CONNECTIVITY_PROMPT: - remaining = max(DAYS_NO_CONNECTIVITY_MAX - dt.days, 1) - set_offroad_alert("Offroad_ConnectivityNeededPrompt", True, extra_text=f"{remaining} day{'' if remaining == 1 else 's'}.") - + return r + b"\n" + except FileNotFoundError: + pass + except Exception: + cloudlog.exception("failed to parse release notes") + return b"" def setup_git_options(cwd: str) -> None: # We sync FS object atimes (which NEOS doesn't use) and mtimes, but ctimes @@ -267,65 +236,161 @@ def handle_agnos_update() -> None: set_offroad_alert("Offroad_NeosUpdate", False) -def check_git_fetch_result(fetch_txt: str) -> bool: - err_msg = "Failed to add the host to the list of known hosts (/data/data/com.termux/files/home/.ssh/known_hosts).\n" - return len(fetch_txt) > 0 and (fetch_txt != err_msg) +class Updater: + def __init__(self): + self.params = Params() + self.branches = defaultdict(lambda: None) + + @property + def target_branch(self) -> str: + b: Union[str, None] = self.params.get("UpdaterTargetBranch", encoding='utf-8') + if b is None: + b = self.get_branch(BASEDIR) + self.params.put("UpdaterTargetBranch", b) + return b + + @property + def update_ready(self) -> bool: + consistent_file = Path(os.path.join(FINALIZED, ".overlay_consistent")) + if consistent_file.is_file(): + hash_mismatch = self.get_commit_hash(BASEDIR) != self.branches[self.target_branch] + branch_mismatch = self.get_branch(BASEDIR) != self.target_branch + on_target_branch = self.get_branch(FINALIZED) == self.target_branch + return ((hash_mismatch or branch_mismatch) and on_target_branch) + return False + + @property + def update_available(self) -> bool: + if os.path.isdir(OVERLAY_MERGED): + hash_mismatch = self.get_commit_hash(OVERLAY_MERGED) != self.branches[self.target_branch] + branch_mismatch = self.get_branch(OVERLAY_MERGED) != self.target_branch + return hash_mismatch or branch_mismatch + return False + + def get_branch(self, path: str) -> str: + return run(["git", "rev-parse", "--abbrev-ref", "HEAD"], path).rstrip() + + def get_commit_hash(self, path: str = OVERLAY_MERGED) -> str: + return run(["git", "rev-parse", "HEAD"], path).rstrip() + + def set_params(self, failed_count: int, exception: Optional[str]) -> None: + self.params.put("UpdateFailedCount", str(failed_count)) + + self.params.put_bool("UpdaterFetchAvailable", self.update_available) + self.params.put("UpdaterAvailableBranches", ','.join(self.branches.keys())) + + last_update = datetime.datetime.utcnow() + if failed_count == 0: + t = last_update.isoformat() + self.params.put("LastUpdateTime", t.encode('utf8')) + else: + try: + t = self.params.get("LastUpdateTime", encoding='utf8') + last_update = datetime.datetime.fromisoformat(t) + except (TypeError, ValueError): + pass -def check_for_update() -> Tuple[bool, bool]: - setup_git_options(OVERLAY_MERGED) - try: - git_fetch_output = run(["git", "fetch", "--dry-run"], OVERLAY_MERGED) - return True, check_git_fetch_result(git_fetch_output) - except subprocess.CalledProcessError: - return False, False - + if exception is None: + self.params.remove("LastUpdateException") + else: + self.params.put("LastUpdateException", exception) -def fetch_update() -> bool: - cloudlog.info("attempting git fetch inside staging overlay") + # Write out current and new version info + def get_description(basedir: str) -> str: + version = "" + branch = "" + commit = "" + try: + branch = self.get_branch(basedir) + commit = self.get_commit_hash(basedir) + with open(os.path.join(basedir, "common", "version.h")) as f: + version = f.read().split('"')[1] + except Exception: + pass + return f"{version} / {branch} / {commit[:7]}" + self.params.put("UpdaterCurrentDescription", get_description(BASEDIR)) + self.params.put("UpdaterCurrentReleaseNotes", parse_release_notes(BASEDIR)) + self.params.put("UpdaterNewDescription", get_description(FINALIZED)) + self.params.put("UpdaterNewReleaseNotes", parse_release_notes(FINALIZED)) + self.params.put_bool("UpdateAvailable", self.update_ready) + + # Handle user prompt + for alert in ("Offroad_UpdateFailed", "Offroad_ConnectivityNeeded", "Offroad_ConnectivityNeededPrompt"): + set_offroad_alert(alert, False) + + now = datetime.datetime.utcnow() + dt = now - last_update + if failed_count > 15 and exception is not None: + if is_tested_branch(): + extra_text = "Ensure the software is correctly installed. Uninstall and re-install if this error persists." + else: + extra_text = exception + set_offroad_alert("Offroad_UpdateFailed", True, extra_text=extra_text) + elif dt.days > DAYS_NO_CONNECTIVITY_MAX and failed_count > 1: + set_offroad_alert("Offroad_ConnectivityNeeded", True) + elif dt.days > DAYS_NO_CONNECTIVITY_PROMPT: + remaining = max(DAYS_NO_CONNECTIVITY_MAX - dt.days, 1) + set_offroad_alert("Offroad_ConnectivityNeededPrompt", True, extra_text=f"{remaining} day{'' if remaining == 1 else 's'}.") + + def check_for_update(self) -> None: + cloudlog.info("checking for updates") + + excluded_branches = ('release2', 'release2-staging', 'dashcam', 'dashcam-staging') + + setup_git_options(OVERLAY_MERGED) + output = run(["git", "ls-remote", "--heads"], OVERLAY_MERGED) + + self.branches = defaultdict(lambda: None) + for line in output.split('\n'): + ls_remotes_re = r'(?P\b[0-9a-f]{5,40}\b)(\s+)(refs\/heads\/)(?P.*$)' + x = re.fullmatch(ls_remotes_re, line.strip()) + if x is not None and x.group('branch_name') not in excluded_branches: + self.branches[x.group('branch_name')] = x.group('commit_sha') + + cur_branch = self.get_branch(OVERLAY_MERGED) + cur_commit = self.get_commit_hash(OVERLAY_MERGED) + new_branch = self.target_branch + new_commit = self.branches[new_branch] + if (cur_branch, cur_commit) != (new_branch, new_commit): + cloudlog.info(f"update available, {cur_branch} ({cur_commit[:7]}) -> {new_branch} ({new_commit[:7]})") + else: + cloudlog.info(f"up to date on {cur_branch} ({cur_commit[:7]})") - setup_git_options(OVERLAY_MERGED) + def fetch_update(self) -> None: + cloudlog.info("attempting git fetch inside staging overlay") - git_fetch_output = run(["git", "fetch"], OVERLAY_MERGED) - cloudlog.info("git fetch success: %s", git_fetch_output) + self.params.put("UpdaterState", "downloading...") - cur_hash = run(["git", "rev-parse", "HEAD"], OVERLAY_MERGED).rstrip() - upstream_hash = run(["git", "rev-parse", "@{u}"], OVERLAY_MERGED).rstrip() - new_version: bool = cur_hash != upstream_hash - git_fetch_result = check_git_fetch_result(git_fetch_output) + # TODO: cleanly interrupt this and invalidate old update + set_consistent_flag(False) + self.params.put_bool("UpdateAvailable", False) - new_branch = Params().get("SwitchToBranch", encoding='utf8') - if new_branch is not None: - new_version = True + setup_git_options(OVERLAY_MERGED) - cloudlog.info(f"comparing {cur_hash} to {upstream_hash}") - if new_version or git_fetch_result: - cloudlog.info("Running update") + branch = self.target_branch + git_fetch_output = run(["git", "fetch", "origin", branch], OVERLAY_MERGED) + cloudlog.info("git fetch success: %s", git_fetch_output) - if new_version: - cloudlog.info("git reset in progress") - cmds = [ - ["git", "reset", "--hard", "@{u}"], - ["git", "clean", "-xdf"], - ["git", "submodule", "init"], - ["git", "submodule", "update"], - ] - if new_branch is not None: - cloudlog.info(f"switching to branch {repr(new_branch)}") - cmds.insert(0, ["git", "checkout", "-f", new_branch]) - r = [run(cmd, OVERLAY_MERGED) for cmd in cmds] - cloudlog.info("git reset success: %s", '\n'.join(r)) + cloudlog.info("git reset in progress") + cmds = [ + ["git", "checkout", "--force", "--no-recurse-submodules", branch], + ["git", "reset", "--hard", f"origin/{branch}"], + ["git", "clean", "-xdf"], + ["git", "submodule", "init"], + ["git", "submodule", "update"], + ] + r = [run(cmd, OVERLAY_MERGED) for cmd in cmds] + cloudlog.info("git reset success: %s", '\n'.join(r)) - if AGNOS: - handle_agnos_update() + # TODO: show agnos download progress + if AGNOS: + handle_agnos_update() # Create the finalized, ready-to-swap update + self.params.put("UpdaterState", "finalizing update...") finalize_update() - cloudlog.info("openpilot update successful!") - else: - cloudlog.info("nothing new from git at this time") - - return new_version + cloudlog.info("finalize success!") def main() -> None: @@ -357,8 +422,12 @@ def main() -> None: overlay_init = Path(os.path.join(BASEDIR, ".overlay_init")) overlay_init.unlink(missing_ok=True) + updater = Updater() update_failed_count = 0 # TODO: Load from param? - wait_helper = WaitTimeHelper(proc) + + # no fetch on the first time + wait_helper = WaitTimeHelper() + wait_helper.only_check_for_update = True # Run the update loop while True: @@ -366,21 +435,24 @@ def main() -> None: # Attempt an update exception = None - new_version = False - update_failed_count += 1 try: + # TODO: reuse overlay from previous updated instance if it looks clean init_overlay() - # TODO: still needed? skip this and just fetch? - # Lightweight internt check - internet_ok, update_available = check_for_update() - if internet_ok and not update_available: - update_failed_count = 0 + # ensure we have some params written soon after startup + updater.set_params(update_failed_count, exception) + update_failed_count += 1 + + # check for update + params.put("UpdaterState", "checking...") + updater.check_for_update() - # Fetch update - if internet_ok: - new_version = fetch_update() - update_failed_count = 0 + # download update + if wait_helper.only_check_for_update: + cloudlog.info("skipping fetch this cycle") + else: + updater.fetch_update() + update_failed_count = 0 except subprocess.CalledProcessError as e: cloudlog.event( "update process failed", @@ -396,12 +468,14 @@ def main() -> None: overlay_init.unlink(missing_ok=True) try: - set_params(new_version, update_failed_count, exception) + params.put("UpdaterState", "idle") + updater.set_params(update_failed_count, exception) except Exception: cloudlog.exception("uncaught updated exception while setting params, shouldn't happen") # infrequent attempts if we successfully updated recently - wait_helper.sleep(5*60 if update_failed_count > 0 else 90*60) + wait_helper.only_check_for_update = False + wait_helper.sleep(5*60 if update_failed_count > 0 else 1.5*60*60) if __name__ == "__main__": From d5410dfac5e2bf9f68edb16d18d8875647021b13 Mon Sep 17 00:00:00 2001 From: Igor Biletskyy Date: Thu, 15 Sep 2022 15:35:24 -0700 Subject: [PATCH 110/152] Panda health: names and mixup fix (#25774) * init * naming * fix names * bump cereal * bump panda * bump panda --- cereal | 2 +- panda | 2 +- selfdrive/boardd/boardd.cc | 8 ++++---- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/cereal b/cereal index bd2f7fa567..513dfc7ee0 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit bd2f7fa56706bcec3c9906bd57c2ec46f0666ac5 +Subproject commit 513dfc7ee001243cd68a57a9d92fe3170fc49c7d diff --git a/panda b/panda index 38257a93e4..046fd58e8d 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 38257a93e4733819a109a4ef52efed1bbeb45cc4 +Subproject commit 046fd58e8d64c58ed80769fcbec5ac2417a04c71 diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 5ff6d56e69..0872a94712 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -346,14 +346,14 @@ std::optional send_panda_states(PubMaster *pm, const std::vector auto ps = pss[i]; ps.setUptime(health.uptime_pkt); - ps.setBlockedCnt(health.blocked_msg_cnt_pkt); + ps.setSafetyTxBlocked(health.safety_tx_blocked_pkt); + ps.setSafetyRxInvalid(health.safety_rx_invalid_pkt); ps.setIgnitionLine(health.ignition_line_pkt); ps.setIgnitionCan(health.ignition_can_pkt); ps.setControlsAllowed(health.controls_allowed_pkt); ps.setGasInterceptorDetected(health.gas_interceptor_detected_pkt); - ps.setCanRxErrs(health.can_rx_errs_pkt); - ps.setCanSendErrs(health.can_send_errs_pkt); - ps.setCanFwdErrs(health.can_fwd_errs_pkt); + ps.setTxBufferOverflow(health.tx_buffer_overflow_pkt); + ps.setRxBufferOverflow(health.rx_buffer_overflow_pkt); ps.setGmlanSendErrs(health.gmlan_send_errs_pkt); ps.setPandaType(panda->hw_type); ps.setSafetyModel(cereal::CarParams::SafetyModel(health.safety_mode_pkt)); From 85b433760a2c1a139062a40040e096b9de880e33 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 16 Sep 2022 06:43:27 +0800 Subject: [PATCH 111/152] Params: add new method to get all keys (#25779) * allKeys * cleanup and test Co-authored-by: Adeeb Shihadeh --- common/params.cc | 9 +++++++++ common/params.h | 2 ++ common/params_pyx.pyx | 5 +++++ common/tests/test_params.py | 8 ++++++++ 4 files changed, 24 insertions(+) diff --git a/common/params.cc b/common/params.cc index 8ff5fc539d..7b2d4490ea 100644 --- a/common/params.cc +++ b/common/params.cc @@ -3,6 +3,7 @@ #include #include +#include #include #include @@ -203,6 +204,14 @@ Params::Params(const std::string &path) { params_path = path.empty() ? default_param_path : ensure_params_path(prefix, path); } +std::vector Params::allKeys() const { + std::vector ret; + for (auto &p : keys) { + ret.push_back(p.first); + } + return ret; +} + bool Params::checkKey(const std::string &key) { return keys.find(key) != keys.end(); } diff --git a/common/params.h b/common/params.h index aa4b1d7af3..7758a015f6 100644 --- a/common/params.h +++ b/common/params.h @@ -2,6 +2,7 @@ #include #include +#include enum ParamKeyType { PERSISTENT = 0x02, @@ -15,6 +16,7 @@ enum ParamKeyType { class Params { public: Params(const std::string &path = {}); + std::vector allKeys() const; bool checkKey(const std::string &key); ParamKeyType getKeyType(const std::string &key); inline std::string getParamPath(const std::string &key = {}) { diff --git a/common/params_pyx.pyx b/common/params_pyx.pyx index 8d52b8d3f6..bbddda46ea 100755 --- a/common/params_pyx.pyx +++ b/common/params_pyx.pyx @@ -2,6 +2,7 @@ # cython: language_level = 3 from libcpp cimport bool from libcpp.string cimport string +from libcpp.vector cimport vector import threading cdef extern from "common/params.h": @@ -22,6 +23,7 @@ cdef extern from "common/params.h": bool checkKey(string) nogil string getParamPath(string) nogil void clearAll(ParamKeyType) + vector[string] allKeys() def ensure_bytes(v): @@ -99,6 +101,9 @@ cdef class Params: cdef string key_bytes = ensure_bytes(key) return self.p.getParamPath(key_bytes).decode("utf-8") + def all_keys(self): + return self.p.allKeys() + def put_nonblocking(key, val, d=""): threading.Thread(target=lambda: Params(d).put(key, val)).start() diff --git a/common/tests/test_params.py b/common/tests/test_params.py index 899a47fe34..ec13e82217 100644 --- a/common/tests/test_params.py +++ b/common/tests/test_params.py @@ -98,6 +98,14 @@ class TestParams(unittest.TestCase): assert q.get("CarParams") is None assert q.get("CarParams", True) == b"1" + def test_params_all_keys(self): + keys = Params().all_keys() + + # sanity checks + assert len(keys) > 20 + assert len(keys) == len(set(keys)) + assert b"CarParams" in keys + if __name__ == "__main__": unittest.main() From ce9c689bb4f8924d47a9beb264081ed922ce9e91 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 15 Sep 2022 16:07:51 -0700 Subject: [PATCH 112/152] Car docs: more consistent package names (#25797) * update docs * Revert "update docs" This reverts commit a5127198fe8e43ecadb0cbde432773f4da2e212a. * spell it out * update docs * add (ACC) for consistency * All VW --- docs/CARS.md | 110 ++++++++++++++--------------- selfdrive/car/chrysler/values.py | 2 +- selfdrive/car/gm/values.py | 2 +- selfdrive/car/volkswagen/values.py | 14 ++-- 4 files changed, 64 insertions(+), 64 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 47694fffee..510500dab7 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -11,27 +11,27 @@ A supported vehicle is one that just works when you install a comma three. All s |Acura|ILX 2016-19|AcuraWatch Plus|openpilot|25 mph|25 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| |Acura|RDX 2016-18|AcuraWatch Plus|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| |Acura|RDX 2019-22|All|openpilot|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| -|Audi|A3 2014-19|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Audi|A3 Sportback e-tron 2017-18|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Audi|Q2 2018|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Audi|Q3 2020-21|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Audi|RS3 2018|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Audi|S3 2015-17|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|Q2 2018|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|Q3 2020-21|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|RS3 2018|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|S3 2015-17|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| |Cadillac|Escalade ESV 2016[1](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| |Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|Stock|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| |Chevrolet|Silverado 1500 2020-21|Safety Package II|Stock|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| -|Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| -|Chrysler|Pacifica 2017-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| -|Chrysler|Pacifica 2019-20|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| +|Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise Control (ACC)|openpilot|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| +|Chrysler|Pacifica 2017-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| +|Chrysler|Pacifica 2019-20|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Chrysler|Pacifica 2021|All|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| -|Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| -|Chrysler|Pacifica Hybrid 2019-22|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| +|Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| +|Chrysler|Pacifica Hybrid 2019-22|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |comma|body|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|None| |Genesis|G70 2018-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| |Genesis|G70 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| |Genesis|G80 2017-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Genesis|G90 2017-18|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| -|GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| +|GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise Control (ACC)|openpilot|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| |GMC|Sierra 1500 2020-21|Driver Alert Package II|Stock|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| |Honda|Accord 2018-22|All|openpilot|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| |Honda|Accord Hybrid 2018-22|All|openpilot|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| @@ -80,8 +80,8 @@ A supported vehicle is one that just works when you install a comma three. All s |Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| |Hyundai|Tucson Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai N| |Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| -|Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| -|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| +|Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| +|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Kia|Ceed 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Kia|EV6 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P| |Kia|Forte 2018|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| @@ -122,9 +122,9 @@ A supported vehicle is one that just works when you install a comma three. All s |Nissan|Leaf 2018-22|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Nissan A| |Nissan|Rogue 2018-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Nissan A| |Nissan|X-Trail 2017|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Nissan A| -|Ram|1500 2019-22|Adaptive Cruise Control|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Ram| -|SEAT|Ateca 2018|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|SEAT|Leon 2014-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Ram|1500 2019-22|Adaptive Cruise Control (ACC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Ram| +|SEAT|Ateca 2018|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|SEAT|Leon 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| |Subaru|Ascent 2019-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A| |Subaru|Crosstrek 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A| |Subaru|Crosstrek 2020-21|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A| @@ -135,13 +135,13 @@ A supported vehicle is one that just works when you install a comma three. All s |Subaru|Outback 2020-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru B| |Subaru|XV 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A| |Subaru|XV 2020-21|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A| -|Škoda|Kamiq 2021[5](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Škoda|Karoq 2019-21[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Škoda|Kodiaq 2018-19|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Škoda|Octavia 2015, 2018-19|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Škoda|Octavia RS 2016|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Škoda|Scala 2020|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Škoda|Superb 2015-18|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Kamiq 2021[5](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Karoq 2019-21[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Kodiaq 2018-19|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Octavia 2015, 2018-19|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Octavia RS 2016|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Scala 2020|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Superb 2015-18|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| |Toyota|Alphard 2019-20|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| |Toyota|Alphard Hybrid 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| |Toyota|Avalon 2016|Toyota Safety Sense P|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| @@ -182,37 +182,37 @@ A supported vehicle is one that just works when you install a comma three. All s |Toyota|RAV4 Hybrid 2019-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| |Toyota|RAV4 Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| |Toyota|Sienna 2018-20|All|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| -|Volkswagen|Arteon 2018-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Arteon eHybrid 2020-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Arteon R 2020-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Atlas 2018-23[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Atlas Cross Sport 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|California 2021[7](#footnotes)|Driver Assistance|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Caravelle 2020[7](#footnotes)|Driver Assistance|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|CC 2018-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|e-Golf 2014-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Golf 2015-20[8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Golf Alltrack 2015-19|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Golf GTD 2015-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Golf GTE 2015-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Golf GTI 2015-21|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Golf R 2015-19[8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Golf SportsVan 2015-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Jetta 2018-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Jetta GLI 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Passat 2015-22[6,7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Passat Alltrack 2015-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Passat GTE 2015-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Polo 2020-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Polo GTI 2020-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|T-Cross 2021[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|T-Roc 2021[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Taos 2022[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Teramont 2018-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Teramont Cross Sport 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Teramont X 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Tiguan 2019-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Touran 2017|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Arteon 2018-22[7,8](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Arteon eHybrid 2020-22[7,8](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Arteon R 2020-22[7,8](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Atlas 2018-23[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Atlas Cross Sport 2021-22[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|California 2021[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Caravelle 2020[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|CC 2018-22[7,8](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|e-Golf 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf 2015-20[8](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf Alltrack 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf GTD 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf GTE 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf GTI 2015-21|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf R 2015-19[8](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf SportsVan 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Jetta 2018-22[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Jetta GLI 2021-22[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Passat 2015-22[6,7,8](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Passat Alltrack 2015-22[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Passat GTE 2015-22[7,8](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Polo 2020-22[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Polo GTI 2020-22[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|T-Cross 2021[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|T-Roc 2021[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Taos 2022[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Teramont 2018-22[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Teramont Cross Sport 2021-22[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Teramont X 2021-22[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Tiguan 2019-22[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Touran 2017|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| 1Requires a community built ASCM harness. NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).
diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index d4ac9f6f00..7180ace524 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -52,7 +52,7 @@ RAM_CARS = RAM_DT | RAM_HD @dataclass class ChryslerCarInfo(CarInfo): - package: str = "Adaptive Cruise Control" + package: str = "Adaptive Cruise Control (ACC)" harness: Enum = Harness.fca CAR_INFO: Dict[str, Optional[Union[ChryslerCarInfo, List[ChryslerCarInfo]]]] = { diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index 21ede171e0..a84cbdc91a 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -71,7 +71,7 @@ class Footnote(Enum): @dataclass class GMCarInfo(CarInfo): - package: str = "Adaptive Cruise Control" + package: str = "Adaptive Cruise Control (ACC)" harness: Enum = Harness.obd_ii footnotes: List[Enum] = field(default_factory=lambda: [Footnote.OBD_II]) diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 6425cd60be..4d17b4e3a6 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -164,7 +164,7 @@ class Footnote(Enum): @dataclass class VWCarInfo(CarInfo): - package: str = "Driver Assistance" + package: str = "Adaptive Cruise Control (ACC) & Lane Assist" harness: Enum = Harness.vw @@ -216,13 +216,13 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = { ], CAR.TROC_MK1: VWCarInfo("Volkswagen T-Roc 2021", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), CAR.AUDI_A3_MK3: [ - VWCarInfo("Audi A3 2014-19", "ACC + Lane Assist"), - VWCarInfo("Audi A3 Sportback e-tron 2017-18", "ACC + Lane Assist"), - VWCarInfo("Audi RS3 2018", "ACC + Lane Assist"), - VWCarInfo("Audi S3 2015-17", "ACC + Lane Assist"), + VWCarInfo("Audi A3 2014-19"), + VWCarInfo("Audi A3 Sportback e-tron 2017-18"), + VWCarInfo("Audi RS3 2018"), + VWCarInfo("Audi S3 2015-17"), ], - CAR.AUDI_Q2_MK1: VWCarInfo("Audi Q2 2018", "ACC + Lane Assist"), - CAR.AUDI_Q3_MK2: VWCarInfo("Audi Q3 2020-21", "ACC + Lane Assist"), + CAR.AUDI_Q2_MK1: VWCarInfo("Audi Q2 2018"), + CAR.AUDI_Q3_MK2: VWCarInfo("Audi Q3 2020-21"), CAR.SEAT_ATECA_MK1: VWCarInfo("SEAT Ateca 2018"), CAR.SEAT_LEON_MK3: VWCarInfo("SEAT Leon 2014-20"), CAR.SKODA_KAMIQ_MK1: VWCarInfo("Škoda Kamiq 2021", footnotes=[Footnote.KAMIQ]), From ae87665e92cb17952abf2b7f182a0302264dc642 Mon Sep 17 00:00:00 2001 From: Lee Jong Mun <43285072+crwusiz@users.noreply.github.com> Date: Fri, 16 Sep 2022 09:04:29 +0900 Subject: [PATCH 113/152] Multilang: add missing Korean translations (#25799) kor translation update --- selfdrive/ui/translations/main_ko.ts | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index b517c8320e..2a827ca4a6 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -985,42 +985,42 @@ location set Updates are only downloaded while the car is off. - + 업데이트는 차량 연결이 해제되어 있는 동안에만 다운로드됩니다. Current Version - + 현재 버전 Download - + 다운로드 Install Update - + 업데이트 설치 INSTALL - + 설치 Target Branch - + 대상 브랜치 SELECT - + 선택 Select a branch - + 브랜치 선택 From 834f212903f5c06a9fe8d6caa6b6da52ac7a7d83 Mon Sep 17 00:00:00 2001 From: cydia2020 <12470297+cydia2020@users.noreply.github.com> Date: Fri, 16 Sep 2022 10:48:17 +1000 Subject: [PATCH 114/152] Multilang: add missing Chinese e2e toggle translations (#25656) * japanese e2e toggle * chinese (simp) * chinese (trad) * OOPS * Mention experimental in details * Also in traditional * Exp. * suggestions * Apply suggestions from code review Co-authored-by: ZwX1616 * add back removed translations from merge * Update selfdrive/ui/translations/main_zh-CHS.ts Co-authored-by: Shane Smiskol Co-authored-by: ZwX1616 --- selfdrive/ui/translations/main_zh-CHS.ts | 4 ++-- selfdrive/ui/translations/main_zh-CHT.ts | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 8fce4e01a7..8a6f856be7 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -1167,7 +1167,7 @@ location set 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + 🌮 端对端纵向控制(实验性功能) 🌮 @@ -1182,7 +1182,7 @@ location set Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. - + 让驾驶模型直接控制油门和刹车,openpilot将会模仿人类司机的驾驶方式。该功能仍非常实验性。 diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 022d41be81..6758305420 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -1169,7 +1169,7 @@ location set 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + 🌮 端對端縱向控制(實驗性功能) 🌮 @@ -1184,7 +1184,7 @@ location set Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. - + 讓駕駛模型直接控製油門和剎車,openpilot將會模仿人類司機的駕駛方式。該功能仍非常實驗性。 From 1aa8c0525ea5339eecd82cb08572636ebbaa7034 Mon Sep 17 00:00:00 2001 From: Jason Shuler Date: Thu, 15 Sep 2022 20:55:02 -0400 Subject: [PATCH 115/152] GM: Chevy Equinox 2019-22 (#25431) * Chevy Equinox Port * LKAS is not standard on 2019, but it's the same package as ACC. (LKAS standard 2020+) * 2019 here too * clean up * add to untested * not in docs Co-authored-by: Shane Smiskol --- selfdrive/car/gm/interface.py | 10 +++++++++- selfdrive/car/gm/values.py | 8 +++++++- selfdrive/car/tests/routes.py | 1 + selfdrive/car/torque_data/override.yaml | 1 + 4 files changed, 18 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index be28890484..49d56cf096 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -71,7 +71,7 @@ class CarInterface(CarInterfaceBase): # These cars have been put into dashcam only due to both a lack of users and test coverage. # These cars likely still work fine. Once a user confirms each car works and a test route is # added to selfdrive/car/tests/routes.py, we can remove it from this list. - ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL} + ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL, CAR.EQUINOX} # Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below. ret.minSteerSpeed = 10 * CV.KPH_TO_MS @@ -170,6 +170,14 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 1.0 CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + elif candidate == CAR.EQUINOX: + ret.minEnableSpeed = -1 + ret.mass = 3500. * CV.LB_TO_KG + STD_CARGO_KG + ret.wheelbase = 2.72 + ret.steerRatio = 14.4 + ret.centerToFront = ret.wheelbase * 0.4 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + # TODO: get actual value, for now starting with reasonable value for # civic and scaling by mass and wheelbase ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index a84cbdc91a..25e624da7b 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -60,6 +60,7 @@ class CAR: ESCALADE_ESV = "CADILLAC ESCALADE ESV 2016" BOLT_EUV = "CHEVROLET BOLT EUV 2022" SILVERADO = "CHEVROLET SILVERADO 1500 2020" + EQUINOX = "CHEVROLET EQUINOX 2019" class Footnote(Enum): @@ -89,6 +90,7 @@ CAR_INFO: Dict[str, Union[GMCarInfo, List[GMCarInfo]]] = { GMCarInfo("Chevrolet Silverado 1500 2020-21", "Safety Package II", footnotes=[], harness=Harness.gm), GMCarInfo("GMC Sierra 1500 2020-21", "Driver Alert Package II", footnotes=[], harness=Harness.gm), ], + CAR.EQUINOX: GMCarInfo("Chevrolet Equinox 2019-22", "Adaptive Cruise Control (ACC)", footnotes=[], harness=Harness.gm), } @@ -166,6 +168,10 @@ FINGERPRINTS = { { 190: 6, 193: 8, 197: 8, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 460: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 534: 2, 560: 8, 562: 8, 563: 5, 565: 5, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 761: 7, 789: 5, 800: 6, 801: 8, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1930: 7 }], + CAR.EQUINOX: [ + { + 190: 6, 193: 8, 197: 8, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 510: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1930: 7 + }], } DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis')) @@ -173,6 +179,6 @@ DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict('gm_global_a_power EV_CAR = {CAR.VOLT, CAR.BOLT_EUV} # We're integrated at the camera with VOACC on these cars (instead of ASCM w/ OBD-II harness) -CAMERA_ACC_CAR = {CAR.BOLT_EUV, CAR.SILVERADO} +CAMERA_ACC_CAR = {CAR.BOLT_EUV, CAR.SILVERADO, CAR.EQUINOX} STEER_THRESHOLD = 1.0 diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 1f5d3edaf0..9f28bf8543 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -21,6 +21,7 @@ non_tested_cars = [ GM.CADILLAC_ATS, GM.HOLDEN_ASTRA, GM.MALIBU, + GM.EQUINOX, HYUNDAI.ELANTRA_GT_I30, HYUNDAI.GENESIS_G90, HYUNDAI.KIA_OPTIMA_H, diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index 20fb5f7a64..2e0f601e84 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -27,6 +27,7 @@ RAM HD 5TH GEN: [1.4, 1.4, 0.0] SUBARU OUTBACK 6TH GEN: [2.3, 2.3, 0.11] CHEVROLET BOLT EUV 2022: [2.0, 2.0, 0.05] CHEVROLET SILVERADO 1500 2020: [1.9, 1.9, 0.112] +CHEVROLET EQUINOX 2019: [2.0, 2.0, 0.05] VOLKSWAGEN PASSAT NMS: [2.5, 2.5, 0.1] HYUNDAI TUCSON HYBRID 4TH GEN: [2.5, 2.5, 0.0] From 5a80fda819fda68cad1caf7c6db15d9a495aefac Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 15 Sep 2022 19:24:18 -0700 Subject: [PATCH 116/152] GM: adjust Bolt EUV centerToFront --- selfdrive/car/gm/interface.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 49d56cf096..f3ab1ee726 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -156,7 +156,7 @@ class CarInterface(CarInterfaceBase): ret.mass = 1669. + STD_CARGO_KG ret.wheelbase = 2.675 ret.steerRatio = 16.8 - ret.centerToFront = ret.wheelbase * 0.4 + ret.centerToFront = 2.15 # measured tire_stiffness_factor = 1.0 ret.steerActuatorDelay = 0.2 CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) From 7ddcde687e3ffaa0ec91002871b76f9ca82752b1 Mon Sep 17 00:00:00 2001 From: eFini Date: Fri, 16 Sep 2022 10:31:57 +0800 Subject: [PATCH 117/152] Multilang: add missing Chinese (Traditional) translations (#25802) --- selfdrive/ui/translations/main_zh-CHT.ts | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 6758305420..ef958e7140 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -985,42 +985,42 @@ location set Updates are only downloaded while the car is off. - + 系統更新只會在熄火時下載。 Current Version - + 當前版本 Download - + 下載 Install Update - + 安裝更新 INSTALL - + 安裝 Target Branch - + 目標分支 SELECT - + 選取 Select a branch - + 選取一個分支 @@ -1174,12 +1174,12 @@ location set Experimental openpilot longitudinal control - + 使用 openpilot 縱向控制(實驗) <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b> - + <b>注意:這台車的 openpilot 縱向控制仍然是實驗中的功能,開啟這功能將會關閉自動緊急煞車 (AEB)。</b> From 64c2d4b30f7d4be1e1726a5668c548ecf8d6e32e Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 15 Sep 2022 19:37:12 -0700 Subject: [PATCH 118/152] Wrap new UI strings --- selfdrive/ui/qt/offroad/settings.cc | 4 ++-- selfdrive/ui/translations/main_ja.ts | 12 +++++++++++- selfdrive/ui/translations/main_ko.ts | 12 +++++++++++- selfdrive/ui/translations/main_pt-BR.ts | 12 +++++++++++- selfdrive/ui/translations/main_zh-CHS.ts | 12 +++++++++++- selfdrive/ui/translations/main_zh-CHT.ts | 12 +++++++++++- 6 files changed, 57 insertions(+), 7 deletions(-) diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 52df247a25..ae878c5419 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -134,8 +134,8 @@ void TogglesPanel::updateToggles() { e2e_toggle->setEnabled(false); params.remove("EndToEndLong"); - const QString no_long = "openpilot longitudinal control is not currently available for this car."; - const QString exp_long = "Enable experimental longitudinal control to enable this."; + const QString no_long = tr("openpilot longitudinal control is not currently available for this car."); + const QString exp_long = tr("Enable experimental longitudinal control to enable this."); e2e_toggle->setDescription("" + (CP.getExperimentalLongitudinalAvailable() ? exp_long : no_long) + "

" + e2e_description); } diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 4262473fb2..3cc9149755 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -1187,7 +1187,17 @@ location set アクセルとブレーキの制御をopenpilotに任せます。openpilotが人間と同じように運転します。最初期の実験段階です。
- + + openpilot longitudinal control is not currently available for this car. + + + + + Enable experimental longitudinal control to enable this. + + + + Disengage On Accelerator Pedal アクセル踏むと openpilot をキャンセル diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 2a827ca4a6..17914f21d8 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -1187,7 +1187,17 @@ location set 주행모델이 가속과 감속을 제어하도록 하면 openpilot은 운전자가 생각하는것처럼 운전합니다. (매우 실험적)
- + + openpilot longitudinal control is not currently available for this car. + + + + + Enable experimental longitudinal control to enable this. + + + + Disengage On Accelerator Pedal 가속페달 조작시 해제 diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 91ffabc625..fe028e18b5 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -1191,7 +1191,17 @@ trabalho definido
- + + openpilot longitudinal control is not currently available for this car. + + + + + Enable experimental longitudinal control to enable this. + + + + Disengage On Accelerator Pedal Desacionar Com Pedal Do Acelerador diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 8a6f856be7..28008ef06f 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -1185,7 +1185,17 @@ location set 让驾驶模型直接控制油门和刹车,openpilot将会模仿人类司机的驾驶方式。该功能仍非常实验性。
- + + openpilot longitudinal control is not currently available for this car. + + + + + Enable experimental longitudinal control to enable this. + + + + Disengage On Accelerator Pedal 踩油门时取消控制 diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index ef958e7140..19f5bf7392 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -1187,7 +1187,17 @@ location set 讓駕駛模型直接控製油門和剎車,openpilot將會模仿人類司機的駕駛方式。該功能仍非常實驗性。
- + + openpilot longitudinal control is not currently available for this car. + + + + + Enable experimental longitudinal control to enable this. + + + + Disengage On Accelerator Pedal 油門取消控車 From cfaa1b7d3eeeb8ae16b77e04a0416dbacf4bc6d2 Mon Sep 17 00:00:00 2001 From: Jason Shuler Date: Thu, 15 Sep 2022 23:11:53 -0400 Subject: [PATCH 119/152] GM: Chevy Bolt EV 2022-23 (#25430) * Chevy Bolt EV w ACC Port * dashcam * The website allows you to select the package without ACC * fix Bolt E(U)V centerToFront * Update selfdrive/car/gm/values.py Co-authored-by: Shane Smiskol --- selfdrive/car/gm/interface.py | 10 +++++----- selfdrive/car/gm/values.py | 6 ++++-- selfdrive/car/tests/routes.py | 1 + selfdrive/car/torque_data/override.yaml | 1 + 4 files changed, 11 insertions(+), 7 deletions(-) diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index f3ab1ee726..93be57cf21 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -71,7 +71,7 @@ class CarInterface(CarInterfaceBase): # These cars have been put into dashcam only due to both a lack of users and test coverage. # These cars likely still work fine. Once a user confirms each car works and a test route is # added to selfdrive/car/tests/routes.py, we can remove it from this list. - ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL, CAR.EQUINOX} + ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL, CAR.EQUINOX, CAR.BOLT_EV} # Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below. ret.minSteerSpeed = 10 * CV.KPH_TO_MS @@ -138,23 +138,23 @@ class CarInterface(CarInterfaceBase): ret.mass = 1601. + STD_CARGO_KG ret.wheelbase = 2.78 ret.steerRatio = 15.3 - ret.centerToFront = ret.wheelbase * 0.49 + ret.centerToFront = ret.wheelbase * 0.5 elif candidate == CAR.ESCALADE_ESV: ret.minEnableSpeed = -1. # engage speed is decided by pcm ret.mass = 2739. + STD_CARGO_KG ret.wheelbase = 3.302 ret.steerRatio = 17.3 - ret.centerToFront = ret.wheelbase * 0.49 + ret.centerToFront = ret.wheelbase * 0.5 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[10., 41.0], [10., 41.0]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.13, 0.24], [0.01, 0.02]] ret.lateralTuning.pid.kf = 0.000045 tire_stiffness_factor = 1.0 - elif candidate == CAR.BOLT_EUV: + elif candidate in (CAR.BOLT_EV, CAR.BOLT_EUV): ret.minEnableSpeed = -1 ret.mass = 1669. + STD_CARGO_KG - ret.wheelbase = 2.675 + ret.wheelbase = 2.63779 ret.steerRatio = 16.8 ret.centerToFront = 2.15 # measured tire_stiffness_factor = 1.0 diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index 25e624da7b..943e8a6585 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -58,6 +58,7 @@ class CAR: ACADIA = "GMC ACADIA DENALI 2018" BUICK_REGAL = "BUICK REGAL ESSENCE 2018" ESCALADE_ESV = "CADILLAC ESCALADE ESV 2016" + BOLT_EV = "CHEVROLET BOLT EV 2022" BOLT_EUV = "CHEVROLET BOLT EUV 2022" SILVERADO = "CHEVROLET SILVERADO 1500 2020" EQUINOX = "CHEVROLET EQUINOX 2019" @@ -85,6 +86,7 @@ CAR_INFO: Dict[str, Union[GMCarInfo, List[GMCarInfo]]] = { CAR.ACADIA: GMCarInfo("GMC Acadia 2018", video_link="https://www.youtube.com/watch?v=0ZN6DdsBUZo"), CAR.BUICK_REGAL: GMCarInfo("Buick Regal Essence 2018"), CAR.ESCALADE_ESV: GMCarInfo("Cadillac Escalade ESV 2016", "Adaptive Cruise Control (ACC) & LKAS"), + CAR.BOLT_EV: GMCarInfo("Chevrolet Bolt EV 2022-23", "Adaptive Cruise Control (ACC)", footnotes=[], harness=Harness.gm), CAR.BOLT_EUV: GMCarInfo("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", video_link="https://youtu.be/xvwzGMUA210", footnotes=[], harness=Harness.gm), CAR.SILVERADO: [ GMCarInfo("Chevrolet Silverado 1500 2020-21", "Safety Package II", footnotes=[], harness=Harness.gm), @@ -176,9 +178,9 @@ FINGERPRINTS = { DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis')) -EV_CAR = {CAR.VOLT, CAR.BOLT_EUV} +EV_CAR = {CAR.VOLT, CAR.BOLT_EV, CAR.BOLT_EUV} # We're integrated at the camera with VOACC on these cars (instead of ASCM w/ OBD-II harness) -CAMERA_ACC_CAR = {CAR.BOLT_EUV, CAR.SILVERADO, CAR.EQUINOX} +CAMERA_ACC_CAR = {CAR.BOLT_EV, CAR.BOLT_EUV, CAR.SILVERADO, CAR.EQUINOX} STEER_THRESHOLD = 1.0 diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 9f28bf8543..e86525baac 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -22,6 +22,7 @@ non_tested_cars = [ GM.HOLDEN_ASTRA, GM.MALIBU, GM.EQUINOX, + GM.BOLT_EV, HYUNDAI.ELANTRA_GT_I30, HYUNDAI.GENESIS_G90, HYUNDAI.KIA_OPTIMA_H, diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index 2e0f601e84..b5d1a31193 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -25,6 +25,7 @@ KIA EV6 2022: [3.5, 3.0, 0.0] RAM 1500 5TH GEN: [2.0, 2.0, 0.0] RAM HD 5TH GEN: [1.4, 1.4, 0.0] SUBARU OUTBACK 6TH GEN: [2.3, 2.3, 0.11] +CHEVROLET BOLT EV 2022: [2.0, 2.0, 0.05] CHEVROLET BOLT EUV 2022: [2.0, 2.0, 0.05] CHEVROLET SILVERADO 1500 2020: [1.9, 1.9, 0.112] CHEVROLET EQUINOX 2019: [2.0, 2.0, 0.05] From b133a4c9a8e8f3ab8211fe1e7a52bd0bb41c5c47 Mon Sep 17 00:00:00 2001 From: Vivek Aithal Date: Thu, 15 Sep 2022 20:15:57 -0700 Subject: [PATCH 120/152] regenerate replay segments for torqued (#25805) * update segments in test_processes * bump cereal * update refs --- cereal | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- .../test/process_replay/test_processes.py | 30 +++++++++---------- 3 files changed, 17 insertions(+), 17 deletions(-) diff --git a/cereal b/cereal index 513dfc7ee0..e4130c9055 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 513dfc7ee001243cd68a57a9d92fe3170fc49c7d +Subproject commit e4130c90558dfb491e132992dce36e0e620e070a diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 7390610252..062611316c 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -ef5395e5f36550d2b485216eee5406bf6062e9c9 \ No newline at end of file +147410f09f242f05b922c9cc7ac04c3c3366419c \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index e8c2e1dc94..0f118971c6 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -38,21 +38,21 @@ original_segments = [ ] segments = [ - ("BODY", "regen660D86654BA|2022-07-06--14-27-15--0"), - ("HYUNDAI", "regen114E5FF24D8|2022-07-14--17-08-47--0"), - ("HYUNDAI", "d824e27e8c60172c|2022-08-19--17-58-07--2"), - ("TOYOTA", "regenBA97410FBEC|2022-07-06--14-26-49--0"), - ("TOYOTA2", "regenDEDB1D9C991|2022-07-06--14-54-08--0"), - ("TOYOTA3", "regenDDC1FE60734|2022-07-06--14-32-06--0"), - ("HONDA", "regenE62960EEC38|2022-07-14--19-33-24--0"), - ("HONDA2", "regenC3EBD92F029|2022-07-14--19-29-47--0"), - ("CHRYSLER", "regen38346FB33D0|2022-07-14--18-05-26--0"), - ("RAM", "2f4452b03ccb98f0|2022-07-07--08-01-56--3"), - ("SUBARU", "regen54A1E2BE5AA|2022-07-14--18-07-50--0"), - ("GM", "regen76027B408B7|2022-08-16--19-56-58--0"), - ("NISSAN", "regenCA0B0DC946E|2022-07-14--18-10-17--0"), - ("VOLKSWAGEN", "regen007098CA0EF|2022-07-06--15-01-26--0"), - ("MAZDA", "regen61BA413D53B|2022-07-06--14-39-42--0"), + ("BODY", "regen9D38397D30D|2022-09-09--13-12-48--0"), + ("HYUNDAI", "regenB3953B393C0|2022-09-09--14-49-37--0"), + ("HYUNDAI", "regen8DB830E5376|2022-09-13--17-24-37--0"), + ("TOYOTA", "regen8FCBB6F06F1|2022-09-09--13-14-07--0"), + ("TOYOTA2", "regen956BFA75300|2022-09-09--14-51-24--0"), + ("TOYOTA3", "regenE909BC2F430|2022-09-09--20-44-49--0"), + ("HONDA", "regenD1D10209015|2022-09-09--14-53-09--0"), + ("HONDA2", "regen3F7C2EFDC08|2022-09-09--19-41-19--0"), + ("CHRYSLER", "regen92783EAE66B|2022-09-09--13-15-44--0"), + ("RAM", "regenBE5DAAEF30F|2022-09-13--17-06-24--0"), + ("SUBARU", "regen8A363AF7E14|2022-09-13--17-20-39--0"), + ("GM", "regen31EA3F9A37C|2022-09-09--21-06-36--0"), + ("NISSAN", "regenAA21ADE5921|2022-09-09--19-44-37--0"), + ("VOLKSWAGEN", "regenA1BF4D17761|2022-09-09--19-46-24--0"), + ("MAZDA", "regen1994C97E977|2022-09-13--16-34-44--0"), ] # dashcamOnly makes don't need to be tested until a full port is done From b7d9f157faa33023ab07db561c155db0abb28c0b Mon Sep 17 00:00:00 2001 From: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com> Date: Thu, 15 Sep 2022 23:16:54 -0400 Subject: [PATCH 121/152] Updater: Reboot instead of shutdown to install new branch (#25804) Reboot instead of shutdown to install new branch --- selfdrive/ui/qt/offroad/software_settings.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/qt/offroad/software_settings.cc b/selfdrive/ui/qt/offroad/software_settings.cc index c9deef2ec4..4f048241c3 100644 --- a/selfdrive/ui/qt/offroad/software_settings.cc +++ b/selfdrive/ui/qt/offroad/software_settings.cc @@ -45,7 +45,7 @@ SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) { installBtn = new ButtonControl(tr("Install Update"), tr("INSTALL")); connect(installBtn, &ButtonControl::clicked, [=]() { installBtn->setEnabled(false); - params.putBool("DoShutdown", true); + params.putBool("DoReboot", true); }); addItem(installBtn); From f0665911b2aa5807348ee5bf209ee21b8be2ca89 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 16 Sep 2022 11:36:13 +0800 Subject: [PATCH 122/152] map: fix repeated call to m_map->setZoom (#25784) Fix repeated map api calls --- selfdrive/ui/qt/maps/map.cc | 3 ++- selfdrive/ui/qt/maps/map.h | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc index 71706fd35e..b5519daccf 100644 --- a/selfdrive/ui/qt/maps/map.cc +++ b/selfdrive/ui/qt/maps/map.cc @@ -204,7 +204,8 @@ void MapWindow::updateState(const UIState &s) { if (zoom_counter == 0) { m_map->setZoom(util::map_val(velocity_filter.x(), 0, 30, MAX_ZOOM, MIN_ZOOM)); - } else { + zoom_counter = -1; + } else if (zoom_counter > 0) { zoom_counter--; } diff --git a/selfdrive/ui/qt/maps/map.h b/selfdrive/ui/qt/maps/map.h index ecba867edb..c3d5e92530 100644 --- a/selfdrive/ui/qt/maps/map.h +++ b/selfdrive/ui/qt/maps/map.h @@ -98,7 +98,7 @@ private: // Panning QPointF m_lastPos; int pan_counter = 0; - int zoom_counter = 0; + int zoom_counter = -1; // Position std::optional last_position; From 8fcbcd800610f30ddf85b5a314dbf40afb0fa320 Mon Sep 17 00:00:00 2001 From: eFini Date: Fri, 16 Sep 2022 11:38:53 +0800 Subject: [PATCH 123/152] Multilang: add missing Chinese (Traditional) translations (#25807) added missing cht translations --- selfdrive/ui/translations/main_zh-CHT.ts | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 19f5bf7392..364508bd1c 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -1189,12 +1189,12 @@ location set openpilot longitudinal control is not currently available for this car. - + openpilot 縱向控制目前不適用於這輛車。 Enable experimental longitudinal control to enable this. - + 打開縱向控制(實驗)以啟用此功能。 From 5356216e92f7c46d5aaefa1c3e85c91fd17816e4 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 15 Sep 2022 20:45:01 -0700 Subject: [PATCH 124/152] remove unused compute_gb (#25808) --- selfdrive/car/mazda/interface.py | 4 ---- selfdrive/car/mock/interface.py | 4 ---- 2 files changed, 8 deletions(-) diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index 89ed5638cb..7c42431e33 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -10,10 +10,6 @@ EventName = car.CarEvent.EventName class CarInterface(CarInterfaceBase): - @staticmethod - def compute_gb(accel, speed): - return float(accel) / 4.0 - @staticmethod def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py index 2c7f4611ee..77e3703c2d 100755 --- a/selfdrive/car/mock/interface.py +++ b/selfdrive/car/mock/interface.py @@ -28,10 +28,6 @@ class CarInterface(CarInterfaceBase): self.yaw_rate = 0. self.yaw_rate_meas = 0. - @staticmethod - def compute_gb(accel, speed): - return accel - @staticmethod def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) From b7dc1968cd4c61d33f96124b36d8d7a48957748f Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 15 Sep 2022 21:21:10 -0700 Subject: [PATCH 125/152] GM minSteerSpeed: add some tolerance for Volt (#25809) * add some tolerance for volts * add comment * update refs --- selfdrive/car/gm/interface.py | 3 ++- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 93be57cf21..22ea83759a 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -74,7 +74,8 @@ class CarInterface(CarInterfaceBase): ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL, CAR.EQUINOX, CAR.BOLT_EV} # Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below. - ret.minSteerSpeed = 10 * CV.KPH_TO_MS + # Some GMs need some tolerance above 10 kph to avoid a fault + ret.minSteerSpeed = 10.1 * CV.KPH_TO_MS ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.00]] ret.lateralTuning.pid.kf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594 diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 062611316c..b1a2785ba3 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -147410f09f242f05b922c9cc7ac04c3c3366419c \ No newline at end of file +a4aa1f37c6d966151d3b43a0b51fffbcfa0187b1 \ No newline at end of file From 40f89b183e5ab39d4a176e54268b0eb9de8e9ebc Mon Sep 17 00:00:00 2001 From: ambientocclusion <1399123+ambientocclusion@users.noreply.github.com> Date: Thu, 15 Sep 2022 21:59:52 -0700 Subject: [PATCH 126/152] Multilang: add missing Japanese translations (#25803) Add missing Japanese translations --- selfdrive/ui/translations/main_ja.ts | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 3cc9149755..b41e1bff77 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -985,42 +985,42 @@ location set Updates are only downloaded while the car is off. - + 車の電源がオフの間のみ、アップデートのダウンロードが行われます。 Current Version - + 現在のバージョン Download - + ダウンロード Install Update - + アップデート INSTALL - + インストール Target Branch - + 対象のブランチ SELECT - + 選択 Select a branch - + ブランチを選択 @@ -1189,12 +1189,12 @@ location set openpilot longitudinal control is not currently available for this car. - + openpilotによるアクセル制御は、この車では現在利用できません。 Enable experimental longitudinal control to enable this. - + ここ機能を使う為には、「実験段階のopenpilotによるアクセル制御」を先に有効化してください。 From 453635394db56098f3473574150147eb977d61f4 Mon Sep 17 00:00:00 2001 From: AlexandreSato <66435071+AlexandreSato@users.noreply.github.com> Date: Fri, 16 Sep 2022 15:43:22 -0300 Subject: [PATCH 127/152] Toyota: add missing Corolla Cross Hybrid engine FW (#25814) * Fingerprint: Add missing toyota corolla cross hybrid FW engine From user lucasolivmed#1416 dongleId: 3eb4c34a2a663c37 * fix typo --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index b0fb143113..26c61f5b74 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -817,6 +817,7 @@ FW_VERSIONS = { b'\x01896637626000\x00\x00\x00\x00', b'\x01896637648000\x00\x00\x00\x00', b'\x01896637643000\x00\x00\x00\x00', + b'\x02896630A07000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630A21000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630ZJ5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630ZN8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', From d460b2c62b9c652c73a1f4b34a3a83784c5eadb5 Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Fri, 16 Sep 2022 16:21:33 -0500 Subject: [PATCH 128/152] VW MQB: Add FW for 2021 Volkswagen Atlas (#25820) --- selfdrive/car/volkswagen/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 4d17b4e3a6..bdd1b5089d 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -300,6 +300,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8703H906026AA\xf1\x899970', b'\xf1\x8703H906026AJ\xf1\x890638', + b'\xf1\x8703H906026AJ\xf1\x891017', b'\xf1\x8703H906026AT\xf1\x891922', b'\xf1\x8703H906026BC\xf1\x892664', b'\xf1\x8703H906026F \xf1\x896696', From e6ff301864b06d0b1dc14e007e1769d53234e38b Mon Sep 17 00:00:00 2001 From: Igor Biletskyy Date: Fri, 16 Sep 2022 14:22:19 -0700 Subject: [PATCH 129/152] RPv2: fix data length check (#25819) fix --- selfdrive/boardd/panda.cc | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index 685dabd873..4d72bc9040 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -389,7 +389,8 @@ void Panda::pack_can_buffer(const capnp::List::Reader &can_data } auto can_data = cmsg.getDat(); uint8_t data_len_code = len_to_dlc(can_data.size()); - assert(can_data.size() <= ((hw_type == cereal::PandaState::PandaType::RED_PANDA) ? 64 : 8)); + assert(can_data.size() <= ((hw_type == cereal::PandaState::PandaType::RED_PANDA || + hw_type == cereal::PandaState::PandaType::RED_PANDA_V2) ? 64 : 8)); assert(can_data.size() == dlc_to_len[data_len_code]); can_header header; From ff63f26409256cc728b35098d135d19c7284c6f1 Mon Sep 17 00:00:00 2001 From: AlexandreSato <66435071+AlexandreSato@users.noreply.github.com> Date: Fri, 16 Sep 2022 18:32:38 -0300 Subject: [PATCH 130/152] Multilang: update pt-BR translations (#25812) * update pt-BR translations * fix some cutoff texts --- selfdrive/ui/translations/main_pt-BR.ts | 32 ++++++++++++------------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index fe028e18b5..a490b4088d 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -888,13 +888,13 @@ trabalho definido OFFLINE - DESCONEC + OFFLINE ONLINE - CONECTADO + ONLINE @@ -989,47 +989,47 @@ trabalho definido Updates are only downloaded while the car is off. - + Atualizações baixadas durante o motor desligado. Current Version - + Versao Atual Download - + Download Install Update - + Instalar Atualização INSTALL - + INSTALAR Target Branch - + Alterar Branch SELECT - + SELECIONE Select a branch - + Selecione uma branch UNINSTALL - DESINSTALAR + DESINSTAL @@ -1178,27 +1178,27 @@ trabalho definido Experimental openpilot longitudinal control - + Controle longitudinal experimental openpilot <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b> - + <b>AVISO: o controle longitudinal openpilot é experimental para este carro e irá desabilitar AEB.</b> Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. - + Deixe o modelo controlar o acelerador e os freios. openpilot irá conduzir como pensa que um humano faria. Super experimental. openpilot longitudinal control is not currently available for this car. - + controle longitudinal openpilot não está disponível para este carro. Enable experimental longitudinal control to enable this. - + Habilite o controle longitudinal experimental para habilitar isso. From 10f08a94dd1cb4ebc803b208697b4dc70795132a Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 16 Sep 2022 15:35:38 -0700 Subject: [PATCH 131/152] sensor test fixups (#25818) * sensor test fixups * fix that * little more * seems reliable now * kill old instances * unused * cleanup Co-authored-by: Bruce Wayne --- selfdrive/sensord/tests/test_sensord.py | 107 +++++++++++------------- 1 file changed, 48 insertions(+), 59 deletions(-) diff --git a/selfdrive/sensord/tests/test_sensord.py b/selfdrive/sensord/tests/test_sensord.py index 837fe88833..0b5f054d2e 100755 --- a/selfdrive/sensord/tests/test_sensord.py +++ b/selfdrive/sensord/tests/test_sensord.py @@ -1,15 +1,13 @@ #!/usr/bin/env python3 - +import os import time import unittest import numpy as np from collections import namedtuple -from smbus2 import SMBus import cereal.messaging as messaging from cereal import log from system.hardware import TICI, HARDWARE -from selfdrive.test.helpers import with_processes from selfdrive.manager.process_config import managed_processes SENSOR_CONFIGURATIONS = ( @@ -50,33 +48,33 @@ SENSOR_CONFIGURATIONS = ( ) Sensor = log.SensorEventData.SensorSource -SensorConfig = namedtuple('SensorConfig', ['type', 'min_samples', 'sanity_min', 'sanity_max']) +SensorConfig = namedtuple('SensorConfig', ['type', 'sanity_min', 'sanity_max']) ALL_SENSORS = { Sensor.rpr0521: { - SensorConfig("light", 100, 0, 150), + SensorConfig("light", 0, 150), }, Sensor.lsm6ds3: { - SensorConfig("acceleration", 100, 5, 15), - SensorConfig("gyroUncalibrated", 100, 0, .2), - SensorConfig("temperature", 100, 0, 60), + SensorConfig("acceleration", 5, 15), + SensorConfig("gyroUncalibrated", 0, .2), + SensorConfig("temperature", 0, 60), }, Sensor.lsm6ds3trc: { - SensorConfig("acceleration", 100, 5, 15), - SensorConfig("gyroUncalibrated", 100, 0, .2), - SensorConfig("temperature", 100, 0, 60), + SensorConfig("acceleration", 5, 15), + SensorConfig("gyroUncalibrated", 0, .2), + SensorConfig("temperature", 0, 60), }, Sensor.bmx055: { - SensorConfig("acceleration", 100, 5, 15), - SensorConfig("gyroUncalibrated", 100, 0, .2), - SensorConfig("magneticUncalibrated", 100, 0, 300), - SensorConfig("temperature", 100, 0, 60), + SensorConfig("acceleration", 5, 15), + SensorConfig("gyroUncalibrated", 0, .2), + SensorConfig("magneticUncalibrated", 0, 300), + SensorConfig("temperature", 0, 60), }, Sensor.mmc5603nj: { - SensorConfig("magneticUncalibrated", 100, 0, 300), + SensorConfig("magneticUncalibrated", 0, 300), } } @@ -96,7 +94,6 @@ def read_sensor_events(duration_sec): return events def get_proc_interrupts(int_pin): - with open("/proc/interrupts") as f: lines = f.read().split("\n") @@ -117,12 +114,18 @@ class TestSensord(unittest.TestCase): HARDWARE.initialize_hardware() # read initial sensor values every test case can use + os.system("pkill -f ./_sensord") + cls.sample_secs = 5 managed_processes["sensord"].start() - cls.events = read_sensor_events(5) + time.sleep(2) + cls.events = read_sensor_events(cls.sample_secs) + managed_processes["sensord"].stop() + + @classmethod + def tearDownClass(cls): managed_processes["sensord"].stop() def tearDown(self): - # interrupt check might leave sensord running managed_processes["sensord"].stop() def test_sensors_present(self): @@ -138,34 +141,32 @@ class TestSensord(unittest.TestCase): self.assertIn(seen, SENSOR_CONFIGURATIONS) - def test_lsm6ds3_100Hz(self): - # verify measurements are sampled and published at a 100Hz rate + def test_lsm6ds3_timing(self): + # verify measurements are sampled and published at 104Hz - data_points = set() + sensor_t = { + 1: [], # accel + 5: [], # gyro + } for event in self.events: for measurement in event.sensorEvents: + if str(measurement.source).startswith("lsm6ds3") and measurement.sensor in sensor_t: + sensor_t[measurement.sensor].append(measurement.timestamp) - # skip lsm6ds3 temperature measurements - if measurement.which() == 'temperature': - continue - - if str(measurement.source).startswith("lsm6ds3"): - data_points.add(measurement.timestamp) - - assert len(data_points) != 0, "No lsm6ds3 sensor events" + for s, vals in sensor_t.items(): + with self.subTest(sensor=s): + assert len(vals) > 0 + tdiffs = np.diff(vals) / 1e6 # millis - data_list = list(data_points) - data_list.sort() - tdiffs = np.diff(data_list) + high_delay_diffs = list(filter(lambda d: d >= 20., tdiffs)) + assert len(high_delay_diffs) < 15, f"Too many large diffs: {high_delay_diffs}" - high_delay_diffs = set(filter(lambda d: d >= 10.1*10**6, tdiffs)) - assert len(high_delay_diffs) < 10, f"Too many high delay packages: {high_delay_diffs}" + # 100-108Hz, expected 104Hz + avg_diff = sum(tdiffs)/len(tdiffs) + assert 9.3 < avg_diff < 10., f"avg difference {avg_diff}, below threshold" - avg_diff = sum(tdiffs)/len(tdiffs) - assert avg_diff > 9.6*10**6, f"avg difference {avg_diff}, below threshold" - - stddev = np.std(tdiffs) - assert stddev < 1.5*10**6, f"Standard-dev to big {stddev}" + stddev = np.std(tdiffs) + assert stddev < 2.0, f"Standard-dev to big {stddev}" def test_events_check(self): # verify if all sensors produce events @@ -217,13 +218,9 @@ class TestSensord(unittest.TestCase): stddev = np.std(tdiffs) assert stddev < 2*10**6, f"Timing diffs have to high stddev: {stddev}" - @with_processes(['sensord']) def test_sensor_values_sanity_check(self): - - events = read_sensor_events(2) - sensor_values = dict() - for event in events: + for event in self.events: for m in event.sensorEvents: # filter unset events (bmx magn) @@ -250,8 +247,9 @@ class TestSensord(unittest.TestCase): key = (sensor, s.type) val_cnt = len(sensor_values[key]) - err_msg = f"Sensor {sensor} {s.type} got {val_cnt} measurements, expected {s.min_samples}" - assert val_cnt > s.min_samples, err_msg + min_samples = self.sample_secs * 100 # Hz + err_msg = f"Sensor {sensor} {s.type} got {val_cnt} measurements, expected {min_samples}" + assert min_samples*0.9 < val_cnt < min_samples*1.1, err_msg mean_norm = np.mean(np.linalg.norm(sensor_values[key], axis=1)) err_msg = f"Sensor '{sensor} {s.type}' failed sanity checks {mean_norm} is not between {s.sanity_min} and {s.sanity_max}" @@ -260,26 +258,17 @@ class TestSensord(unittest.TestCase): def test_sensor_verify_no_interrupts_after_stop(self): managed_processes["sensord"].start() - time.sleep(1) - - # check if the interrupts are enableds - with SMBus(SENSOR_BUS, force=True) as bus: - int1_ctrl_reg = bus.read_byte_data(I2C_ADDR_LSM, 0x0D) - assert int1_ctrl_reg == 3, "Interrupts not enabled!" + time.sleep(3) # read /proc/interrupts to verify interrupts are received state_one = get_proc_interrupts(LSM_INT_GPIO) time.sleep(1) state_two = get_proc_interrupts(LSM_INT_GPIO) - assert state_one != state_two, "no Interrupts received after sensord start!" + assert state_one != state_two, f"no interrupts received after sensord start!\n{state_one} {state_two}" managed_processes["sensord"].stop() - - # check if the interrupts got disabled - with SMBus(SENSOR_BUS, force=True) as bus: - int1_ctrl_reg = bus.read_byte_data(I2C_ADDR_LSM, 0x0D) - assert int1_ctrl_reg == 0, "Interrupts not disabled!" + time.sleep(1) # read /proc/interrupts to verify no more interrupts are received state_one = get_proc_interrupts(LSM_INT_GPIO) From f73b041d43a1ece437df38e26b1dd30759a79c9f Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sat, 17 Sep 2022 02:33:38 +0200 Subject: [PATCH 132/152] Hyundai: match ego speed on dash (#25235) * hyundai: match speed on dash * still needs conversion to m/s * always use CF_Clu_VehicleSpeed2 * clean up, like honda * experiment * to the source * works pretty well on optima (matches exactly on Sonata) * could be 0.5 * clean up test * revert test_moedls revert test_moedls * woops * woops. * . * fix hyst * only CF_Clu_VehicleSpeed * omgomgomg * add all this mess because it always takes a while * set vEgoCluster * fix all rounding errors * stash * clean up * clean up * fix metric conversion * only calculate when updated * try to filter (didn't look great from plots) * Revert "try to filter (didn't look great from plots)" This reverts commit 7e9876c237341d07163985b0718fd9c553372e72. * clean up * update refs Co-authored-by: Shane Smiskol --- selfdrive/car/hyundai/carstate.py | 26 ++++++++++++++++++++---- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 23 insertions(+), 5 deletions(-) diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index eab6e73f1f..61da04d04b 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -1,5 +1,6 @@ from collections import deque import copy +import math from cereal import car from common.conversions import Conversions as CV @@ -9,6 +10,7 @@ from selfdrive.car.hyundai.values import HyundaiFlags, DBC, FEATURES, CAMERA_SCC from selfdrive.car.interfaces import CarStateBase PREV_BUTTON_SAMPLES = 8 +CLUSTER_SAMPLE_RATE = 20 # frames class CarState(CarStateBase): @@ -32,6 +34,10 @@ class CarState(CarStateBase): self.park_brake = False self.buttons_counter = 0 + # On some cars, CLU15->CF_Clu_VehicleSpeed can oscillate faster than the dash updates. Sample at 5 Hz + self.cluster_speed = 0 + self.cluster_speed_counter = CLUSTER_SAMPLE_RATE + self.params = CarControllerParams(CP) def update(self, cp, cp_cam): @@ -39,8 +45,9 @@ class CarState(CarStateBase): return self.update_canfd(cp, cp_cam) ret = car.CarState.new_message() - cp_cruise = cp_cam if self.CP.carFingerprint in CAMERA_SCC_CAR else cp + is_metric = cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"] == 0 + speed_conv = CV.KPH_TO_MS if is_metric else CV.MPH_TO_MS ret.doorOpen = any([cp.vl["CGW1"]["CF_Gway_DrvDrSw"], cp.vl["CGW1"]["CF_Gway_AstDrSw"], cp.vl["CGW2"]["CF_Gway_RLDrSw"], cp.vl["CGW2"]["CF_Gway_RRDrSw"]]) @@ -55,9 +62,19 @@ class CarState(CarStateBase): ) ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.vEgoRaw < 0.1 + self.cluster_speed_counter += 1 + if self.cluster_speed_counter > CLUSTER_SAMPLE_RATE: + self.cluster_speed = cp.vl["CLU15"]["CF_Clu_VehicleSpeed"] + self.cluster_speed_counter = 0 + + # mimic how dash converts to imperial + if not is_metric: + self.cluster_speed = math.floor(self.cluster_speed * CV.KPH_TO_MPH + CV.KPH_TO_MPH) + + ret.vEgoCluster = self.cluster_speed * speed_conv + ret.steeringAngleDeg = cp.vl["SAS11"]["SAS_Angle"] ret.steeringRateDeg = cp.vl["SAS11"]["SAS_Speed"] ret.yawRate = cp.vl["ESP12"]["YAW_RATE"] @@ -78,7 +95,6 @@ class CarState(CarStateBase): ret.cruiseState.available = cp_cruise.vl["SCC11"]["MainMode_ACC"] == 1 ret.cruiseState.enabled = cp_cruise.vl["SCC12"]["ACCMode"] != 0 ret.cruiseState.standstill = cp_cruise.vl["SCC11"]["SCCInfoDisplay"] == 4. - speed_conv = CV.MPH_TO_MS if cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"] else CV.KPH_TO_MS ret.cruiseState.speed = cp_cruise.vl["SCC11"]["VSetDis"] * speed_conv # TODO: Find brake pressure @@ -227,6 +243,8 @@ class CarState(CarStateBase): ("CF_Clu_AmpInfo", "CLU11"), ("CF_Clu_AliveCnt1", "CLU11"), + ("CF_Clu_VehicleSpeed", "CLU15"), + ("ACCEnable", "TCS13"), ("ACC_REQ", "TCS13"), ("DriverBraking", "TCS13"), @@ -251,6 +269,7 @@ class CarState(CarStateBase): ("TCS13", 50), ("TCS15", 10), ("CLU11", 50), + ("CLU15", 5), ("ESP12", 100), ("CGW1", 10), ("CGW2", 5), @@ -309,7 +328,6 @@ class CarState(CarStateBase): if CP.carFingerprint in FEATURES["use_cluster_gears"]: signals.append(("CF_Clu_Gear", "CLU15")) - checks.append(("CLU15", 5)) elif CP.carFingerprint in FEATURES["use_tcu_gears"]: signals.append(("CUR_GR", "TCU12")) checks.append(("TCU12", 100)) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index b1a2785ba3..bca5d0c3eb 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -a4aa1f37c6d966151d3b43a0b51fffbcfa0187b1 \ No newline at end of file +a9a25795f5d8202f7f4c137f80ae030e790ff974 \ No newline at end of file From 1a7d6665deafc1e35e5f8d56106a81a4686a6e44 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 17 Sep 2022 10:45:51 +0800 Subject: [PATCH 133/152] sensord: remove unnecessary brace pair (#25816) Remove unnecessary brace pair --- selfdrive/sensord/sensors_qcom2.cc | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/selfdrive/sensord/sensors_qcom2.cc b/selfdrive/sensord/sensors_qcom2.cc index a9d6e31d3e..aaf79592c6 100644 --- a/selfdrive/sensord/sensors_qcom2.cc +++ b/selfdrive/sensord/sensors_qcom2.cc @@ -88,10 +88,8 @@ void interrupt_loop(int fd, std::vector& sensors, PubMaster& pm) { events.adoptWithCaveats(i, kj::mv(collected_events[i])); } - { - std::lock_guard lock(pm_mutex); - pm.send("sensorEvents", msg); - } + std::lock_guard lock(pm_mutex); + pm.send("sensorEvents", msg); } // poweroff sensors, disable interrupts From 467c4f7fb3bd954d7e0d9120ccd1c687532e6cdc Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 17 Sep 2022 11:10:08 +0800 Subject: [PATCH 134/152] camera_qcom2: remove unneeded static keywords (#25780) --- system/camerad/cameras/camera_qcom2.cc | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 544d653676..532b25d6de 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -821,8 +821,8 @@ void cameras_open(MultiCameraState *s) { // query icp for MMU handles LOG("-- Query ICP for MMU handles"); - static struct cam_isp_query_cap_cmd isp_query_cap_cmd = {0}; - static struct cam_query_cap_cmd query_cap_cmd = {0}; + struct cam_isp_query_cap_cmd isp_query_cap_cmd = {0}; + struct cam_query_cap_cmd query_cap_cmd = {0}; query_cap_cmd.handle_type = 1; query_cap_cmd.caps_handle = (uint64_t)&isp_query_cap_cmd; query_cap_cmd.size = sizeof(isp_query_cap_cmd); @@ -835,7 +835,7 @@ void cameras_open(MultiCameraState *s) { // subscribe LOG("-- Subscribing"); - static struct v4l2_event_subscription sub = {0}; + struct v4l2_event_subscription sub = {0}; sub.type = V4L_EVENT_CAM_REQ_MGR_EVENT; sub.id = V4L_EVENT_CAM_REQ_MGR_SOF_BOOT_TS; ret = HANDLE_EINTR(ioctl(s->video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub)); @@ -864,7 +864,7 @@ void CameraState::camera_close() { LOGD("stop csiphy: %d", ret); // link control stop LOG("-- Stop link control"); - static struct cam_req_mgr_link_control req_mgr_link_control = {0}; + struct cam_req_mgr_link_control req_mgr_link_control = {0}; req_mgr_link_control.ops = CAM_REQ_MGR_LINK_DEACTIVATE; req_mgr_link_control.session_hdl = session_handle; req_mgr_link_control.num_links = 1; @@ -874,7 +874,7 @@ void CameraState::camera_close() { // unlink LOG("-- Unlink"); - static struct cam_req_mgr_unlink_info req_mgr_unlink_info = {0}; + struct cam_req_mgr_unlink_info req_mgr_unlink_info = {0}; req_mgr_unlink_info.session_hdl = session_handle; req_mgr_unlink_info.link_hdl = link_handle; ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_UNLINK, &req_mgr_unlink_info, sizeof(req_mgr_unlink_info)); From 25ce997f3768913915e83b72f4b3c2649a83d720 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 17 Sep 2022 11:11:46 +0800 Subject: [PATCH 135/152] CameraBuf: remove unused member 'camera_state' (#25736) --- system/camerad/cameras/camera_common.cc | 4 +--- system/camerad/cameras/camera_common.h | 5 ----- 2 files changed, 1 insertion(+), 8 deletions(-) diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index 3dbe97596d..b1b4dc7b47 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -65,11 +65,9 @@ private: void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType init_yuv_type) { vipc_server = v; this->yuv_type = init_yuv_type; - - const CameraInfo *ci = &s->ci; - camera_state = s; frame_buf_count = frame_cnt; + const CameraInfo *ci = &s->ci; // RAW frame const int frame_size = (ci->frame_height + ci->extra_height) * ci->frame_stride; camera_bufs = std::make_unique(frame_buf_count); diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index bb6de9c8fb..8b4f5a933d 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -81,15 +81,10 @@ class Debayer; class CameraBuf { private: VisionIpcServer *vipc_server; - CameraState *camera_state; Debayer *debayer = nullptr; - VisionStreamType yuv_type; - int cur_buf_idx; - SafeQueue safe_queue; - int frame_buf_count; public: From 5bb230cde4dd61ff7b180a29a0951a44068161c1 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 17 Sep 2022 11:18:54 +0800 Subject: [PATCH 136/152] camerad: remove function camera_autoexposure (#25733) --- system/camerad/cameras/camera_common.h | 1 - system/camerad/cameras/camera_qcom2.cc | 15 ++------------- 2 files changed, 2 insertions(+), 14 deletions(-) diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index 8b4f5a933d..eaefd3c906 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -117,7 +117,6 @@ void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_i void cameras_open(MultiCameraState *s); void cameras_run(MultiCameraState *s); void cameras_close(MultiCameraState *s); -void camera_autoexposure(CameraState *s, float grey_frac); void camerad_thread(); int open_v4l_by_name_and_index(const char name[], int index = 0, int flags = O_RDWR | O_NONBLOCK); diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 532b25d6de..ce1d0d6f28 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -1180,10 +1180,6 @@ void CameraState::set_camera_exposure(float grey_frac) { } } -void camera_autoexposure(CameraState *s, float grey_frac) { - s->set_camera_exposure(grey_frac); -} - static float ar0231_parse_temp_sensor(uint16_t calib1, uint16_t calib2, uint16_t data_reg) { // See AR0231 Developer Guide - page 36 float slope = (125.0 - 55.0) / ((float)calib1 - (float)calib2); @@ -1210,15 +1206,8 @@ static void ar0231_process_registers(MultiCameraState *s, CameraState *c, cereal framed.setTemperaturesC({temp_0, temp_1}); } -static void driver_cam_auto_exposure(CameraState *c) { - struct ExpRect {int x1, x2, x_skip, y1, y2, y_skip;}; - const CameraBuf *b = &c->buf; - static ExpRect rect = {96, 1832, 2, 242, 1148, 4}; - camera_autoexposure(c, set_exposure_target(b, rect.x1, rect.x2, rect.x_skip, rect.y1, rect.y2, rect.y_skip)); -} - static void process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) { - driver_cam_auto_exposure(c); + c->set_camera_exposure(set_exposure_target(&c->buf, 96, 1832, 2, 242, 1148, 4)); MessageBuilder msg; auto framed = msg.initEvent().initDriverCameraState(); @@ -1254,7 +1243,7 @@ void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { const auto [x, y, w, h] = (c == &s->wide_road_cam) ? std::tuple(96, 250, 1734, 524) : std::tuple(96, 160, 1734, 986); const int skip = 2; - camera_autoexposure(c, set_exposure_target(b, x, x + w, skip, y, y + h, skip)); + c->set_camera_exposure(set_exposure_target(b, x, x + w, skip, y, y + h, skip)); } void cameras_run(MultiCameraState *s) { From 78fd303d50b78dbb99992bb3ee4938eec8913575 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 17 Sep 2022 11:50:10 +0800 Subject: [PATCH 137/152] camerad: cleanup CameraBuf::acquire (#25737) * cleanup * add that back * less indent Co-authored-by: Comma Device --- system/camerad/cameras/camera_common.cc | 23 ++++++----------------- system/camerad/cameras/camera_common.h | 1 - 2 files changed, 6 insertions(+), 18 deletions(-) diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index b1b4dc7b47..787fd99306 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -116,30 +116,24 @@ bool CameraBuf::acquire() { if (camera_bufs_metadata[cur_buf_idx].frame_id == -1) { LOGE("no frame data? wtf"); - release(); return false; } cur_frame_data = camera_bufs_metadata[cur_buf_idx]; cur_yuv_buf = vipc_server->get_buffer(yuv_type); - cl_mem camrabuf_cl = camera_bufs[cur_buf_idx].buf_cl; - cl_event event; - - double start_time = millis_since_boot(); - cur_camera_buf = &camera_bufs[cur_buf_idx]; - debayer->queue(q, camrabuf_cl, cur_yuv_buf->buf_cl, rgb_width, rgb_height, &event); - + double start_time = millis_since_boot(); + cl_event event; + debayer->queue(q, camera_bufs[cur_buf_idx].buf_cl, cur_yuv_buf->buf_cl, rgb_width, rgb_height, &event); clWaitForEvents(1, &event); CL_CHECK(clReleaseEvent(event)); - cur_frame_data.processing_time = (millis_since_boot() - start_time) / 1000.0; VisionIpcBufExtra extra = { - cur_frame_data.frame_id, - cur_frame_data.timestamp_sof, - cur_frame_data.timestamp_eof, + cur_frame_data.frame_id, + cur_frame_data.timestamp_sof, + cur_frame_data.timestamp_eof, }; cur_yuv_buf->set_frame_id(cur_frame_data.frame_id); vipc_server->send(cur_yuv_buf, &extra); @@ -147,10 +141,6 @@ bool CameraBuf::acquire() { return true; } -void CameraBuf::release() { - // Empty -} - void CameraBuf::queue(size_t buf_idx) { safe_queue.push(buf_idx); } @@ -328,7 +318,6 @@ void *processing_thread(MultiCameraState *cameras, CameraState *cs, process_thre // this takes 10ms??? publish_thumbnail(cameras->pm, &(cs->buf)); } - cs->buf.release(); ++cnt; } return NULL; diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index eaefd3c906..e5580a7a92 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -102,7 +102,6 @@ public: ~CameraBuf(); void init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType yuv_type); bool acquire(); - void release(); void queue(size_t buf_idx); }; From 8ae3199578b3f771396cd35315ce51b7cce27e49 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 17 Sep 2022 12:10:26 +0800 Subject: [PATCH 138/152] camerad: make sure cl_context is valid for lifetime of camerad (#25735) --- system/camerad/cameras/camera_common.cc | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index 787fd99306..580c4bc5ee 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -336,15 +336,17 @@ void camerad_thread() { cl_context context = CL_CHECK_ERR(clCreateContext(NULL, 1, &device_id, NULL, NULL, &err)); #endif - MultiCameraState cameras = {}; - VisionIpcServer vipc_server("camerad", device_id, context); + { + MultiCameraState cameras = {}; + VisionIpcServer vipc_server("camerad", device_id, context); - cameras_open(&cameras); - cameras_init(&vipc_server, &cameras, device_id, context); + cameras_open(&cameras); + cameras_init(&vipc_server, &cameras, device_id, context); - vipc_server.start_listener(); + vipc_server.start_listener(); - cameras_run(&cameras); + cameras_run(&cameras); + } CL_CHECK(clReleaseContext(context)); } From aa0d12842202ddf63d9a5998ccd04f865b6e9d6a Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 17 Sep 2022 13:17:30 +0800 Subject: [PATCH 139/152] ui: always show SetupWidget (#25742) * always show SetupWidget update translations * delete hide --- selfdrive/ui/qt/widgets/prime.cc | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/selfdrive/ui/qt/widgets/prime.cc b/selfdrive/ui/qt/widgets/prime.cc index 1d765d0949..04684fc765 100644 --- a/selfdrive/ui/qt/widgets/prime.cc +++ b/selfdrive/ui/qt/widgets/prime.cc @@ -277,7 +277,7 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { primeUser = new PrimeUserWidget; mainLayout->addWidget(primeUser); - mainLayout->setCurrentWidget(primeAd); + mainLayout->setCurrentWidget(uiState()->prime_type ? (QWidget*)primeUser : (QWidget*)primeAd); setFixedWidth(750); setStyleSheet(R"( @@ -299,11 +299,9 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { QObject::connect(repeater, &RequestRepeater::requestDone, this, &SetupWidget::replyFinished); } - hide(); // Only show when first request comes back } void SetupWidget::replyFinished(const QString &response, bool success) { - show(); if (!success) return; QJsonDocument doc = QJsonDocument::fromJson(response.toUtf8()); From 407448bbfb79ad9d9d235bc3d098887ea0d045fb Mon Sep 17 00:00:00 2001 From: cydia2020 <12470297+cydia2020@users.noreply.github.com> Date: Sat, 17 Sep 2022 16:28:05 +1000 Subject: [PATCH 140/152] Toyota: go into standstill if interceptor detected (#25024) * Toyota: go into standstill if interceptor detected * or --- selfdrive/car/toyota/carcontroller.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index b34a31a01c..faea08ed3f 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -81,7 +81,7 @@ class CarController: pcm_cancel_cmd = 1 # on entering standstill, send standstill request - if CS.out.standstill and not self.last_standstill and self.CP.carFingerprint not in NO_STOP_TIMER_CAR: + if CS.out.standstill and not self.last_standstill and (self.CP.carFingerprint not in NO_STOP_TIMER_CAR or self.CP.enableGasInterceptor): self.standstill_req = True if CS.pcm_acc_status != 8: # pcm entered standstill or it's disabled From 85ed5c4cb5d9b0132ab0e3eb5bcb096026f70b22 Mon Sep 17 00:00:00 2001 From: Vivek Aithal Date: Sat, 17 Sep 2022 00:07:54 -0700 Subject: [PATCH 141/152] Torque Refactor (#25822) * add torque gains refactor * update refs * avoid dict, use cereal struct * bugfix * no as_builder * address final comments --- selfdrive/car/interfaces.py | 30 ++++++++++++++---- selfdrive/controls/lib/latcontrol_torque.py | 35 ++++++++++----------- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 41 insertions(+), 26 deletions(-) diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index bc6c31e12c..87720f8754 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -2,24 +2,27 @@ import yaml import os import time from abc import abstractmethod, ABC -from typing import Any, Dict, Optional, Tuple, List +from typing import Any, Dict, Optional, Tuple, List, Callable from cereal import car from common.basedir import BASEDIR from common.conversions import Conversions as CV from common.kalman.simple_kalman import KF1D +from common.numpy_fast import interp from common.realtime import DT_CTRL from selfdrive.car import apply_hysteresis, create_button_enable_events, gen_empty_fingerprint -from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX +from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX, apply_deadzone from selfdrive.controls.lib.events import Events from selfdrive.controls.lib.vehicle_model import VehicleModel GearShifter = car.CarState.GearShifter EventName = car.CarEvent.EventName +TorqueFromLateralAccelCallbackType = Callable[[float, car.CarParams.LateralTorqueTuning, float, float, bool], float] MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS ACCEL_MAX = 2.0 ACCEL_MIN = -3.5 +FRICTION_THRESHOLD = 0.2 TORQUE_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/params.yaml') TORQUE_OVERRIDE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/override.yaml') @@ -101,6 +104,20 @@ class CarInterfaceBase(ABC): def get_steer_feedforward_function(self): return self.get_steer_feedforward_default + @staticmethod + def torque_from_lateral_accel_linear(lateral_accel_value, torque_params, lateral_accel_error, lateral_accel_deadzone, friction_compensation): + # The default is a linear relationship between torque and lateral acceleration (accounting for road roll and steering friction) + friction_interp = interp( + apply_deadzone(lateral_accel_error, lateral_accel_deadzone), + [-FRICTION_THRESHOLD, FRICTION_THRESHOLD], + [-torque_params.friction, torque_params.friction] + ) + friction = friction_interp if friction_compensation else 0.0 + return (lateral_accel_value / torque_params.latAccelFactor) + friction + + def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType: + return self.torque_from_lateral_accel_linear + # returns a set of default params to avoid repetition in car specific params @staticmethod def get_std_params(candidate, fingerprint): @@ -144,11 +161,12 @@ class CarInterfaceBase(ABC): tune.init('torque') tune.torque.useSteeringAngle = use_steering_angle - tune.torque.kp = 1.0 / params['LAT_ACCEL_FACTOR'] - tune.torque.kf = 1.0 / params['LAT_ACCEL_FACTOR'] - tune.torque.ki = 0.1 / params['LAT_ACCEL_FACTOR'] + tune.torque.kp = 1.0 + tune.torque.kf = 1.0 + tune.torque.ki = 0.1 tune.torque.friction = params['FRICTION'] - tune.torque.steeringAngleDeadzoneDeg = steering_angle_deadzone_deg + tune.torque.latAccelFactor = params['LAT_ACCEL_FACTOR'] + tune.torque.latAccelOffset = 0.0 @abstractmethod def _update(self, c: car.CarControl) -> car.CarState: diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index c4604d90e1..f65a58275b 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -4,7 +4,6 @@ from cereal import log from common.numpy_fast import interp from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED from selfdrive.controls.lib.pid import PIDController -from selfdrive.controls.lib.drive_helpers import apply_deadzone from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY # At higher speeds (25+mph) we can assume: @@ -19,19 +18,20 @@ from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY # move it at all, this is compensated for too. -FRICTION_THRESHOLD = 0.2 - - class LatControlTorque(LatControl): def __init__(self, CP, CI): super().__init__(CP, CI) - self.pid = PIDController(CP.lateralTuning.torque.kp, CP.lateralTuning.torque.ki, - k_f=CP.lateralTuning.torque.kf, pos_limit=self.steer_max, neg_limit=-self.steer_max) - self.get_steer_feedforward = CI.get_steer_feedforward_function() - self.use_steering_angle = CP.lateralTuning.torque.useSteeringAngle - self.friction = CP.lateralTuning.torque.friction - self.kf = CP.lateralTuning.torque.kf - self.steering_angle_deadzone_deg = CP.lateralTuning.torque.steeringAngleDeadzoneDeg + self.torque_params = CP.lateralTuning.torque + self.pid = PIDController(self.torque_params.kp, self.torque_params.ki, + k_f=self.torque_params.kf, pos_limit=self.steer_max, neg_limit=-self.steer_max) + self.torque_from_lateral_accel = CI.torque_from_lateral_accel() + self.use_steering_angle = self.torque_params.useSteeringAngle + self.steering_angle_deadzone_deg = self.torque_params.steeringAngleDeadzoneDeg + + def update_live_torque_params(self, latAccelFactor, latAccelOffset, friction): + self.torque_params.latAccelFactor = latAccelFactor + self.torque_params.latAccelOffset = latAccelOffset + self.torque_params.friction = friction def update(self, active, CS, VM, params, last_actuators, steer_limited, desired_curvature, desired_curvature_rate, llk): pid_log = log.ControlsState.LateralTorqueState.new_message() @@ -55,19 +55,16 @@ class LatControlTorque(LatControl): actual_lateral_accel = actual_curvature * CS.vEgo ** 2 lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2 - low_speed_factor = interp(CS.vEgo, [0, 10, 20], [500, 500, 200]) setpoint = desired_lateral_accel + low_speed_factor * desired_curvature measurement = actual_lateral_accel + low_speed_factor * actual_curvature error = setpoint - measurement - pid_log.error = error + gravity_adjusted_lateral_accel = desired_lateral_accel - params.roll * ACCELERATION_DUE_TO_GRAVITY + pid_log.error = self.torque_from_lateral_accel(error, self.torque_params, error, lateral_accel_deadzone, friction_compensation=False) + ff = self.torque_from_lateral_accel(gravity_adjusted_lateral_accel, self.torque_params, error, lateral_accel_deadzone, friction_compensation=True) - ff = desired_lateral_accel - params.roll * ACCELERATION_DUE_TO_GRAVITY - # convert friction into lateral accel units for feedforward - friction_compensation = interp(apply_deadzone(error, lateral_accel_deadzone), [-FRICTION_THRESHOLD, FRICTION_THRESHOLD], [-self.friction, self.friction]) - ff += friction_compensation / self.kf freeze_integrator = steer_limited or CS.steeringPressed or CS.vEgo < 5 - output_torque = self.pid.update(error, + output_torque = self.pid.update(pid_log.error, feedforward=ff, speed=CS.vEgo, freeze_integrator=freeze_integrator) @@ -78,9 +75,9 @@ class LatControlTorque(LatControl): pid_log.d = self.pid.d pid_log.f = self.pid.f pid_log.output = -output_torque - pid_log.saturated = self._check_saturation(self.steer_max - abs(output_torque) < 1e-3, CS, steer_limited) pid_log.actualLateralAccel = actual_lateral_accel pid_log.desiredLateralAccel = desired_lateral_accel + pid_log.saturated = self._check_saturation(self.steer_max - abs(output_torque) < 1e-3, CS, steer_limited) # TODO left is positive in this convention return -output_torque, 0.0, pid_log diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index bca5d0c3eb..afde6ec422 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -a9a25795f5d8202f7f4c137f80ae030e790ff974 \ No newline at end of file +d14f1a61a4bfde810128a6bb703aa543268fa4a9 \ No newline at end of file From 06fb52c146aa9e00126127ac28fbbd22e9914e6f Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Sat, 17 Sep 2022 00:24:57 -0700 Subject: [PATCH 142/152] Kia: update required packages (#25824) * Kia: LKAS is standard on Ceed 2019 https://www.downeys.co.uk/newmodels/Ceed_V3_24_09_2019.pdf * Kia: delete Forte 2018 It doesn't appear that this vehicle has Adaptive/Smart Cruise Control in any form, which was later added in 2019. https://cdn.dealereprocess.org/cdn/brochures/kia/2018-forte.pdf https://cdn.dealereprocess.org/cdn/brochures/kia/2019-forte.pdf * Kia: LKAS is standard on Forte 2019+ https://cdn.dealereprocess.org/cdn/brochures/kia/2019-forte.pdf https://cdn.dealereprocess.org/cdn/brochures/kia/2020-forte.pdf * Kia: rename Niro Electric to EV https://www.kia.com/us/en/niro Co-authored-by: Shane Smiskol * Kia: LKAS is standard on Niro PHEV 2018+ https://cdn.dealereprocess.org/cdn/brochures/kia/2018-niro.pdf https://cdn.dealereprocess.org/cdn/brochures/kia/2019-niro.pdf * Kia: update required package on Optima 2017 The ACC package on the Optima 2017 is named "Advanced Smart Cruise Control". It also doesn't have an LKAS package, only LDWS is available. https://cdn.dealereprocess.org/cdn/brochures/kia/2017-optima.pdf Co-authored-by: Shane Smiskol * Kia: LKAS is standard on Optima 2019 https://cdn.dealereprocess.org/cdn/brochures/kia/2019-optima.pdf * Kia: revert package change to Seltos 2021 LKAS is NOT a standard package on the Seltos 2021 https://cdn.dealereprocess.org/cdn/brochures/kia/2021-seltos.pdf * Kia: update required package on Sorento 2018 Similar to the Optima 2017, the ACC package on the Sorento 2018 is named "Advanced Smart Cruise Control". It also doesn't have an LKAS package, only LDWS. SCC and LKAS were introduced in MY2019. https://cdn.dealereprocess.org/cdn/brochures/kia/2018-sorento.pdf Co-authored-by: Shane Smiskol * Kia: SCC is standard on Kia Niro PHEV 2018-19 https://cdn.dealereprocess.org/cdn/brochures/kia/2018-niro.pdf Co-authored-by: Shane Smiskol * Kia: update required package on Optima Hybrid 2017 Similar to the Optima 2017, the ACC package on he Optima Hybrid 2017 is named "Advanced Smart Cruise Control". It also doesn't have an LKAS pacakge, only LDWS. https://cdn.dealereprocess.org/cdn/brochures/kia/2017-optimahybrid.pdf * update docs Co-authored-by: Shane Smiskol --- docs/CARS.md | 25 ++++++++++++------------- selfdrive/car/hyundai/values.py | 30 +++++++++++++++--------------- selfdrive/car/tests/test_docs.py | 3 ++- 3 files changed, 29 insertions(+), 29 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 510500dab7..9df3b803d9 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -4,7 +4,7 @@ A supported vehicle is one that just works when you install a comma three. All supported cars provide a better experience than any stock system. -# 205 Supported Cars +# 204 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Harness| |---|---|---|:---:|:---:|:---:|:---:|:---:|:---:| @@ -82,22 +82,21 @@ A supported vehicle is one that just works when you install a comma three. All s |Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| -|Kia|Ceed 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| +|Kia|Ceed 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Kia|EV6 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P| -|Kia|Forte 2018|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| -|Kia|Forte 2019-21|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| +|Kia|Forte 2019-21|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| |Kia|K5 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| -|Kia|Niro Electric 2019|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| -|Kia|Niro Electric 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| -|Kia|Niro Electric 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| -|Kia|Niro Electric 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Kia|Niro EV 2019|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Kia|Niro EV 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| +|Kia|Niro EV 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Kia|Niro EV 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Kia|Niro Hybrid 2021|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| |Kia|Niro Hybrid 2022|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| -|Kia|Niro Plug-in Hybrid 2018-19|Smart Cruise Control (SCC) & LKAS|openpilot|10 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| -|Kia|Optima 2017|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| -|Kia|Optima 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| -|Kia|Seltos 2021|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| -|Kia|Sorento 2018|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Kia|Niro Plug-in Hybrid 2018-19|All|openpilot|10 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Kia|Optima 2017|Advanced Smart Cruise Control & LDWS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| +|Kia|Optima 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| +|Kia|Seltos 2021|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| +|Kia|Sorento 2018|Advanced Smart Cruise Control & LDWS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |Kia|Sorento 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Kia|Stinger 2018-20|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |Kia|Telluride 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index b816614879..3bc2062979 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -143,34 +143,34 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { CAR.TUCSON_HYBRID_4TH_GEN: HyundaiCarInfo("Hyundai Tucson Hybrid 2022", "All", harness=Harness.hyundai_n), # Kia - CAR.KIA_FORTE: [ - HyundaiCarInfo("Kia Forte 2018", harness=Harness.hyundai_b), - HyundaiCarInfo("Kia Forte 2019-21", harness=Harness.hyundai_g), - ], + CAR.KIA_FORTE: HyundaiCarInfo("Kia Forte 2019-21", "Smart Cruise Control (SCC)", harness=Harness.hyundai_g), CAR.KIA_K5_2021: HyundaiCarInfo("Kia K5 2021-22", "Smart Cruise Control (SCC)", harness=Harness.hyundai_a), CAR.KIA_NIRO_EV: [ - HyundaiCarInfo("Kia Niro Electric 2019", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h), - HyundaiCarInfo("Kia Niro Electric 2020", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_f), - HyundaiCarInfo("Kia Niro Electric 2021", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_c), - HyundaiCarInfo("Kia Niro Electric 2022", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h), + HyundaiCarInfo("Kia Niro EV 2019", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h), + HyundaiCarInfo("Kia Niro EV 2020", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_f), + HyundaiCarInfo("Kia Niro EV 2021", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_c), + HyundaiCarInfo("Kia Niro EV 2022", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h), ], - CAR.KIA_NIRO_PHEV: HyundaiCarInfo("Kia Niro Plug-in Hybrid 2018-19", min_enable_speed=10. * CV.MPH_TO_MS, harness=Harness.hyundai_c), + CAR.KIA_NIRO_PHEV: HyundaiCarInfo("Kia Niro Plug-in Hybrid 2018-19", "All", min_enable_speed=10. * CV.MPH_TO_MS, harness=Harness.hyundai_c), CAR.KIA_NIRO_HEV_2021: [ HyundaiCarInfo("Kia Niro Hybrid 2021", harness=Harness.hyundai_f), # TODO: could be hyundai_d, verify HyundaiCarInfo("Kia Niro Hybrid 2022", harness=Harness.hyundai_h), ], CAR.KIA_OPTIMA: [ - HyundaiCarInfo("Kia Optima 2017", min_steer_speed=32. * CV.MPH_TO_MS, harness=Harness.hyundai_b), - HyundaiCarInfo("Kia Optima 2019", harness=Harness.hyundai_g), + HyundaiCarInfo("Kia Optima 2017", "Advanced Smart Cruise Control & LDWS", min_steer_speed=32. * CV.MPH_TO_MS, harness=Harness.hyundai_b), + HyundaiCarInfo("Kia Optima 2019", "Smart Cruise Control (SCC)", harness=Harness.hyundai_g), + ], + CAR.KIA_OPTIMA_H: [ + HyundaiCarInfo("Kia Optima Hybrid 2017", "Advanced Smart Cruise Control & LDWS"), # TODO: info may be incorrect + HyundaiCarInfo("Kia Optima Hybrid 2019"), ], - CAR.KIA_OPTIMA_H: HyundaiCarInfo("Kia Optima Hybrid 2017, 2019"), # TODO: info may be incorrect - CAR.KIA_SELTOS: HyundaiCarInfo("Kia Seltos 2021", "Smart Cruise Control (SCC)", harness=Harness.hyundai_a), + CAR.KIA_SELTOS: HyundaiCarInfo("Kia Seltos 2021", harness=Harness.hyundai_a), CAR.KIA_SORENTO: [ - HyundaiCarInfo("Kia Sorento 2018", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_c), + HyundaiCarInfo("Kia Sorento 2018", "Advanced Smart Cruise Control & LDWS", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_c), HyundaiCarInfo("Kia Sorento 2019", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_e), ], CAR.KIA_STINGER: HyundaiCarInfo("Kia Stinger 2018-20", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", harness=Harness.hyundai_c), - CAR.KIA_CEED: HyundaiCarInfo("Kia Ceed 2019", harness=Harness.hyundai_e), + CAR.KIA_CEED: HyundaiCarInfo("Kia Ceed 2019", "Smart Cruise Control (SCC)", harness=Harness.hyundai_e), CAR.KIA_EV6: HyundaiCarInfo("Kia EV6 2022", "Highway Driving Assist II", harness=Harness.hyundai_p), # Genesis diff --git a/selfdrive/car/tests/test_docs.py b/selfdrive/car/tests/test_docs.py index af58bb5e59..191b36b8f2 100755 --- a/selfdrive/car/tests/test_docs.py +++ b/selfdrive/car/tests/test_docs.py @@ -34,9 +34,10 @@ class TestCarDocs(unittest.TestCase): if car.car_name == "hyundai": self.assertNotIn("phev", tokens, "Use `Plug-in Hybrid`") self.assertNotIn("hev", tokens, "Use `Hybrid`") - self.assertNotIn("ev", tokens, "Use `Electric`") if "plug-in hybrid" in car.model.lower(): self.assertIn("Plug-in Hybrid", car.model, "Use correct capitalization") + if car.make != "Kia": + self.assertNotIn("ev", tokens, "Use `Electric`") elif car.car_name == "toyota": if "rav4" in tokens: self.assertIn("RAV4", car.model, "Use correct capitalization") From 35f624c628c0e8f2e936ba945bdc516a8d17517e Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Sat, 17 Sep 2022 15:51:49 -0700 Subject: [PATCH 143/152] translations: remove locations (#25826) * Remove locations * no line nos --- selfdrive/ui/tests/test_translations.py | 12 +- selfdrive/ui/translations/main_en.ts | 4 - selfdrive/ui/translations/main_ja.ts | 248 ----------------------- selfdrive/ui/translations/main_ko.ts | 248 ----------------------- selfdrive/ui/translations/main_pt-BR.ts | 248 ----------------------- selfdrive/ui/translations/main_zh-CHS.ts | 248 ----------------------- selfdrive/ui/translations/main_zh-CHT.ts | 248 ----------------------- selfdrive/ui/update_translations.py | 2 +- 8 files changed, 9 insertions(+), 1249 deletions(-) diff --git a/selfdrive/ui/tests/test_translations.py b/selfdrive/ui/tests/test_translations.py index d8609f110b..11ecd30ae0 100755 --- a/selfdrive/ui/tests/test_translations.py +++ b/selfdrive/ui/tests/test_translations.py @@ -29,10 +29,7 @@ class TestTranslations(unittest.TestCase): def _read_translation_file(path, file): tr_file = os.path.join(path, f"{file}.ts") with open(tr_file, "r") as f: - # ignore locations when checking if translations are updated - lines = [line for line in f.read().splitlines() if - not line.strip().startswith(LOCATION_TAG)] - return "\n".join(lines) + return f.read() def test_missing_translation_files(self): for name, file in self.translation_files.items(): @@ -93,6 +90,13 @@ class TestTranslations(unittest.TestCase): self.assertTrue(all([re.search("%[0-9]+", t) is None for t in numerusform]), "Plural translations must use %n, not %1, %2, etc.: {}".format(numerusform)) + def test_no_locations(self): + for name, file in self.translation_files.items(): + with self.subTest(name=name, file=file): + for line in self._read_translation_file(TRANSLATIONS_DIR, file).splitlines(): + self.assertFalse(line.strip().startswith(LOCATION_TAG), + f"Line contains location tag: {line.strip()}, remove all line numbers.") + if __name__ == "__main__": unittest.main() diff --git a/selfdrive/ui/translations/main_en.ts b/selfdrive/ui/translations/main_en.ts index 42e30a59af..3f9692e5fa 100644 --- a/selfdrive/ui/translations/main_en.ts +++ b/selfdrive/ui/translations/main_en.ts @@ -4,7 +4,6 @@ InputDialog - Need at least %n character(s)! Need at least %n character! @@ -15,7 +14,6 @@ QObject - %n minute(s) ago %n minute ago @@ -23,7 +21,6 @@ - %n hour(s) ago %n hour ago @@ -31,7 +28,6 @@ - %n day(s) ago %n day ago diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index b41e1bff77..543893d440 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -4,17 +4,14 @@ AbstractAlert - Close 閉じる - Snooze Update 更新の一時停止 - Reboot and Update 再起動してアップデート @@ -22,53 +19,42 @@ AdvancedNetworking - Back 戻る - Enable Tethering テザリングを有効化 - Tethering Password テザリングパスワード - - EDIT 編集 - Enter new tethering password 新しいテザリングパスワードを入力 - IP Address IP アドレス - Enable Roaming ローミングを有効化 - APN Setting APN 設定 - Enter APN APN を入力 - leave blank for automatic configuration 空白のままにして、自動設定にします @@ -76,13 +62,10 @@ ConfirmationDialog - - Ok OK - Cancel キャンセル @@ -90,17 +73,14 @@ DeclinePage - You must accept the Terms and Conditions in order to use openpilot. openpilot をご利用される前に、利用規約に同意する必要があります。 - Back 戻る - Decline, uninstall %1 拒否して %1 をアンインストール @@ -108,152 +88,122 @@ DevicePanel - Dongle ID ドングル番号 (Dongle ID) - N/A N/A - Serial シリアル番号 - Driver Camera 車内カメラ - PREVIEW 見る - Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 車内カメラをプレビューして、ドライバー監視システムの視界を確認ができます。(車両の電源を切る必要があります) - Reset Calibration キャリブレーションをリセット - RESET リセット - Are you sure you want to reset calibration? キャリブレーションをリセットしてもよろしいですか? - Review Training Guide 入門書を見る - REVIEW 見る - Review the rules, features, and limitations of openpilot openpilot の特徴を見る - Are you sure you want to review the training guide? 入門書を見てもよろしいですか? - Regulatory 認証情報 - VIEW 見る - Change Language 言語を変更 - CHANGE 変更 - Select a language 言語を選択 - Reboot 再起動 - Power Off 電源を切る - openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot は、左または右の4°以内、上の5°または下の8°以内にデバイスを取付ける必要があります。キャリブレーションを引き続きます、リセットはほとんど必要ありません。 - Your device is pointed %1° %2 and %3° %4. このデバイスは%2の%1°、%4の%3°に向けます。 - down - up - left - right - Are you sure you want to reboot? 再起動してもよろしいですか? - Disengage to Reboot openpilot をキャンセルして再起動ができます - Are you sure you want to power off? シャットダウンしてもよろしいですか? - Disengage to Power Off openpilot をキャンセルしてシャットダウンができます @@ -261,32 +211,26 @@ DriveStats - Drives 運転履歴 - Hours 時間 - ALL TIME 累計 - PAST WEEK 先週 - KM km - Miles マイル @@ -294,7 +238,6 @@ DriverViewScene - camera starting カメラを起動しています @@ -302,12 +245,10 @@ InputDialog - Cancel キャンセル - Need at least %n character(s)! %n文字以上でお願いします! @@ -317,22 +258,18 @@ Installer - Installing... インストールしています... - Receiving objects: オブジェクトをダウンロードしています: - Resolving deltas: デルタを解決しています: - Updating files: ファイルを更新しています: @@ -340,27 +277,22 @@ MapETA - eta 予定到着時間 - min - hr 時間 - km キロメートル - mi マイル @@ -368,22 +300,18 @@ MapInstructions - km キロメートル - m メートル - mi マイル - ft フィート @@ -391,48 +319,40 @@ MapPanel - Current Destination 現在の目的地 - CLEAR 削除 - Recent Destinations 最近の目的地 - Try the Navigation Beta β版ナビゲーションを試す - Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai より詳細な案内情報を得ることができます。 詳しくはこちら:https://connect.comma.ai - No home location set 自宅の住所はまだ 設定されていません - No work location set 職場の住所はまだ 設定されていません - no recent destinations 最近の目的地履歴がありません @@ -440,12 +360,10 @@ location set MapWindow - Map Loading マップを読み込んでいます - Waiting for GPS GPS信号を探しています @@ -453,12 +371,10 @@ location set MultiOptionDialog - Select 選択 - Cancel キャンセル @@ -466,23 +382,18 @@ location set Networking - Advanced 詳細 - Enter password パスワードを入力 - - for "%1" ネットワーク名:%1 - Wrong password パスワードが間違っています @@ -490,30 +401,22 @@ location set NvgWindow - km/h km/h - mph mph - - MAX 最高速度 - - SPEED 速度 - - LIMIT 制限速度 @@ -521,17 +424,14 @@ location set OffroadHome - UPDATE 更新 - ALERTS 警告 - ALERT 警告 @@ -539,22 +439,18 @@ location set PairingPopup - Pair your device to your comma account デバイスと comma アカウントを連携する - Go to https://connect.comma.ai on your phone モバイルデバイスで「connect.comma.ai」にアクセスして - Click "add new device" and scan the QR code on the right 「新しいデバイスを追加」を押すと、右側のQRコードをスキャンしてください - Bookmark connect.comma.ai to your home screen to use it like an app 「connect.comma.ai」をホーム画面に追加して、アプリのように使うことができます @@ -562,32 +458,26 @@ location set PrimeAdWidget - Upgrade Now 今すぐアップグレート - Become a comma prime member at connect.comma.ai connect.comma.ai でプライム会員に登録できます - PRIME FEATURES: 特典: - Remote access リモートアクセス - 1 year of storage 一年間の保存期間 - Developer perks 開発者向け特典 @@ -595,22 +485,18 @@ location set PrimeUserWidget - ✓ SUBSCRIBED ✓ 入会しました - comma prime comma prime - CONNECT.COMMA.AI CONNECT.COMMA.AI - COMMA POINTS COMMA POINTS @@ -618,41 +504,34 @@ location set QObject - Reboot 再起動 - Exit 閉じる - dashcam ドライブレコーダー - openpilot openpilot - %n minute(s) ago %n 分前 - %n hour(s) ago %n 時間前 - %n day(s) ago %n 日前 @@ -662,47 +541,38 @@ location set Reset - Reset failed. Reboot to try again. 初期化に失敗しました。再起動後に再試行してください。 - Are you sure you want to reset your device? 初期化してもよろしいですか? - Resetting device... デバイスが初期化されます... - System Reset システムを初期化 - System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. システムの初期化をリクエストしました。「確認」ボタンを押すとデバイスが初期化されます。「キャンセル」ボタンを押すと起動を続行します。 - Cancel キャンセル - Reboot 再起動 - Confirm 確認 - Unable to mount data partition. Press confirm to reset your device. 「data」パーティションをマウントできません。「確認」ボタンを押すとデバイスが初期化されます。 @@ -710,7 +580,6 @@ location set RichTextDialog - Ok OK @@ -718,33 +587,26 @@ location set SettingsWindow - × × - Device デバイス - - Network ネットワーク - Toggles 切り替え - Software ソフトウェア - Navigation ナビゲーション @@ -752,105 +614,82 @@ location set Setup - WARNING: Low Voltage 警告:低電圧 - Power your device in a car with a harness or proceed at your own risk. 自己責任でハーネスから電源を供給してください。 - Power off 電源を切る - - - Continue 続ける - Getting Started はじめに - Before we get on the road, let’s finish installation and cover some details. その前に、インストールを完了し、いくつかの詳細を説明します。 - Connect to Wi-Fi Wi-Fi に接続 - - Back 戻る - Continue without Wi-Fi Wi-Fi に未接続で続行 - Waiting for internet インターネット接続を待機中 - Choose Software to Install インストールするソフトウェアを選びます - Dashcam ドライブレコーダー - Custom Software カスタムソフトウェア - Enter URL URL を入力 - for Custom Software カスタムソフトウェア - Downloading... ダウンロード中... - Download Failed ダウンロード失敗 - Ensure the entered URL is valid, and the device’s internet connection is good. 入力された URL を確認し、デバイスがインターネットに接続されていることを確認してください。 - Reboot device デバイスを再起動 - Start over 最初からやり直す @@ -858,17 +697,14 @@ location set SetupWidget - Finish Setup セットアップ完了 - Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. デバイスを comma connect (connect.comma.ai)でペアリングし comma prime 特典を申請してください。 - Pair device デバイスをペアリング @@ -876,106 +712,82 @@ location set Sidebar - - CONNECT 接続 - OFFLINE オフライン - - ONLINE オンライン - ERROR エラー - - - TEMP 温度 - HIGH 高温 - GOOD 最適 - OK OK - VEHICLE 車両 - NO NO - PANDA PANDA - GPS GPS - SEARCH 検索 - -- -- - Wi-Fi Wi-Fi - ETH ETH - 2G 2G - 3G 3G - LTE LTE - 5G 5G @@ -983,63 +795,50 @@ location set SoftwarePanel - Updates are only downloaded while the car is off. 車の電源がオフの間のみ、アップデートのダウンロードが行われます。 - Current Version 現在のバージョン - Download ダウンロード - Install Update アップデート - INSTALL インストール - Target Branch 対象のブランチ - SELECT 選択 - Select a branch ブランチを選択 - UNINSTALL アンインストール - Uninstall %1 %1をアンインストール - Are you sure you want to uninstall? アンインストールしてもよろしいですか? - - CHECK 確認 @@ -1047,48 +846,38 @@ location set SshControl - SSH Keys SSH 鍵 - Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. 警告: これは、GitHub の設定にあるすべての公開鍵への SSH アクセスを許可するものです。自分以外の GitHub のユーザー名を入力しないでください。コンマのスタッフが GitHub のユーザー名を追加するようお願いすることはありません。 - - ADD 追加 - Enter your GitHub username GitHub のユーザー名を入力してください - LOADING ローディング - REMOVE 削除 - Username '%1' has no keys on GitHub ユーザー名 “%1” は GitHub に鍵がありません - Request timed out リクエストタイムアウト - Username '%1' doesn't exist on GitHub ユーザー名 '%1' は GitHub に存在しません @@ -1096,7 +885,6 @@ location set SshToggle - Enable SSH SSH を有効化 @@ -1104,22 +892,18 @@ location set TermsPage - Terms & Conditions 利用規約 - Decline 拒否 - Scroll to accept スクロールして同意 - Agree 同意 @@ -1127,102 +911,82 @@ location set TogglesPanel - Enable openpilot openpilot を有効化 - Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. アダプティブクルーズコントロールとレーンキーピングドライバーアシスト(openpilotシステム)。この機能を使用するには、常に注意が必要です。この設定を変更すると、車の電源が切れたときに有効になります。 - Enable Lane Departure Warnings 車線逸脱警報機能を有効化 - Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). 時速31マイル(50km)を超えるスピードで走行中、ウインカーを作動させずに検出された車線ライン上に車両が触れた場合、車線に戻るアラートを受信します。 - Use Metric System メートル法を有効化 - Display speed in km/h instead of mph. 速度は mph ではなく km/h で表示されます。 - Record and Upload Driver Camera 車内カメラの録画とアップロード - Upload data from the driver facing camera and help improve the driver monitoring algorithm. 車内カメラの映像をアップロードし、ドライバー監視システムのアルゴリズムの向上に役立てます。 - 🌮 End-to-end longitudinal (extremely alpha) 🌮 🌮 エンドツーエンドのアクセル制御 (超アルファ版) 🌮 - Experimental openpilot longitudinal control 実験段階のopenpilotによるアクセル制御 - <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b> <b>警告: openpilotによるアクセル制御は実験段階であり、AEBを無効化します。</b> - Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. アクセルとブレーキの制御をopenpilotに任せます。openpilotが人間と同じように運転します。最初期の実験段階です。 - openpilot longitudinal control is not currently available for this car. openpilotによるアクセル制御は、この車では現在利用できません。 - Enable experimental longitudinal control to enable this. ここ機能を使う為には、「実験段階のopenpilotによるアクセル制御」を先に有効化してください。 - Disengage On Accelerator Pedal アクセル踏むと openpilot をキャンセル - When enabled, pressing the accelerator pedal will disengage openpilot. 有効な場合は、アクセルを踏むと openpilot をキャンセルします。 - Show ETA in 24h Format 24時間表示 - Use 24h format instead of am/pm AM/PM の代わりに24時間形式を使用します - Show Map on Left Side of UI ディスプレイの左側にマップを表示 - Show map on left side when in split screen view. 分割画面表示の場合、ディスプレイの左側にマップを表示します。 @@ -1230,42 +994,34 @@ location set Updater - Update Required 更新が必要です - An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. オペレーティングシステムのアップデートが必要です。Wi-Fi に接続することで、最速のアップデートを体験できます。ダウンロードサイズは約 1GB です。 - Connect to Wi-Fi Wi-Fi に接続 - Install インストール - Back 戻る - Loading... 読み込み中... - Reboot 再起動 - Update failed 更新失敗 @@ -1273,22 +1029,18 @@ location set WifiUI - Scanning for networks... ネットワークをスキャン中... - CONNECTING... 接続中... - FORGET 削除 - Forget Wi-Fi Network "%1"? Wi-Fiネットワーク%1を削除してもよろしいですか? diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 17914f21d8..2a806aaed9 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -4,17 +4,14 @@ AbstractAlert - Close 닫기 - Snooze Update 업데이트 일시중지 - Reboot and Update 업데이트 및 재부팅 @@ -22,53 +19,42 @@ AdvancedNetworking - Back 뒤로 - Enable Tethering 테더링 사용 - Tethering Password 테더링 비밀번호 - - EDIT 편집 - Enter new tethering password 새 테더링 비밀번호를 입력하세요 - IP Address IP 주소 - Enable Roaming 로밍 사용 - APN Setting APN 설정 - Enter APN APN 입력 - leave blank for automatic configuration 자동설정하려면 공백으로 두세요 @@ -76,13 +62,10 @@ ConfirmationDialog - - Ok 확인 - Cancel 취소 @@ -90,17 +73,14 @@ DeclinePage - You must accept the Terms and Conditions in order to use openpilot. openpilot을 사용하려면 이용약관에 동의해야 합니다. - Back 뒤로 - Decline, uninstall %1 거절, %1 제거 @@ -108,152 +88,122 @@ DevicePanel - Dongle ID Dongle ID - N/A N/A - Serial Serial - Driver Camera 운전자 카메라 - PREVIEW 미리보기 - Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 운전자 모니터링이 좋은 가시성을 갖도록 운전자를 향한 카메라를 미리 봅니다. (차량연결은 해제되어있어야 합니다) - Reset Calibration 캘리브레이션 - RESET 재설정 - Are you sure you want to reset calibration? 캘리브레이션을 재설정하시겠습니까? - Review Training Guide 트레이닝 가이드 - REVIEW 다시보기 - Review the rules, features, and limitations of openpilot openpilot의 규칙, 기능 및 제한 다시보기 - Are you sure you want to review the training guide? 트레이닝 가이드를 다시보시겠습니까? - Regulatory 규제 - VIEW 보기 - Change Language 언어 변경 - CHANGE 변경 - Select a language 언어를 선택하세요 - Reboot 재부팅 - Power Off 전원 종료 - openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot은 좌우측은 4° 이내, 위쪽은 5° 아래쪽은 8° 이내로 장치를 설치해야 합니다. openpilot은 지속적으로 보정되므로 리셋은 거의 필요하지 않습니다. - Your device is pointed %1° %2 and %3° %4. 사용자의 장치가 %1° %2 및 %3° %4 위치에 설치되어있습니다. - down 아래로 - up 위로 - left 좌측으로 - right 우측으로 - Are you sure you want to reboot? 재부팅 하시겠습니까? - Disengage to Reboot 재부팅 하려면 해제하세요 - Are you sure you want to power off? 전원을 종료하시겠습니까? - Disengage to Power Off 전원을 종료하려면 해제하세요 @@ -261,32 +211,26 @@ DriveStats - Drives 주행 - Hours 시간 - ALL TIME 전체 - PAST WEEK 지난주 - KM Km - Miles Miles @@ -294,7 +238,6 @@ DriverViewScene - camera starting 카메라 시작중 @@ -302,12 +245,10 @@ InputDialog - Cancel 취소 - Need at least %n character(s)! 최소 %n 자가 필요합니다! @@ -317,22 +258,18 @@ Installer - Installing... 설치중... - Receiving objects: 수신중: - Resolving deltas: 델타병합: - Updating files: 파일갱신: @@ -340,27 +277,22 @@ MapETA - eta 도착 - min - hr 시간 - km km - mi mi @@ -368,22 +300,18 @@ MapInstructions - km km - m m - mi mi - ft ft @@ -391,48 +319,40 @@ MapPanel - Current Destination 현재 목적지 - CLEAR 삭제 - Recent Destinations 최근 목적지 - Try the Navigation Beta 네비게이션(베타)를 사용해보세요 - Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai 자세한 경로안내를 원하시면 comma prime을 구독하세요. 등록:https://connect.comma.ai - No home location set 집 설정되지않음 - No work location set 회사 설정되지않음 - no recent destinations 최근 목적지 없음 @@ -440,12 +360,10 @@ location set MapWindow - Map Loading 지도 로딩 - Waiting for GPS GPS를 기다리는 중 @@ -453,12 +371,10 @@ location set MultiOptionDialog - Select 선택 - Cancel 취소 @@ -466,23 +382,18 @@ location set Networking - Advanced 고급 설정 - Enter password 비밀번호를 입력하세요 - - for "%1" "%1"에 접속하려면 인증이 필요합니다 - Wrong password 비밀번호가 틀렸습니다 @@ -490,30 +401,22 @@ location set NvgWindow - km/h km/h - mph mph - - MAX MAX - - SPEED SPEED - - LIMIT LIMIT @@ -521,17 +424,14 @@ location set OffroadHome - UPDATE 업데이트 - ALERTS 알림 - ALERT 알림 @@ -539,22 +439,18 @@ location set PairingPopup - Pair your device to your comma account 장치를 콤마 계정과 페어링합니다 - Go to https://connect.comma.ai on your phone https://connect.comma.ai에 접속하세요 - Click "add new device" and scan the QR code on the right "새 장치 추가"를 클릭하고 오른쪽 QR 코드를 검색합니다 - Bookmark connect.comma.ai to your home screen to use it like an app connect.comma.ai을 앱처럼 사용하려면 홈 화면에 바로가기를 만드십시오 @@ -562,32 +458,26 @@ location set PrimeAdWidget - Upgrade Now 지금 업그레이드 - Become a comma prime member at connect.comma.ai connect.comma.ai에서 comma prime에 가입합니다 - PRIME FEATURES: PRIME 기능: - Remote access 원격 접속 - 1 year of storage 1년간 저장 - Developer perks 개발자 혜택 @@ -595,22 +485,18 @@ location set PrimeUserWidget - ✓ SUBSCRIBED ✓ 구독함 - comma prime comma prime - CONNECT.COMMA.AI CONNECT.COMMA.AI - COMMA POINTS COMMA POINTS @@ -618,41 +504,34 @@ location set QObject - Reboot 재부팅 - Exit 종료 - dashcam dashcam - openpilot openpilot - %n minute(s) ago %n 분전 - %n hour(s) ago %n 시간전 - %n day(s) ago %n 일전 @@ -662,47 +541,38 @@ location set Reset - Reset failed. Reboot to try again. 초기화 실패. 재부팅후 다시 시도하세요. - Are you sure you want to reset your device? 장치를 초기화 하시겠습니까? - Resetting device... 장치 초기화중... - System Reset 장치 초기화 - System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. 장치를 초기화 합니다. 확인버튼을 누르면 모든 내용과 설정이 초기화됩니다. 부팅을 재개하려면 취소를 누르세요. - Cancel 취소 - Reboot 재부팅 - Confirm 확인 - Unable to mount data partition. Press confirm to reset your device. 데이터 파티션을 마운트할 수 없습니다. 확인 버튼을 눌러 장치를 리셋합니다. @@ -710,7 +580,6 @@ location set RichTextDialog - Ok 확인 @@ -718,33 +587,26 @@ location set SettingsWindow - × × - Device 장치 - - Network 네트워크 - Toggles 토글 - Software 소프트웨어 - Navigation 네비게이션 @@ -752,105 +614,82 @@ location set Setup - WARNING: Low Voltage 경고: 전압이 낮습니다 - Power your device in a car with a harness or proceed at your own risk. 하네스 보드에 차량의 전원을 연결하세요. - Power off 전원 종료 - - - Continue 계속 - Getting Started 설정 시작 - Before we get on the road, let’s finish installation and cover some details. 출발하기 전에 설정을 완료하고 몇 가지 세부 사항을 살펴보겠습니다. - Connect to Wi-Fi wifi 연결 - - Back 뒤로 - Continue without Wi-Fi wifi 연결없이 계속하기 - Waiting for internet 네트워크 접속을 기다립니다 - Choose Software to Install 설치할 소프트웨어를 선택하세요 - Dashcam Dashcam - Custom Software Custom Software - Enter URL URL 입력 - for Custom Software for Custom Software - Downloading... 다운로드중... - Download Failed 다운로드 실패 - Ensure the entered URL is valid, and the device’s internet connection is good. 입력된 URL이 유효하고 장치의 네트워크 연결이 잘 되어 있는지 확인하세요. - Reboot device 재부팅 - Start over 다시 시작 @@ -858,17 +697,14 @@ location set SetupWidget - Finish Setup 설정 완료 - Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. 장치를 (connect.comma.ai)에서 페어링하고 comma prime 오퍼를 청구합니다. - Pair device 장치 페어링 @@ -876,106 +712,82 @@ location set Sidebar - - CONNECT 연결 - OFFLINE 오프라인 - - ONLINE 온라인 - ERROR 오류 - - - TEMP 온도 - HIGH 높음 - GOOD 좋음 - OK 경고 - VEHICLE 차량 - NO NO - PANDA PANDA - GPS GPS - SEARCH 검색중 - -- -- - Wi-Fi Wi-Fi - ETH 이더넷 - 2G 2G - 3G 3G - LTE LTE - 5G 5G @@ -983,63 +795,50 @@ location set SoftwarePanel - Updates are only downloaded while the car is off. 업데이트는 차량 연결이 해제되어 있는 동안에만 다운로드됩니다. - Current Version 현재 버전 - Download 다운로드 - Install Update 업데이트 설치 - INSTALL 설치 - Target Branch 대상 브랜치 - SELECT 선택 - Select a branch 브랜치 선택 - UNINSTALL 제거 - Uninstall %1 %1 제거 - Are you sure you want to uninstall? 제거하시겠습니까? - - CHECK 확인 @@ -1047,48 +846,38 @@ location set SshControl - SSH Keys SSH 키 - Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. 경고: 허용으로 설정하면 GitHub 설정의 모든 공용 키에 대한 SSH 액세스 권한이 부여됩니다. GitHub 사용자 ID 이외에는 입력하지 마십시오. comma에서는 GitHub ID를 추가하라는 요청을 하지 않습니다. - - ADD 추가 - Enter your GitHub username GitHub 사용자 ID - LOADING 로딩 - REMOVE 제거 - Username '%1' has no keys on GitHub '%1'의 키가 GitHub에 없습니다 - Request timed out 요청 시간 초과 - Username '%1' doesn't exist on GitHub '%1'은 GitHub에 없습니다 @@ -1096,7 +885,6 @@ location set SshToggle - Enable SSH SSH 사용 @@ -1104,22 +892,18 @@ location set TermsPage - Terms & Conditions 약관 - Decline 거절 - Scroll to accept 허용하려면 아래로 스크롤하세요 - Agree 동의 @@ -1127,102 +911,82 @@ location set TogglesPanel - Enable openpilot openpilot 사용 - Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. 어댑티브 크루즈 컨트롤 및 차선 유지 운전자 보조를 위해 openpilot 시스템을 사용하십시오. 이 기능을 사용하려면 항상 주의를 기울여야 합니다. 설정변경은 장치 재부팅후 적용됩니다. - Enable Lane Departure Warnings 차선 이탈 경고 사용 - Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). 차량이 50km/h(31mph) 이상의 속도로 주행하는 동안 방향지시등 없이 감지된 차선 위를 주행할 경우 차선이탈 경고를 표시합니다. - Use Metric System 미터법 사용 - Display speed in km/h instead of mph. mph 대신 km/h로 속도를 표시합니다. - Record and Upload Driver Camera 운전자 카메라 녹화 및 업로드 - Upload data from the driver facing camera and help improve the driver monitoring algorithm. 운전자 카메라에서 데이터를 업로드하고 운전자 모니터링 알고리즘을 개선합니다. - 🌮 End-to-end longitudinal (extremely alpha) 🌮 🌮 e2e 롱컨트롤 사용 (매우 실험적) 🌮 - Experimental openpilot longitudinal control openpilot 롱컨트롤 (실험적) - <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b> <b>경고: openpilot 롱컨트롤은 실험적인 기능으로 차량의 AEB를 비활성화합니다.</b> - Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. 주행모델이 가속과 감속을 제어하도록 하면 openpilot은 운전자가 생각하는것처럼 운전합니다. (매우 실험적) - openpilot longitudinal control is not currently available for this car. - Enable experimental longitudinal control to enable this. - Disengage On Accelerator Pedal 가속페달 조작시 해제 - When enabled, pressing the accelerator pedal will disengage openpilot. 활성화된 경우 가속 페달을 누르면 openpilot이 해제됩니다. - Show ETA in 24h Format 24시간 형식으로 도착예정시간 표시 - Use 24h format instead of am/pm 오전/오후 대신 24시간 형식 사용 - Show Map on Left Side of UI UI 왼쪽에 지도 표시 - Show map on left side when in split screen view. 분할 화면 보기에서 지도를 왼쪽에 표시합니다. @@ -1230,42 +994,34 @@ location set Updater - Update Required 업데이트 필요 - An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. OS 업데이트가 필요합니다. 장치를 wifi에 연결하면 가장 빠른 업데이트 경험을 제공합니다. 다운로드 크기는 약 1GB입니다. - Connect to Wi-Fi wifi 연결 - Install 설치 - Back 뒤로 - Loading... 로딩중... - Reboot 재부팅 - Update failed 업데이트 실패 @@ -1273,22 +1029,18 @@ location set WifiUI - Scanning for networks... 네트워크 검색 중... - CONNECTING... 연결중... - FORGET 저장안함 - Forget Wi-Fi Network "%1"? wifi 네트워크 저장안함 "%1"? diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index a490b4088d..ff6f27dd46 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -4,17 +4,14 @@ AbstractAlert - Close Fechar - Snooze Update Adiar Atualização - Reboot and Update Reiniciar e Atualizar @@ -22,53 +19,42 @@ AdvancedNetworking - Back Voltar - Enable Tethering Ativar Tether - Tethering Password Senha Tethering - - EDIT EDITAR - Enter new tethering password Insira nova senha tethering - IP Address Endereço IP - Enable Roaming Ativar Roaming - APN Setting APN Config - Enter APN Insira APN - leave blank for automatic configuration deixe em branco para configuração automática @@ -76,13 +62,10 @@ ConfirmationDialog - - Ok OK - Cancel Cancelar @@ -90,17 +73,14 @@ DeclinePage - You must accept the Terms and Conditions in order to use openpilot. Você precisa aceitar os Termos e Condições para utilizar openpilot. - Back Voltar - Decline, uninstall %1 Rejeitar, desintalar %1 @@ -108,152 +88,122 @@ DevicePanel - Dongle ID Dongle ID - N/A N/A - Serial Serial - Driver Camera Câmera voltada para o Motorista - PREVIEW PREVISUAL - Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) Pré-visualizar a câmera voltada para o motorista para garantir que monitor tem uma boa visibilidade (veículo precisa estar desligado) - Reset Calibration Resetar Calibragem - RESET RESET - Are you sure you want to reset calibration? Tem certeza que quer resetar a calibragem? - Review Training Guide Revisar Guia de Treinamento - REVIEW REVISAR - Review the rules, features, and limitations of openpilot Revisar regras, aprimoramentos e limitações do openpilot - Are you sure you want to review the training guide? Tem certeza que quer rever o treinamento? - Regulatory Regulatório - VIEW VER - Change Language Alterar Idioma - CHANGE ALTERAR - Select a language Selecione o Idioma - Reboot Reiniciar - Power Off Desligar - openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. o openpilot requer que o dispositivo seja montado dentro de 4° esquerda ou direita e dentro de 5° para cima ou 8° para baixo. o openpilot está continuamente calibrando, resetar raramente é necessário. - Your device is pointed %1° %2 and %3° %4. Seu dispositivo está montado %1° %2 e %3° %4. - down baixo - up cima - left esquerda - right direita - Are you sure you want to reboot? Tem certeza que quer reiniciar? - Disengage to Reboot Desacione para Reiniciar - Are you sure you want to power off? Tem certeza que quer desligar? - Disengage to Power Off Desacione para Desligar @@ -261,32 +211,26 @@ DriveStats - Drives Dirigidas - Hours Horas - ALL TIME TOTAL - PAST WEEK SEMANA PASSADA - KM KM - Miles Milhas @@ -294,7 +238,6 @@ DriverViewScene - camera starting câmera iniciando @@ -302,12 +245,10 @@ InputDialog - Cancel Cancelar - Need at least %n character(s)! Necessita no mínimo %n caractere! @@ -318,22 +259,18 @@ Installer - Installing... Instalando... - Receiving objects: Recebendo objetos: - Resolving deltas: Resolvendo deltas: - Updating files: Atualizando arquivos: @@ -341,27 +278,22 @@ MapETA - eta eta - min min - hr hr - km km - mi mi @@ -369,22 +301,18 @@ MapInstructions - km km - m m - mi milha - ft pés @@ -392,48 +320,40 @@ MapPanel - Current Destination Destino Atual - CLEAR LIMPAR - Recent Destinations Destinos Recentes - Try the Navigation Beta Experimente a Navegação Beta - Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai Obtenha instruções passo a passo exibidas e muito mais com uma assinatura prime Inscreva-se agora: https://connect.comma.ai - No home location set Sem local residência definido - No work location set Sem local de trabalho definido - no recent destinations sem destinos recentes @@ -441,12 +361,10 @@ trabalho definido MapWindow - Map Loading Carregando Mapa - Waiting for GPS Esperando por GPS @@ -454,12 +372,10 @@ trabalho definido MultiOptionDialog - Select Selecione - Cancel Cancelar @@ -467,23 +383,18 @@ trabalho definido Networking - Advanced Avançado - Enter password Insira a senha - - for "%1" para "%1" - Wrong password Senha incorreta @@ -491,30 +402,22 @@ trabalho definido NvgWindow - km/h km/h - mph mph - - MAX LIMITE - - SPEED MAX - - LIMIT VELO @@ -522,17 +425,14 @@ trabalho definido OffroadHome - UPDATE ATUALIZAÇÃO - ALERTS ALERTAS - ALERT ALERTA @@ -540,22 +440,18 @@ trabalho definido PairingPopup - Pair your device to your comma account Pareie seu dispositivo à sua conta comma - Go to https://connect.comma.ai on your phone navegue até https://connect.comma.ai no seu telefone - Click "add new device" and scan the QR code on the right Clique "add new device" e escaneie o QR code a seguir - Bookmark connect.comma.ai to your home screen to use it like an app Salve connect.comma.ai como sua página inicial para utilizar como um app @@ -563,32 +459,26 @@ trabalho definido PrimeAdWidget - Upgrade Now Atualizar Agora - Become a comma prime member at connect.comma.ai Torne-se um membro comma prime em connect.comma.ai - PRIME FEATURES: APRIMORAMENTOS PRIME: - Remote access Acesso remoto - 1 year of storage 1 ano de armazenamento - Developer perks Benefícios para desenvolvedor @@ -596,22 +486,18 @@ trabalho definido PrimeUserWidget - ✓ SUBSCRIBED ✓ INSCRITO - comma prime comma prime - CONNECT.COMMA.AI CONNECT.COMMA.AI - COMMA POINTS PONTOS COMMA @@ -619,27 +505,22 @@ trabalho definido QObject - Reboot Reiniciar - Exit Sair - dashcam dashcam - openpilot openpilot - %n minute(s) ago há %n minuto @@ -647,7 +528,6 @@ trabalho definido - %n hour(s) ago há %n hora @@ -655,7 +535,6 @@ trabalho definido - %n day(s) ago há %n dia @@ -666,47 +545,38 @@ trabalho definido Reset - Reset failed. Reboot to try again. Reset falhou. Reinicie para tentar novamente. - Are you sure you want to reset your device? Tem certeza que quer resetar seu dispositivo? - Resetting device... Resetando dispositivo... - System Reset Resetar Sistema - System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. Solicitado reset do sistema. Confirme para apagar todo conteúdo e configurações. Aperte cancelar para continuar boot. - Cancel Cancelar - Reboot Reiniciar - Confirm Confirmar - Unable to mount data partition. Press confirm to reset your device. Não foi possível montar a partição de dados. Pressione confirmar para resetar seu dispositivo. @@ -714,7 +584,6 @@ trabalho definido RichTextDialog - Ok Ok @@ -722,33 +591,26 @@ trabalho definido SettingsWindow - × × - Device Dispositivo - - Network Rede - Toggles Ajustes - Software Software - Navigation Navegação @@ -756,105 +618,82 @@ trabalho definido Setup - WARNING: Low Voltage ALERTA: Baixa Voltagem - Power your device in a car with a harness or proceed at your own risk. Ligue seu dispositivo em um carro com um chicote ou prossiga por sua conta e risco. - Power off Desligar - - - Continue Continuar - Getting Started Começando - Before we get on the road, let’s finish installation and cover some details. Antes de pegarmos a estrada, vamos terminar a instalação e cobrir alguns detalhes. - Connect to Wi-Fi Conectar ao Wi-Fi - - Back Voltar - Continue without Wi-Fi Continuar sem Wi-Fi - Waiting for internet Esperando pela internet - Choose Software to Install Escolher Software para Instalar - Dashcam Dashcam - Custom Software Sofware Customizado - Enter URL Preencher URL - for Custom Software para o Software Customizado - Downloading... Baixando... - Download Failed Download Falhou - Ensure the entered URL is valid, and the device’s internet connection is good. Garanta que a URL inserida é valida, e uma boa conexão à internet. - Reboot device Reiniciar Dispositivo - Start over Inicializar @@ -862,17 +701,14 @@ trabalho definido SetupWidget - Finish Setup Concluir - Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. Pareie seu dispositivo com comma connect (connect.comma.ai) e reivindique sua oferta de comma prime. - Pair device Parear dispositivo @@ -880,106 +716,82 @@ trabalho definido Sidebar - - CONNECT CONEXÃO - OFFLINE OFFLINE - - ONLINE ONLINE - ERROR ERRO - - - TEMP TEMP - HIGH ALTA - GOOD BOA - OK OK - VEHICLE VEÍCULO - NO SEM - PANDA PANDA - GPS GPS - SEARCH PROCURA - -- -- - Wi-Fi Wi-Fi - ETH ETH - 2G 2G - 3G 3G - LTE LTE - 5G 5G @@ -987,63 +799,50 @@ trabalho definido SoftwarePanel - Updates are only downloaded while the car is off. Atualizações baixadas durante o motor desligado. - Current Version Versao Atual - Download Download - Install Update Instalar Atualização - INSTALL INSTALAR - Target Branch Alterar Branch - SELECT SELECIONE - Select a branch Selecione uma branch - UNINSTALL DESINSTAL - Uninstall %1 Desintalar o %1 - Are you sure you want to uninstall? Tem certeza que quer desinstalar? - - CHECK VERIFICAR @@ -1051,48 +850,38 @@ trabalho definido SshControl - SSH Keys Chave SSH - Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. Aviso: isso concede acesso SSH a todas as chaves públicas nas configurações do GitHub. Nunca insira um nome de usuário do GitHub que não seja o seu. Um funcionário da comma NUNCA pedirá que você adicione seu nome de usuário do GitHub. - - ADD ADICIONAR - Enter your GitHub username Insira seu nome de usuário do GitHub - LOADING CARREGANDO - REMOVE REMOVER - Username '%1' has no keys on GitHub Usuário "%1” não possui chaves no GitHub - Request timed out A solicitação expirou - Username '%1' doesn't exist on GitHub Usuário '%1' não existe no GitHub @@ -1100,7 +889,6 @@ trabalho definido SshToggle - Enable SSH Habilitar SSH @@ -1108,22 +896,18 @@ trabalho definido TermsPage - Terms & Conditions Termos & Condições - Decline Declinar - Scroll to accept Role a tela para aceitar - Agree Concordo @@ -1131,102 +915,82 @@ trabalho definido TogglesPanel - Enable openpilot Ativar openpilot - Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. Use o sistema openpilot para controle de cruzeiro adaptativo e assistência ao motorista de manutenção de faixa. Sua atenção é necessária o tempo todo para usar esse recurso. A alteração desta configuração tem efeito quando o carro é desligado. - Enable Lane Departure Warnings Ativar Avisos de Saída de Faixa - Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). Receba alertas para voltar para a pista se o seu veículo sair da faixa e a seta não tiver sido acionada previamente quando em velocidades superiores a 50 km/h. - Use Metric System Usar Sistema Métrico - Display speed in km/h instead of mph. Exibir velocidade em km/h invés de mph. - Record and Upload Driver Camera Gravar e Upload Câmera Motorista - Upload data from the driver facing camera and help improve the driver monitoring algorithm. Upload dados da câmera voltada para o motorista e ajude a melhorar o algoritmo de monitoramentor. - 🌮 End-to-end longitudinal (extremely alpha) 🌮 🌮 End-to-end longitudinal (experimental) 🌮 - Experimental openpilot longitudinal control Controle longitudinal experimental openpilot - <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b> <b>AVISO: o controle longitudinal openpilot é experimental para este carro e irá desabilitar AEB.</b> - Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. Deixe o modelo controlar o acelerador e os freios. openpilot irá conduzir como pensa que um humano faria. Super experimental. - openpilot longitudinal control is not currently available for this car. controle longitudinal openpilot não está disponível para este carro. - Enable experimental longitudinal control to enable this. Habilite o controle longitudinal experimental para habilitar isso. - Disengage On Accelerator Pedal Desacionar Com Pedal Do Acelerador - When enabled, pressing the accelerator pedal will disengage openpilot. Quando ativado, pressionar o pedal do acelerador desacionará o openpilot. - Show ETA in 24h Format Mostrar ETA em formato 24h - Use 24h format instead of am/pm Use o formato 24h em vez de am/pm - Show Map on Left Side of UI Exibir Mapa no Lado Esquerdo - Show map on left side when in split screen view. Exibir mapa do lado esquerdo quando a tela for dividida. @@ -1234,42 +998,34 @@ trabalho definido Updater - Update Required Atualização Necessária - An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. Uma atualização do sistema operacional é necessária. Conecte seu dispositivo ao Wi-Fi para a experiência de atualização mais rápida. O tamanho do download é de aproximadamente 1GB. - Connect to Wi-Fi Conecte-se ao Wi-Fi - Install Instalar - Back Voltar - Loading... Carregando... - Reboot Reiniciar - Update failed Falha na atualização @@ -1277,22 +1033,18 @@ trabalho definido WifiUI - Scanning for networks... Procurando redes... - CONNECTING... CONECTANDO... - FORGET ESQUECER - Forget Wi-Fi Network "%1"? Esquecer Rede Wi-Fi "%1"? diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 28008ef06f..6300875ee3 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -4,17 +4,14 @@ AbstractAlert - Close 关闭 - Snooze Update 暂停更新 - Reboot and Update 重启并更新 @@ -22,53 +19,42 @@ AdvancedNetworking - Back 返回 - Enable Tethering 启用WiFi热点 - Tethering Password WiFi热点密码 - - EDIT 编辑 - Enter new tethering password 输入新的WiFi热点密码 - IP Address IP地址 - Enable Roaming 启用数据漫游 - APN Setting APN设置 - Enter APN 输入APN - leave blank for automatic configuration 留空以自动配置 @@ -76,13 +62,10 @@ ConfirmationDialog - - Ok 好的 - Cancel 取消 @@ -90,17 +73,14 @@ DeclinePage - You must accept the Terms and Conditions in order to use openpilot. 您必须接受条款和条件以使用openpilot。 - Back 返回 - Decline, uninstall %1 拒绝并卸载%1 @@ -108,152 +88,122 @@ DevicePanel - Dongle ID 设备ID(Dongle ID) - N/A N/A - Serial 序列号 - Driver Camera 驾驶员摄像头 - PREVIEW 预览 - Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 打开并预览驾驶员摄像头,以确保驾驶员监控具有良好视野。仅熄火时可用。 - Reset Calibration 重置设备校准 - RESET 重置 - Are you sure you want to reset calibration? 您确定要重置设备校准吗? - Review Training Guide 新手指南 - REVIEW 查看 - Review the rules, features, and limitations of openpilot 查看openpilot的使用规则,以及其功能和限制。 - Are you sure you want to review the training guide? 您确定要查看新手指南吗? - Regulatory 监管信息 - VIEW 查看 - Change Language 切换语言 - CHANGE 切换 - Select a language 选择语言 - Reboot 重启 - Power Off 关机 - openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot要求设备安装的偏航角在左4°和右4°之间,俯仰角在上5°和下8°之间。一般来说,openpilot会持续更新校准,很少需要重置。 - Your device is pointed %1° %2 and %3° %4. 您的设备校准为%1° %2、%3° %4。 - down 朝下 - up 朝上 - left 朝左 - right 朝右 - Are you sure you want to reboot? 您确定要重新启动吗? - Disengage to Reboot 取消openpilot以重新启动 - Are you sure you want to power off? 您确定要关机吗? - Disengage to Power Off 取消openpilot以关机 @@ -261,32 +211,26 @@ DriveStats - Drives 旅程数 - Hours 小时 - ALL TIME 全部 - PAST WEEK 过去一周 - KM 公里 - Miles 英里 @@ -294,7 +238,6 @@ DriverViewScene - camera starting 正在启动相机 @@ -302,12 +245,10 @@ InputDialog - Cancel 取消 - Need at least %n character(s)! 至少需要 %n 个字符! @@ -317,22 +258,18 @@ Installer - Installing... 正在安装…… - Receiving objects: 正在接收: - Resolving deltas: 正在处理: - Updating files: 正在更新文件: @@ -340,27 +277,22 @@ MapETA - eta 埃塔 - min 分钟 - hr 小时 - km km - mi mi @@ -368,22 +300,18 @@ MapInstructions - km km - m m - mi mi - ft ft @@ -391,46 +319,38 @@ MapPanel - Current Destination 当前目的地 - CLEAR 清空 - Recent Destinations 最近目的地 - Try the Navigation Beta 试用导航测试版 - Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai 订阅comma prime以获取导航。 立即注册:https://connect.comma.ai - No home location set 家:未设定 - No work location set 工作:未设定 - no recent destinations 无最近目的地 @@ -438,12 +358,10 @@ location set MapWindow - Map Loading 地图加载中 - Waiting for GPS 等待 GPS @@ -451,12 +369,10 @@ location set MultiOptionDialog - Select 选择 - Cancel 取消 @@ -464,23 +380,18 @@ location set Networking - Advanced 高级 - Enter password 输入密码 - - for "%1" 网络名称:"%1" - Wrong password 密码错误 @@ -488,30 +399,22 @@ location set NvgWindow - km/h km/h - mph mph - - MAX 最高定速 - - SPEED SPEED - - LIMIT LIMIT @@ -519,17 +422,14 @@ location set OffroadHome - UPDATE 更新 - ALERTS 警报 - ALERT 警报 @@ -537,22 +437,18 @@ location set PairingPopup - Pair your device to your comma account 将您的设备与comma账号配对 - Go to https://connect.comma.ai on your phone 在手机上访问 https://connect.comma.ai - Click "add new device" and scan the QR code on the right 点击“添加新设备”,扫描右侧二维码 - Bookmark connect.comma.ai to your home screen to use it like an app 将 connect.comma.ai 收藏到您的主屏幕,以便像应用程序一样使用它 @@ -560,32 +456,26 @@ location set PrimeAdWidget - Upgrade Now 现在升级 - Become a comma prime member at connect.comma.ai 打开connect.comma.ai以注册comma prime会员 - PRIME FEATURES: comma prime特权: - Remote access 远程访问 - 1 year of storage 1年数据存储 - Developer perks 开发者福利 @@ -593,22 +483,18 @@ location set PrimeUserWidget - ✓ SUBSCRIBED ✓ 已订阅 - comma prime comma prime - CONNECT.COMMA.AI CONNECT.COMMA.AI - COMMA POINTS COMMA POINTS点数 @@ -616,41 +502,34 @@ location set QObject - Reboot 重启 - Exit 退出 - dashcam 行车记录仪 - openpilot openpilot - %n minute(s) ago %n 分钟前 - %n hour(s) ago %n 小时前 - %n day(s) ago %n 天前 @@ -660,47 +539,38 @@ location set Reset - Reset failed. Reboot to try again. 重置失败。 重新启动以重试。 - Are you sure you want to reset your device? 您确定要重置您的设备吗? - Resetting device... 正在重置设备…… - System Reset 恢复出厂设置 - System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. 已触发系统重置:确认以删除所有内容和设置。取消以正常启动设备。 - Cancel 取消 - Reboot 重启 - Confirm 确认 - Unable to mount data partition. Press confirm to reset your device. 无法挂载数据分区。 确认以重置您的设备。 @@ -708,7 +578,6 @@ location set RichTextDialog - Ok 好的 @@ -716,33 +585,26 @@ location set SettingsWindow - × × - Device 设备 - - Network 网络 - Toggles 设定 - Software 软件 - Navigation 导航 @@ -750,105 +612,82 @@ location set Setup - WARNING: Low Voltage 警告:低电压 - Power your device in a car with a harness or proceed at your own risk. 请使用car harness线束为您的设备供电,或自行承担风险。 - Power off 关机 - - - Continue 继续 - Getting Started 开始设置 - Before we get on the road, let’s finish installation and cover some details. 开始旅程之前,让我们完成安装并介绍一些细节。 - Connect to Wi-Fi 连接到WiFi - - Back 返回 - Continue without Wi-Fi 不连接WiFi并继续 - Waiting for internet 等待网络连接 - Choose Software to Install 选择要安装的软件 - Dashcam Dashcam(行车记录仪) - Custom Software 自定义软件 - Enter URL 输入网址 - for Custom Software 以下载自定义软件 - Downloading... 正在下载…… - Download Failed 下载失败 - Ensure the entered URL is valid, and the device’s internet connection is good. 请确保互联网连接良好且输入的URL有效。 - Reboot device 重启设备 - Start over 重来 @@ -856,17 +695,14 @@ location set SetupWidget - Finish Setup 完成设置 - Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. 将您的设备与comma connect (connect.comma.ai)配对并领取您的comma prime优惠。 - Pair device 配对设备 @@ -874,106 +710,82 @@ location set Sidebar - - CONNECT CONNECT - OFFLINE 离线 - - ONLINE 在线 - ERROR 连接出错 - - - TEMP 设备温度 - HIGH 过热 - GOOD 良好 - OK 一般 - VEHICLE 车辆连接 - NO - PANDA PANDA - GPS GPS - SEARCH 搜索中 - -- -- - Wi-Fi Wi-Fi - ETH 以太网 - 2G 2G - 3G 3G - LTE LTE - 5G 5G @@ -981,63 +793,50 @@ location set SoftwarePanel - Updates are only downloaded while the car is off. - Current Version - Download - Install Update - INSTALL - Target Branch - SELECT - Select a branch - UNINSTALL 卸载 - Uninstall %1 卸载 %1 - Are you sure you want to uninstall? 您确定要卸载吗? - - CHECK 查看 @@ -1045,48 +844,38 @@ location set SshControl - SSH Keys SSH密钥 - Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. 警告:这将授予SSH访问权限给您GitHub设置中的所有公钥。切勿输入您自己以外的GitHub用户名。comma员工永远不会要求您添加他们的GitHub用户名。 - - ADD 添加 - Enter your GitHub username 输入您的GitHub用户名 - LOADING 正在加载 - REMOVE 删除 - Username '%1' has no keys on GitHub 用户名“%1”在GitHub上没有密钥 - Request timed out 请求超时 - Username '%1' doesn't exist on GitHub GitHub上不存在用户名“%1” @@ -1094,7 +883,6 @@ location set SshToggle - Enable SSH 启用SSH @@ -1102,22 +890,18 @@ location set TermsPage - Terms & Conditions 条款和条件 - Decline 拒绝 - Scroll to accept 滑动以接受 - Agree 同意 @@ -1125,102 +909,82 @@ location set TogglesPanel - Enable openpilot 启用openpilot - Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. 使用openpilot进行自适应巡航和车道保持辅助。使用此功能时您必须时刻保持注意力。该设置的更改在熄火时生效。 - Enable Lane Departure Warnings 启用车道偏离警告 - Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). 车速超过31mph(50km/h)时,若检测到车辆越过车道线且未打转向灯,系统将发出警告以提醒您返回车道。 - Use Metric System 使用公制单位 - Display speed in km/h instead of mph. 显示车速时,以km/h代替mph。 - Record and Upload Driver Camera 录制并上传驾驶员摄像头 - Upload data from the driver facing camera and help improve the driver monitoring algorithm. 上传驾驶员摄像头的数据,帮助改进驾驶员监控算法。 - 🌮 End-to-end longitudinal (extremely alpha) 🌮 🌮 端对端纵向控制(实验性功能) 🌮 - Experimental openpilot longitudinal control - <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b> - Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. 让驾驶模型直接控制油门和刹车,openpilot将会模仿人类司机的驾驶方式。该功能仍非常实验性。 - openpilot longitudinal control is not currently available for this car. - Enable experimental longitudinal control to enable this. - Disengage On Accelerator Pedal 踩油门时取消控制 - When enabled, pressing the accelerator pedal will disengage openpilot. 启用后,踩下油门踏板将取消openpilot。 - Show ETA in 24h Format 以24小时格式显示预计到达时间 - Use 24h format instead of am/pm 使用24小时制代替am/pm - Show Map on Left Side of UI 在介面左侧显示地图 - Show map on left side when in split screen view. 在分屏模式中,将地图置于屏幕左侧。 @@ -1228,42 +992,34 @@ location set Updater - Update Required 需要更新 - An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. 操作系统需要更新。请将您的设备连接到WiFi以获取更快的更新体验。下载大小约为1GB。 - Connect to Wi-Fi 连接到WiFi - Install 安装 - Back 返回 - Loading... 正在加载…… - Reboot 重启 - Update failed 更新失败 @@ -1271,22 +1027,18 @@ location set WifiUI - Scanning for networks... 正在扫描网络…… - CONNECTING... 正在连接…… - FORGET 忘记 - Forget Wi-Fi Network "%1"? 忘记WiFi网络 "%1"? diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 364508bd1c..73faf11f69 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -4,17 +4,14 @@ AbstractAlert - Close 關閉 - Snooze Update 暫停更新 - Reboot and Update 重啟並更新 @@ -22,53 +19,42 @@ AdvancedNetworking - Back 回上頁 - Enable Tethering 啟用網路分享 - Tethering Password 網路分享密碼 - - EDIT 編輯 - Enter new tethering password 輸入新的網路分享密碼 - IP Address IP 地址 - Enable Roaming 啟用漫遊 - APN Setting APN 設置 - Enter APN 輸入 APN - leave blank for automatic configuration 留空白將自動配置 @@ -76,13 +62,10 @@ ConfirmationDialog - - Ok 確定 - Cancel 取消 @@ -90,17 +73,14 @@ DeclinePage - You must accept the Terms and Conditions in order to use openpilot. 您必須先接受條款和條件才能使用 openpilot。 - Back 回上頁 - Decline, uninstall %1 拒絕並卸載 %1 @@ -108,152 +88,122 @@ DevicePanel - Dongle ID Dongle ID - N/A 無法使用 - Serial 序號 - Driver Camera 駕駛員攝像頭 - PREVIEW 預覽 - Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 預覽駕駛員監控鏡頭畫面,以確保其具有良好視野。(僅在熄火時可用) - Reset Calibration 重置校準 - RESET 重置 - Are you sure you want to reset calibration? 您確定要重置校準嗎? - Review Training Guide 觀看使用教學 - REVIEW 觀看 - Review the rules, features, and limitations of openpilot 觀看 openpilot 的使用規則、功能和限制 - Are you sure you want to review the training guide? 您確定要觀看使用教學嗎? - Regulatory 法規/監管 - VIEW 觀看 - Change Language 更改語言 - CHANGE 更改 - Select a language 選擇語言 - Reboot 重新啟動 - Power Off 關機 - openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot 需要將裝置固定在左右偏差 4° 以內,朝上偏差 5° 以内或朝下偏差 8° 以内。鏡頭在後台會持續自動校準,很少有需要重置的情况。 - Your device is pointed %1° %2 and %3° %4. 你的設備目前朝%2 %1° 以及朝%4 %3° 。 - down - up - left - right - Are you sure you want to reboot? 您確定要重新啟動嗎? - Disengage to Reboot 請先取消控車才能重新啟動 - Are you sure you want to power off? 您確定您要關機嗎? - Disengage to Power Off 請先取消控車才能關機 @@ -261,32 +211,26 @@ DriveStats - Drives 旅程 - Hours 小時 - ALL TIME 總共 - PAST WEEK 上周 - KM 公里 - Miles 英里 @@ -294,7 +238,6 @@ DriverViewScene - camera starting 開啟相機中 @@ -302,12 +245,10 @@ InputDialog - Cancel 取消 - Need at least %n character(s)! 需要至少 %n 個字元! @@ -317,22 +258,18 @@ Installer - Installing... 安裝中… - Receiving objects: 接收對象: - Resolving deltas: 分析差異: - Updating files: 更新檔案: @@ -340,27 +277,22 @@ MapETA - eta 抵達 - min 分鐘 - hr 小時 - km km - mi mi @@ -368,22 +300,18 @@ MapInstructions - km km - m m - mi mi - ft ft @@ -391,48 +319,40 @@ MapPanel - Current Destination 當前目的地 - CLEAR 清除 - Recent Destinations 最近目的地 - Try the Navigation Beta 試用導航功能 - Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai 成為 comma 高級會員來使用導航功能 立即註冊:https://connect.comma.ai - No home location set 未設定 住家位置 - No work location set 未設定 工作位置 - no recent destinations 沒有最近的導航記錄 @@ -440,12 +360,10 @@ location set MapWindow - Map Loading 地圖加載中 - Waiting for GPS 等待 GPS @@ -453,12 +371,10 @@ location set MultiOptionDialog - Select 選擇 - Cancel 取消 @@ -466,23 +382,18 @@ location set Networking - Advanced 進階 - Enter password 輸入密碼 - - for "%1" 給 "%1" - Wrong password 密碼錯誤 @@ -490,30 +401,22 @@ location set NvgWindow - km/h km/h - mph mph - - MAX 最高 - - SPEED 速度 - - LIMIT 速限 @@ -521,17 +424,14 @@ location set OffroadHome - UPDATE 更新 - ALERTS 提醒 - ALERT 提醒 @@ -539,22 +439,18 @@ location set PairingPopup - Pair your device to your comma account 將設備與您的 comma 帳號配對 - Go to https://connect.comma.ai on your phone 用手機連至 https://connect.comma.ai - Click "add new device" and scan the QR code on the right 點選 "add new device" 後掃描右邊的二維碼 - Bookmark connect.comma.ai to your home screen to use it like an app 將 connect.comma.ai 加入您的主屏幕,以便像手機 App 一樣使用它 @@ -562,32 +458,26 @@ location set PrimeAdWidget - Upgrade Now 馬上升級 - Become a comma prime member at connect.comma.ai 成為 connect.comma.ai 的高級會員 - PRIME FEATURES: 高級會員特點: - Remote access 遠程訪問 - 1 year of storage 一年的雲端行車記錄 - Developer perks 開發者福利 @@ -595,22 +485,18 @@ location set PrimeUserWidget - ✓ SUBSCRIBED ✓ 已訂閱 - comma prime comma 高級會員 - CONNECT.COMMA.AI CONNECT.COMMA.AI - COMMA POINTS COMMA 積分 @@ -618,41 +504,34 @@ location set QObject - Reboot 重新啟動 - Exit 離開 - dashcam 行車記錄器 - openpilot openpilot - %n minute(s) ago %n 分鐘前 - %n hour(s) ago %n 小時前 - %n day(s) ago %n 天前 @@ -662,47 +541,38 @@ location set Reset - Reset failed. Reboot to try again. 重置失敗。請重新啟動後再試。 - Are you sure you want to reset your device? 您確定要重置你的設備嗎? - Resetting device... 重置設備中… - System Reset 系統重置 - System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. 系統重置已觸發。請按確認刪除所有內容和設置。按取消恢復啟動。 - Cancel 取消 - Reboot 重新啟動 - Confirm 確認 - Unable to mount data partition. Press confirm to reset your device. 無法掛載數據分區。請按確認重置您的設備。 @@ -710,7 +580,6 @@ location set RichTextDialog - Ok 確定 @@ -718,33 +587,26 @@ location set SettingsWindow - × × - Device 設備 - - Network 網路 - Toggles 設定 - Software 軟體 - Navigation 導航 @@ -752,105 +614,82 @@ location set Setup - WARNING: Low Voltage 警告:電壓過低 - Power your device in a car with a harness or proceed at your own risk. 請使用車上 harness 提供的電源,若繼續的話您需要自擔風險。 - Power off 關機 - - - Continue 繼續 - Getting Started 入門 - Before we get on the road, let’s finish installation and cover some details. 在我們上路之前,讓我們完成安裝並介紹一些細節。 - Connect to Wi-Fi 連接到無線網絡 - - Back 回上頁 - Continue without Wi-Fi 在沒有 Wi-Fi 的情況下繼續 - Waiting for internet 連接至網路中 - Choose Software to Install 選擇要安裝的軟體 - Dashcam 行車記錄器 - Custom Software 定制的軟體 - Enter URL 輸入網址 - for Custom Software 定制的軟體 - Downloading... 下載中… - Download Failed 下載失敗 - Ensure the entered URL is valid, and the device’s internet connection is good. 請確定您輸入的是有效的安裝網址,並且確定設備的網路連線狀態良好。 - Reboot device 重新啟動 - Start over 重新開始 @@ -858,17 +697,14 @@ location set SetupWidget - Finish Setup 完成設置 - Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. 將您的設備與 comma connect (connect.comma.ai) 配對並領取您的 comma 高級會員優惠。 - Pair device 配對設備 @@ -876,106 +712,82 @@ location set Sidebar - - CONNECT 雲端服務 - OFFLINE 已離線 - - ONLINE 已連線 - ERROR 錯誤 - - - TEMP 溫度 - HIGH 偏高 - GOOD 正常 - OK 一般 - VEHICLE 車輛通訊 - NO 未連線 - PANDA 車輛通訊 - GPS GPS - SEARCH 車輛通訊 - -- -- - Wi-Fi - ETH - 2G - 3G - LTE - 5G @@ -983,63 +795,50 @@ location set SoftwarePanel - Updates are only downloaded while the car is off. 系統更新只會在熄火時下載。 - Current Version 當前版本 - Download 下載 - Install Update 安裝更新 - INSTALL 安裝 - Target Branch 目標分支 - SELECT 選取 - Select a branch 選取一個分支 - UNINSTALL 卸載 - Uninstall %1 卸載 %1 - Are you sure you want to uninstall? 您確定您要卸載嗎? - - CHECK 檢查 @@ -1047,48 +846,38 @@ location set SshControl - SSH Keys SSH 密鑰 - Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. 警告:這將授權給 GitHub 帳號中所有公鑰 SSH 訪問權限。切勿輸入非您自己的 GitHub 用戶名。comma 員工「永遠不會」要求您添加他們的 GitHub 用戶名。 - - ADD 新增 - Enter your GitHub username 請輸入您 GitHub 的用戶名 - LOADING 載入中 - REMOVE 移除 - Username '%1' has no keys on GitHub GitHub 用戶 '%1' 沒有設定任何密鑰 - Request timed out 請求超時 - Username '%1' doesn't exist on GitHub GitHub 用戶 '%1' 不存在 @@ -1096,7 +885,6 @@ location set SshToggle - Enable SSH 啟用 SSH 服務 @@ -1104,22 +892,18 @@ location set TermsPage - Terms & Conditions 條款和條件 - Decline 拒絕 - Scroll to accept 滑動至頁尾接受條款 - Agree 接受 @@ -1127,102 +911,82 @@ location set TogglesPanel - Enable openpilot 啟用 openpilot - Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. 使用 openpilot 的主動式巡航和車道保持功能,開啟後您需要持續集中注意力,設定變更在重新啟動車輛後生效。 - Enable Lane Departure Warnings 啟用車道偏離警告 - Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). 車速在時速 50 公里 (31 英里) 以上且未打方向燈的情況下,如果偵測到車輛駛出目前車道線時,發出車道偏離警告。 - Use Metric System 使用公制單位 - Display speed in km/h instead of mph. 啟用後,速度單位顯示將從 mp/h 改為 km/h。 - Record and Upload Driver Camera 記錄並上傳駕駛監控影像 - Upload data from the driver facing camera and help improve the driver monitoring algorithm. 上傳駕駛監控的錄像來協助我們提升駕駛監控的準確率。 - 🌮 End-to-end longitudinal (extremely alpha) 🌮 🌮 端對端縱向控制(實驗性功能) 🌮 - Experimental openpilot longitudinal control 使用 openpilot 縱向控制(實驗) - <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b> <b>注意:這台車的 openpilot 縱向控制仍然是實驗中的功能,開啟這功能將會關閉自動緊急煞車 (AEB)。</b> - Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. 讓駕駛模型直接控製油門和剎車,openpilot將會模仿人類司機的駕駛方式。該功能仍非常實驗性。 - openpilot longitudinal control is not currently available for this car. openpilot 縱向控制目前不適用於這輛車。 - Enable experimental longitudinal control to enable this. 打開縱向控制(實驗)以啟用此功能。 - Disengage On Accelerator Pedal 油門取消控車 - When enabled, pressing the accelerator pedal will disengage openpilot. 啟用後,踩踏油門將會取消 openpilot 控制。 - Show ETA in 24h Format 預計到達時間單位改用 24 小時制 - Use 24h format instead of am/pm 使用 24 小時制。(預設值為 12 小時制) - Show Map on Left Side of UI 將地圖顯示在畫面的左側 - Show map on left side when in split screen view. 進入分割畫面後,地圖將會顯示在畫面的左側。 @@ -1230,42 +994,34 @@ location set Updater - Update Required 系統更新 - An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. 設備的操作系統需要更新。請將您的設備連接到 Wi-Fi 以獲得最快的更新體驗。下載大小約為 1GB。 - Connect to Wi-Fi 連接到無線網絡 - Install 安裝 - Back 回上頁 - Loading... 載入中… - Reboot 重新啟動 - Update failed 更新失敗 @@ -1273,22 +1029,18 @@ location set WifiUI - Scanning for networks... 掃描無線網路中... - CONNECTING... 連線中... - FORGET 清除 - Forget Wi-Fi Network "%1"? 清除 Wi-Fi 網路 "%1"? diff --git a/selfdrive/ui/update_translations.py b/selfdrive/ui/update_translations.py index afd42c3b3a..e15d4c3433 100755 --- a/selfdrive/ui/update_translations.py +++ b/selfdrive/ui/update_translations.py @@ -19,7 +19,7 @@ def update_translations(vanish=False, plural_only=None, translations_dir=TRANSLA for file in translation_files.values(): tr_file = os.path.join(translations_dir, f"{file}.ts") - args = f"lupdate -locations relative -recursive {UI_DIR} -ts {tr_file}" + args = f"lupdate -locations none -recursive {UI_DIR} -ts {tr_file}" if vanish: args += " -no-obsolete" if file in plural_only: From e4612ac4c48597864dabef6f25b4db0d846426e0 Mon Sep 17 00:00:00 2001 From: royjr Date: Sat, 17 Sep 2022 18:55:12 -0400 Subject: [PATCH 144/152] ui: fix toggle spacing issue (#25831) --- selfdrive/ui/qt/widgets/controls.cc | 2 -- 1 file changed, 2 deletions(-) diff --git a/selfdrive/ui/qt/widgets/controls.cc b/selfdrive/ui/qt/widgets/controls.cc index b5f646c379..a1ebf57b07 100644 --- a/selfdrive/ui/qt/widgets/controls.cc +++ b/selfdrive/ui/qt/widgets/controls.cc @@ -18,8 +18,6 @@ QFrame *horizontal_line(QWidget *parent) { } AbstractControl::AbstractControl(const QString &title, const QString &desc, const QString &icon, QWidget *parent) : QFrame(parent) { - setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Minimum); - QVBoxLayout *main_layout = new QVBoxLayout(this); main_layout->setMargin(0); From 583304fc7b5970ec5f079720bf6c6aa7ff91ce5a Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 19 Sep 2022 05:01:33 +0800 Subject: [PATCH 145/152] params: cleanup constructor (#25834) --- common/params.cc | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/common/params.cc b/common/params.cc index 7b2d4490ea..a64c2f133b 100644 --- a/common/params.cc +++ b/common/params.cc @@ -198,10 +198,8 @@ std::unordered_map keys = { Params::Params(const std::string &path) { - const char* env = std::getenv("OPENPILOT_PREFIX"); - prefix = env ? "/" + std::string(env) : "/d"; - std::string default_param_path = ensure_params_path(prefix); - params_path = path.empty() ? default_param_path : ensure_params_path(prefix, path); + prefix = "/" + util::getenv("OPENPILOT_PREFIX", "d"); + params_path = ensure_params_path(prefix, path); } std::vector Params::allKeys() const { From 8870b439dd5f9b0ae1a53d75bab3a1470ea7d372 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 20 Sep 2022 04:24:20 +0800 Subject: [PATCH 146/152] camerad: fix class/struct forward declaration mistake (#25842) --- system/camerad/cameras/camera_common.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index e5580a7a92..088b9f7939 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -75,7 +75,7 @@ typedef struct FrameMetadata { } FrameMetadata; struct MultiCameraState; -struct CameraState; +class CameraState; class Debayer; class CameraBuf { From 8b741261cf4538ab88f42f18837ba13d71bcc0de Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 19 Sep 2022 14:06:03 -0700 Subject: [PATCH 147/152] loggerd: add params test cases (#25843) --- selfdrive/loggerd/tests/test_loggerd.py | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/selfdrive/loggerd/tests/test_loggerd.py b/selfdrive/loggerd/tests/test_loggerd.py index b0907c54af..a2138b0aa6 100755 --- a/selfdrive/loggerd/tests/test_loggerd.py +++ b/selfdrive/loggerd/tests/test_loggerd.py @@ -83,8 +83,10 @@ class TestLoggerd(unittest.TestCase): ("GitRemote", "gitRemote", "remote"), ] params = Params() + params.clear_all() for k, _, v in fake_params: params.put(k, v) + params.put("LaikadEphemeris", "abc") lr = list(LogReader(str(self._gen_bootlog()))) initData = lr[0].initData @@ -99,8 +101,14 @@ class TestLoggerd(unittest.TestCase): with open("/proc/version") as f: self.assertEqual(initData.kernelVersion, f.read()) - for _, k, v in fake_params: - self.assertEqual(getattr(initData, k), v) + # check params + logged_params = {entry.key: entry.value for entry in initData.params.entries} + expected_params = set(k for k, _, __ in fake_params) | {'LaikadEphemeris'} + assert set(logged_params.keys()) == expected_params, set(logged_params.keys()) ^ expected_params + assert logged_params['LaikadEphemeris'] == b'', f"DONT_LOG param value was logged: {repr(logged_params['LaikadEphemeris'])}" + for param_key, initData_key, v in fake_params: + self.assertEqual(getattr(initData, initData_key), v) + self.assertEqual(logged_params[param_key].decode(), v) def test_rotation(self): os.environ["LOGGERD_TEST"] = "1" From 7b5d8adfb1819799ec635347712a2f9a40278fa3 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 19 Sep 2022 14:14:19 -0700 Subject: [PATCH 148/152] Hyundai Elantra 2021: replace VW engine FW 5a4405495d2750ef|2022-09-11--12-37-48 --- selfdrive/car/hyundai/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 3bc2062979..ea6fca5926 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1200,7 +1200,7 @@ FW_VERSIONS = { ], (Ecu.engine, 0x7e0, None): [ b'\xf1\x82CNCWD0AMFCXCSFFA', - b'\xf1\x82CNCWD0AMFCXCSFFB', + b'\xf1\x81HM6M2_0a0_FF0', b'\xf1\x82CNCVD0AMFCXCSFFB', b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M2_0a0_G80', ], From 4fa62f146426f76c9c1c2867d9729b33ec612b59 Mon Sep 17 00:00:00 2001 From: Vivek Aithal Date: Mon, 19 Sep 2022 15:19:26 -0700 Subject: [PATCH 149/152] Live torque (#25456) * wip torqued * add basic logic * setup in manager * check sanity and publish msg * add first order filter to outputs * wire up controlsd, and update gains * rename intercept to offset * add cloudlog, live values are not updated * fix bugs, do not reset points for now * fix crashes * rename to main * fix bugs, works offline * fix float in cereal bug * add latacc filter * randomly choose points, approx for iid * add variable decay * local param to capnp instead of dict * verify works in replay * use torqued output in controlsd * use in controlsd; use points from past routes * controlsd bugfix * filter before updating gains, needs to be replaced * save all points to ensure smooth transition across routes, revert friction factor to 1.5 * add filters to prevent noisy low-speed data points; improve fit sanity * add engaged buffer * revert lat_acc thresh * use paramsd realtime process config * make latacc-to-torque generic, and overrideable * move freq to 4Hz, avoid storing in np.array, don't publish points in the message * float instead of np * remove constant while storing pts * rename slope, offset to lat_accet_factor, offset * resolve issues * use camelcase in all capnp params * use camelcase everywhere * reduce latacc threshold or sanity, add car_sane todo, save points properly * add and check tag * write param to disk at end of route * remove args * rebase op, cereal * save on exit * restore default handler * cpu usage check * add to process replay * handle reset better, reduce unnecessary computation * always publish raw values - useful for debug * regen routes * update refs * checks on cache restore * check tuning vals too * clean that up * reduce cpu usage * reduce cpu usage by 75% * cleanup * optimize further * handle reset condition better, don't put points in init, use only in corolla * bump cereal after rebasing * update refs * Update common/params.cc Co-authored-by: Adeeb Shihadeh * remove unnecessary checks * Update RELEASES.md Co-authored-by: Adeeb Shihadeh --- RELEASES.md | 2 + common/params.cc | 2 + release/files_common | 1 + selfdrive/car/interfaces.py | 1 + selfdrive/controls/controlsd.py | 8 +- selfdrive/controls/lib/latcontrol_torque.py | 2 +- selfdrive/locationd/torqued.py | 290 ++++++++++++++++++ selfdrive/manager/process_config.py | 1 + .../test/process_replay/process_replay.py | 27 +- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/test/process_replay/regen.py | 8 +- selfdrive/test/process_replay/regen_all.py | 11 +- .../test/process_replay/test_processes.py | 10 +- selfdrive/test/test_onroad.py | 1 + selfdrive/test/update_ci_routes.py | 2 +- 15 files changed, 350 insertions(+), 18 deletions(-) create mode 100755 selfdrive/locationd/torqued.py diff --git a/RELEASES.md b/RELEASES.md index 56cffeebe7..a749158cb4 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -2,6 +2,8 @@ Version 0.8.17 (2022-XX-XX) ======================== * New driving model * Internal feature space accuracy increased tenfold during training, this makes the model dramatically more accurate. +* torqued + * Learn torque parameters live for each car as opposed to using platform average values, which improves lateral control Version 0.8.16 (2022-08-26) ======================== diff --git a/common/params.cc b/common/params.cc index a64c2f133b..63208879b2 100644 --- a/common/params.cc +++ b/common/params.cc @@ -144,6 +144,8 @@ std::unordered_map keys = { {"LastUpdateException", CLEAR_ON_MANAGER_START}, {"LastUpdateTime", PERSISTENT}, {"LiveParameters", PERSISTENT}, + {"LiveTorqueCarParams", PERSISTENT}, + {"LiveTorqueParameters", PERSISTENT | DONT_LOG}, {"NavDestination", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF}, {"NavSettingTime24h", PERSISTENT}, {"NavSettingLeftSide", PERSISTENT}, diff --git a/release/files_common b/release/files_common index be0a4f0f03..fa4fa997c4 100644 --- a/release/files_common +++ b/release/files_common @@ -240,6 +240,7 @@ selfdrive/locationd/models/live_kf.cc selfdrive/locationd/models/constants.py selfdrive/locationd/models/gnss_helpers.py +selfdrive/locationd/torqued.py selfdrive/locationd/calibrationd.py system/logcatd/.gitignore diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 87720f8754..a789fc6cad 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -167,6 +167,7 @@ class CarInterfaceBase(ABC): tune.torque.friction = params['FRICTION'] tune.torque.latAccelFactor = params['LAT_ACCEL_FACTOR'] tune.torque.latAccelOffset = 0.0 + tune.torque.steeringAngleDeadzoneDeg = steering_angle_deadzone_deg @abstractmethod def _update(self, c: car.CarControl) -> car.CarState: diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 3087535291..8b41e305f1 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -104,7 +104,7 @@ class Controls: ignore += ['roadCameraState'] self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', 'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman', - 'managerState', 'liveParameters', 'radarState'] + self.camera_packets + joystick_packet, + 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters'] + self.camera_packets + joystick_packet, ignore_alive=ignore, ignore_avg_freq=['radarState', 'longitudinalPlan']) # set alternative experiences from parameters @@ -578,6 +578,12 @@ class Controls: sr = max(params.steerRatio, 0.1) self.VM.update_params(x, sr) + # Update Torque Params + if self.CP.lateralTuning.which() == 'torque': + torque_params = self.sm['liveTorqueParameters'] + if self.sm.all_checks(['liveTorqueParameters']) and torque_params.useParams: + self.LaC.update_live_torque_params(torque_params.latAccelFactorFiltered, torque_params.latAccelOffsetFiltered, torque_params.frictionCoefficientFiltered) + lat_plan = self.sm['lateralPlan'] long_plan = self.sm['longitudinalPlan'] diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index f65a58275b..fa1bb480f1 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -51,7 +51,7 @@ class LatControlTorque(LatControl): desired_lateral_accel = desired_curvature * CS.vEgo ** 2 # desired rate is the desired rate of change in the setpoint, not the absolute desired curvature - #desired_lateral_jerk = desired_curvature_rate * CS.vEgo ** 2 + # desired_lateral_jerk = desired_curvature_rate * CS.vEgo ** 2 actual_lateral_accel = actual_curvature * CS.vEgo ** 2 lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2 diff --git a/selfdrive/locationd/torqued.py b/selfdrive/locationd/torqued.py new file mode 100755 index 0000000000..9f07008214 --- /dev/null +++ b/selfdrive/locationd/torqued.py @@ -0,0 +1,290 @@ +#!/usr/bin/env python3 +import os +import sys +import signal +import numpy as np +from collections import deque, defaultdict + +import cereal.messaging as messaging +from cereal import car, log +from common.params import Params +from common.realtime import config_realtime_process, DT_MDL +from common.filter_simple import FirstOrderFilter +from system.swaglog import cloudlog +from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY +from selfdrive.car.toyota.values import CAR as TOYOTA + +HISTORY = 5 # secs +POINTS_PER_BUCKET = 1500 +MIN_POINTS_TOTAL = 4000 +FIT_POINTS_TOTAL = 2000 +MIN_VEL = 15 # m/s +FRICTION_FACTOR = 1.5 # ~85% of data coverage +FACTOR_SANITY = 0.3 +FRICTION_SANITY = 0.5 +STEER_MIN_THRESHOLD = 0.02 +MIN_FILTER_DECAY = 50 +MAX_FILTER_DECAY = 250 +LAT_ACC_THRESHOLD = 1 +STEER_BUCKET_BOUNDS = [(-0.5, -0.3), (-0.3, -0.2), (-0.2, -0.1), (-0.1, 0), (0, 0.1), (0.1, 0.2), (0.2, 0.3), (0.3, 0.5)] +MIN_BUCKET_POINTS = [100, 300, 500, 500, 500, 500, 300, 100] +MAX_RESETS = 5.0 +MAX_INVALID_THRESHOLD = 10 +MIN_ENGAGE_BUFFER = 2 # secs + +VERSION = 1 # bump this to invalidate old parameter caches +ALLOWED_FINGERPRINTS = [TOYOTA.COROLLA_TSS2, TOYOTA.COROLLA, TOYOTA.COROLLAH_TSS2] + + +def slope2rot(slope): + sin = np.sqrt(slope**2 / (slope**2 + 1)) + cos = np.sqrt(1 / (slope**2 + 1)) + return np.array([[cos, -sin], [sin, cos]]) + + +class npqueue: + def __init__(self, maxlen, rowsize): + self.maxlen = maxlen + self.arr = np.empty((0, rowsize)) + + def __len__(self): + return len(self.arr) + + def append(self, pt): + if len(self.arr) < self.maxlen: + self.arr = np.append(self.arr, [pt], axis=0) + else: + self.arr[:-1] = self.arr[1:] + self.arr[-1] = pt + + +class PointBuckets: + def __init__(self, x_bounds, min_points): + self.x_bounds = x_bounds + self.buckets = {bounds: npqueue(maxlen=POINTS_PER_BUCKET, rowsize=3) for bounds in x_bounds} + self.buckets_min_points = {bounds: min_point for bounds, min_point in zip(x_bounds, min_points)} + + def bucket_lengths(self): + return [len(v) for v in self.buckets.values()] + + def __len__(self): + return sum(self.bucket_lengths()) + + def is_valid(self): + return all(len(v) >= min_pts for v, min_pts in zip(self.buckets.values(), self.buckets_min_points.values())) and (self.__len__() >= MIN_POINTS_TOTAL) + + def add_point(self, x, y): + for bound_min, bound_max in self.x_bounds: + if (x >= bound_min) and (x < bound_max): + self.buckets[(bound_min, bound_max)].append([x, 1.0, y]) + break + + def get_points(self, num_points=None): + points = np.concatenate([x.arr for x in self.buckets.values() if len(x) > 0]) + if num_points is None: + return points + return points[np.random.choice(np.arange(len(points)), min(len(points), num_points), replace=False)] + + def load_points(self, points): + for x, y in points: + self.add_point(x, y) + + +class TorqueEstimator: + def __init__(self, CP): + self.hist_len = int(HISTORY / DT_MDL) + self.lag = CP.steerActuatorDelay + .2 # from controlsd + + self.offline_friction = 0.0 + self.offline_latAccelFactor = 0.0 + self.resets = 0.0 + self.use_params = CP.carFingerprint in ALLOWED_FINGERPRINTS + + if CP.lateralTuning.which() == 'torque': + self.offline_friction = CP.lateralTuning.torque.friction + self.offline_latAccelFactor = CP.lateralTuning.torque.latAccelFactor + + self.reset() + + initial_params = { + 'latAccelFactor': self.offline_latAccelFactor, + 'latAccelOffset': 0.0, + 'frictionCoefficient': self.offline_friction, + 'points': [] + } + self.decay = MIN_FILTER_DECAY + self.min_lataccel_factor = (1.0 - FACTOR_SANITY) * self.offline_latAccelFactor + self.max_lataccel_factor = (1.0 + FACTOR_SANITY) * self.offline_latAccelFactor + self.min_friction = (1.0 - FRICTION_SANITY) * self.offline_friction + self.max_friction = (1.0 + FRICTION_SANITY) * self.offline_friction + + # try to restore cached params + params = Params() + params_cache = params.get("LiveTorqueCarParams") + torque_cache = params.get("LiveTorqueParameters") + if params_cache is not None and torque_cache is not None: + try: + cache_ltp = log.Event.from_bytes(torque_cache).liveTorqueParameters + cache_CP = car.CarParams.from_bytes(params_cache) + if self.get_restore_key(cache_CP, cache_ltp.version) == self.get_restore_key(CP, VERSION): + initial_params = { + 'latAccelFactor': cache_ltp.latAccelFactorFiltered, + 'latAccelOffset': cache_ltp.latAccelOffsetFiltered, + 'frictionCoefficient': cache_ltp.frictionCoefficientFiltered, + 'points': cache_ltp.points + } + self.decay = cache_ltp.decay + self.filtered_points.load_points(initial_params['points']) + cloudlog.info("restored torque params from cache") + except Exception: + cloudlog.exception("failed to restore cached torque params") + params.remove("LiveTorqueCarParams") + params.remove("LiveTorqueParameters") + + self.filtered_params = {} + for param in initial_params: + self.filtered_params[param] = FirstOrderFilter(initial_params[param], self.decay, DT_MDL) + + def get_restore_key(self, CP, version): + a, b = None, None + if CP.lateralTuning.which() == 'torque': + a = CP.lateralTuning.torque.friction + b = CP.lateralTuning.torque.latAccelFactor + return (CP.carFingerprint, CP.lateralTuning.which(), a, b, version) + + def reset(self): + self.resets += 1.0 + self.invalid_values_tracker = 0.0 + self.decay = MIN_FILTER_DECAY + self.raw_points = defaultdict(lambda: deque(maxlen=self.hist_len)) + self.filtered_points = PointBuckets(x_bounds=STEER_BUCKET_BOUNDS, min_points=MIN_BUCKET_POINTS) + + def estimate_params(self): + points = self.filtered_points.get_points(FIT_POINTS_TOTAL) + # total least square solution as both x and y are noisy observations + # this is empirically the slope of the hysteresis parallelogram as opposed to the line through the diagonals + try: + _, _, v = np.linalg.svd(points, full_matrices=False) + slope, offset = -v.T[0:2, 2] / v.T[2, 2] + _, spread = np.matmul(points[:, [0, 2]], slope2rot(slope)).T + friction_coeff = np.std(spread) * FRICTION_FACTOR + except np.linalg.LinAlgError as e: + cloudlog.exception(f"Error computing live torque params: {e}") + slope = offset = friction_coeff = np.nan + return slope, offset, friction_coeff + + def update_params(self, params): + self.decay = min(self.decay + DT_MDL, MAX_FILTER_DECAY) + for param, value in params.items(): + self.filtered_params[param].update(value) + self.filtered_params[param].update_alpha(self.decay) + + def is_sane(self, latAccelFactor, latAccelOffset, friction): + if any([val is None or np.isnan(val) for val in [latAccelFactor, latAccelOffset, friction]]): + return False + return (self.max_friction >= friction >= self.min_friction) and\ + (self.max_lataccel_factor >= latAccelFactor >= self.min_lataccel_factor) + + def handle_log(self, t, which, msg): + if which == "carControl": + self.raw_points["carControl_t"].append(t + self.lag) + self.raw_points["steer_torque"].append(-msg.actuatorsOutput.steer) + self.raw_points["active"].append(msg.latActive) + elif which == "carState": + self.raw_points["carState_t"].append(t + self.lag) + self.raw_points["vego"].append(msg.vEgo) + self.raw_points["steer_override"].append(msg.steeringPressed) + elif which == "liveLocationKalman": + if len(self.raw_points['steer_torque']) == self.hist_len: + yaw_rate = msg.angularVelocityCalibrated.value[2] + roll = msg.orientationNED.value[0] + active = np.interp(np.arange(t - MIN_ENGAGE_BUFFER, t, DT_MDL), self.raw_points['carControl_t'], self.raw_points['active']).astype(bool) + steer_override = np.interp(np.arange(t - MIN_ENGAGE_BUFFER, t, DT_MDL), self.raw_points['carState_t'], self.raw_points['steer_override']).astype(bool) + vego = np.interp(t, self.raw_points['carState_t'], self.raw_points['vego']) + steer = np.interp(t, self.raw_points['carControl_t'], self.raw_points['steer_torque']) + lateral_acc = (vego * yaw_rate) - (np.sin(roll) * ACCELERATION_DUE_TO_GRAVITY) + if all(active) and (not any(steer_override)) and (vego > MIN_VEL) and (abs(steer) > STEER_MIN_THRESHOLD) and (abs(lateral_acc) <= LAT_ACC_THRESHOLD): + self.filtered_points.add_point(float(steer), float(lateral_acc)) + + def get_msg(self, valid=True, with_points=False): + msg = messaging.new_message('liveTorqueParameters') + msg.valid = valid + liveTorqueParameters = msg.liveTorqueParameters + liveTorqueParameters.version = VERSION + liveTorqueParameters.useParams = self.use_params + + if self.filtered_points.is_valid(): + latAccelFactor, latAccelOffset, friction_coeff = self.estimate_params() + liveTorqueParameters.latAccelFactorRaw = float(latAccelFactor) + liveTorqueParameters.latAccelOffsetRaw = float(latAccelOffset) + liveTorqueParameters.frictionCoefficientRaw = float(friction_coeff) + + if self.is_sane(latAccelFactor, latAccelOffset, friction_coeff): + liveTorqueParameters.liveValid = True + self.update_params({'latAccelFactor': latAccelFactor, 'latAccelOffset': latAccelOffset, 'frictionCoefficient': friction_coeff}) + self.invalid_values_tracker = max(0.0, self.invalid_values_tracker - 0.5) + else: + cloudlog.exception("live torque params are numerically unstable") + liveTorqueParameters.liveValid = False + self.invalid_values_tracker += 1.0 + # Reset when ~10 invalid over 5 secs + if self.invalid_values_tracker > MAX_INVALID_THRESHOLD: + # Do not reset the filter as it may cause a drastic jump, just reset points + self.reset() + else: + liveTorqueParameters.liveValid = False + + if with_points: + liveTorqueParameters.points = self.filtered_points.get_points()[:, [0, 2]].tolist() + + liveTorqueParameters.latAccelFactorFiltered = float(self.filtered_params['latAccelFactor'].x) + liveTorqueParameters.latAccelOffsetFiltered = float(self.filtered_params['latAccelOffset'].x) + liveTorqueParameters.frictionCoefficientFiltered = float(self.filtered_params['frictionCoefficient'].x) + liveTorqueParameters.totalBucketPoints = len(self.filtered_points) + liveTorqueParameters.decay = self.decay + liveTorqueParameters.maxResets = self.resets + return msg + + +def main(sm=None, pm=None): + config_realtime_process([0, 1, 2, 3], 5) + + if sm is None: + sm = messaging.SubMaster(['carControl', 'carState', 'liveLocationKalman'], poll=['liveLocationKalman']) + + if pm is None: + pm = messaging.PubMaster(['liveTorqueParameters']) + + params = Params() + CP = car.CarParams.from_bytes(params.get("CarParams", block=True)) + estimator = TorqueEstimator(CP) + + def cache_params(sig, frame): + signal.signal(sig, signal.SIG_DFL) + cloudlog.warning("caching torque params") + + params = Params() + params.put("LiveTorqueCarParams", CP.as_builder().to_bytes()) + + msg = estimator.get_msg(with_points=True) + params.put("LiveTorqueParameters", msg.to_bytes()) + + sys.exit(0) + if "REPLAY" not in os.environ: + signal.signal(signal.SIGINT, cache_params) + + while True: + sm.update() + if sm.all_checks(): + for which in sm.updated.keys(): + if sm.updated[which]: + t = sm.logMonoTime[which] * 1e-9 + estimator.handle_log(t, which, sm[which]) + + # 4Hz driven by liveLocationKalman + if sm.frame % 5 == 0: + pm.send('liveTorqueParameters', estimator.get_msg(valid=sm.all_checks())) + + +if __name__ == "__main__": + main() diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index 7702b96eaa..06efdbb960 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -38,6 +38,7 @@ procs = [ NativeProcess("locationd", "selfdrive/locationd", ["./locationd"]), NativeProcess("boardd", "selfdrive/boardd", ["./boardd"], enabled=False), PythonProcess("calibrationd", "selfdrive.locationd.calibrationd"), + PythonProcess("torqued", "selfdrive.locationd.torqued"), PythonProcess("controlsd", "selfdrive.controls.controlsd"), PythonProcess("deleter", "selfdrive.loggerd.deleter", offroad=True), PythonProcess("dmonitoringd", "selfdrive.monitoring.dmonitoringd", enabled=(not PC or WEBCAM), callback=driverview), diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index b4e3f62656..038b0cf468 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -229,6 +229,15 @@ def calibration_rcv_callback(msg, CP, cfg, fsm): return recv_socks, fsm.frame == 0 or msg.which() == 'cameraOdometry' +def torqued_rcv_callback(msg, CP, cfg, fsm): + # should_recv always true to increment frame + recv_socks = [] + frame = fsm.frame + 1 # incrementing hasn't happened yet in SubMaster + if msg.which() == 'liveLocationKalman' and (frame % 5) == 0: + recv_socks = ["liveTorqueParameters"] + return recv_socks, fsm.frame == 0 or msg.which() == 'liveLocationKalman' + + def ublox_rcv_callback(msg): msg_class, msg_id = msg.ubloxRaw[2:4] if (msg_class, msg_id) in {(1, 7 * 16)}: @@ -251,8 +260,10 @@ CONFIGS = [ proc_name="controlsd", pub_sub={ "can": ["controlsState", "carState", "carControl", "sendcan", "carEvents", "carParams"], - "deviceState": [], "pandaStates": [], "peripheralState": [], "liveCalibration": [], "driverMonitoringState": [], "longitudinalPlan": [], "lateralPlan": [], "liveLocationKalman": [], "liveParameters": [], "radarState": [], - "modelV2": [], "driverCameraState": [], "roadCameraState": [], "wideRoadCameraState": [], "managerState": [], "testJoystick": [], + "deviceState": [], "pandaStates": [], "peripheralState": [], "liveCalibration": [], "driverMonitoringState": [], + "longitudinalPlan": [], "lateralPlan": [], "liveLocationKalman": [], "liveParameters": [], "radarState": [], + "modelV2": [], "driverCameraState": [], "roadCameraState": [], "wideRoadCameraState": [], "managerState": [], + "testJoystick": [], "liveTorqueParameters": [], }, ignore=["logMonoTime", "valid", "controlsState.startMonoTime", "controlsState.cumLagMs"], init_callback=fingerprint, @@ -374,6 +385,18 @@ CONFIGS = [ tolerance=NUMPY_TOLERANCE, fake_pubsubmaster=True, ), + ProcessConfig( + proc_name="torqued", + pub_sub={ + "liveLocationKalman": ["liveTorqueParameters"], + "carState": [], "controlsState": [], + }, + ignore=["logMonoTime"], + init_callback=get_car_params, + should_recv_callback=torqued_rcv_callback, + tolerance=NUMPY_TOLERANCE, + fake_pubsubmaster=True, + ), ] diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index afde6ec422..7b24c04c98 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -d14f1a61a4bfde810128a6bb703aa543268fa4a9 \ No newline at end of file +deb07ca8c5dc021e57e81307764a84aa3d7aef32 \ No newline at end of file diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py index 4e1cbfd30d..d565e36390 100755 --- a/selfdrive/test/process_replay/regen.py +++ b/selfdrive/test/process_replay/regen.py @@ -269,11 +269,11 @@ def regen_segment(lr, frs=None, outdir=FAKEDATA, disable_tqdm=False): return seg_path -def regen_and_save(route, sidx, upload=False, use_route_meta=False, outdir=FAKEDATA, disable_tqdm=False): +def regen_and_save(route, sidx, upload=False, use_route_meta=True, outdir=FAKEDATA, disable_tqdm=False): if use_route_meta: - r = Route(args.route) - lr = LogReader(r.log_paths()[args.seg]) - fr = FrameReader(r.camera_paths()[args.seg]) + r = Route(route) + lr = LogReader(r.log_paths()[sidx]) + fr = FrameReader(r.camera_paths()[sidx]) else: lr = LogReader(f"cd:/{route.replace('|', '/')}/{sidx}/rlog.bz2") fr = FrameReader(f"cd:/{route.replace('|', '/')}/{sidx}/fcamera.hevc") diff --git a/selfdrive/test/process_replay/regen_all.py b/selfdrive/test/process_replay/regen_all.py index f10d7ea03a..f69d07eb69 100755 --- a/selfdrive/test/process_replay/regen_all.py +++ b/selfdrive/test/process_replay/regen_all.py @@ -3,11 +3,12 @@ import argparse import concurrent.futures import os import random +import traceback from tqdm import tqdm from selfdrive.test.process_replay.helpers import OpenpilotPrefix from selfdrive.test.process_replay.regen import regen_and_save -from selfdrive.test.process_replay.test_processes import FAKEDATA, original_segments as segments +from selfdrive.test.process_replay.test_processes import FAKEDATA, source_segments as segments from tools.lib.route import SegmentName @@ -16,11 +17,15 @@ def regen_job(segment, upload, disable_tqdm): sn = SegmentName(segment[1]) fake_dongle_id = 'regen' + ''.join(random.choice('0123456789ABCDEF') for _ in range(11)) try: - relr = regen_and_save(sn.route_name.canonical_name, sn.segment_num, upload=upload, use_route_meta=False, outdir=os.path.join(FAKEDATA, fake_dongle_id), disable_tqdm=disable_tqdm) + relr = regen_and_save(sn.route_name.canonical_name, sn.segment_num, upload=upload, use_route_meta=False, + outdir=os.path.join(FAKEDATA, fake_dongle_id), disable_tqdm=disable_tqdm) relr = '|'.join(relr.split('/')[-2:]) return f' ("{segment[0]}", "{relr}"), ' except Exception as e: - return f" {segment} failed: {str(e)}" + err = f" {segment} failed: {str(e)}" + err += traceback.format_exc() + err += "\n\n" + return err if __name__ == "__main__": diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 0f118971c6..ee892a2fd9 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -15,22 +15,22 @@ from system.version import get_commit from tools.lib.filereader import FileReader from tools.lib.logreader import LogReader -original_segments = [ +source_segments = [ ("BODY", "937ccb7243511b65|2022-05-24--16-03-09--1"), # COMMA.BODY ("HYUNDAI", "02c45f73a2e5c6e9|2021-01-01--19-08-22--1"), # HYUNDAI.SONATA - ("HYUNDAI", "d824e27e8c60172c|2022-08-19--17-58-07--2"), # HYUNDAI.KIA_EV6 + ("HYUNDAI", "d824e27e8c60172c|2022-09-13--11-26-50--2"), # HYUNDAI.KIA_EV6 ("TOYOTA", "0982d79ebb0de295|2021-01-04--17-13-21--13"), # TOYOTA.PRIUS (INDI) ("TOYOTA2", "0982d79ebb0de295|2021-01-03--20-03-36--6"), # TOYOTA.RAV4 (LQR) ("TOYOTA3", "f7d7e3538cda1a2a|2021-08-16--08-55-34--6"), # TOYOTA.COROLLA_TSS2 ("HONDA", "eb140f119469d9ab|2021-06-12--10-46-24--27"), # HONDA.CIVIC (NIDEC) ("HONDA2", "7d2244f34d1bbcda|2021-06-25--12-25-37--26"), # HONDA.ACCORD (BOSCH) ("CHRYSLER", "4deb27de11bee626|2021-02-20--11-28-55--8"), # CHRYSLER.PACIFICA - ("RAM", "2f4452b03ccb98f0|2022-07-07--08-01-56--3"), # CHRYSLER.RAM_1500 - ("SUBARU", "4d70bc5e608678be|2021-01-15--17-02-04--5"), # SUBARU.IMPREZA + ("RAM", "2f4452b03ccb98f0|2022-09-07--13-55-08--10"), # CHRYSLER.RAM_1500 + ("SUBARU", "341dccd5359e3c97|2022-09-12--10-35-33--3"), # SUBARU.OUTBACK ("GM", "0c58b6a25109da2b|2021-02-23--16-35-50--11"), # GM.VOLT ("NISSAN", "35336926920f3571|2021-02-12--18-38-48--46"), # NISSAN.XTRAIL ("VOLKSWAGEN", "de9592456ad7d144|2021-06-29--11-00-15--6"), # VOLKSWAGEN.GOLF - ("MAZDA", "bd6a637565e91581|2021-10-30--15-14-53--2"), # MAZDA.CX9_2021 + ("MAZDA", "bd6a637565e91581|2021-10-30--15-14-53--4"), # MAZDA.CX9_2021 # Enable when port is tested and dashcamOnly is no longer set #("TESLA", "bb50caf5f0945ab1|2021-06-19--17-20-18--3"), # TESLA.AP2_MODELS diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 55e1ef161a..b29ca5d35b 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -36,6 +36,7 @@ PROCS = { "./_dmonitoringmodeld": 5.0, "selfdrive.thermald.thermald": 3.87, "selfdrive.locationd.calibrationd": 2.0, + "selfdrive.locationd.torqued": 5.0, "./_soundd": 1.0, "selfdrive.monitoring.dmonitoringd": 4.0, "./proclogd": 1.54, diff --git a/selfdrive/test/update_ci_routes.py b/selfdrive/test/update_ci_routes.py index 99a63b8dfd..a1e8c35f6b 100755 --- a/selfdrive/test/update_ci_routes.py +++ b/selfdrive/test/update_ci_routes.py @@ -4,7 +4,7 @@ import subprocess from azure.storage.blob import BlockBlobService # pylint: disable=import-error from selfdrive.car.tests.routes import routes as test_car_models_routes -from selfdrive.test.process_replay.test_processes import original_segments as replay_segments +from selfdrive.test.process_replay.test_processes import source_segments as replay_segments from xx.chffr.lib import azureutil # pylint: disable=import-error from xx.chffr.lib.storage import _DATA_ACCOUNT_PRODUCTION, _DATA_ACCOUNT_CI, _DATA_BUCKET_PRODUCTION # pylint: disable=import-error From 805a54ad0f24b64bb1253f5aeed6e5b99c3f842e Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 19 Sep 2022 17:41:37 -0700 Subject: [PATCH 150/152] updated: commits are always strings --- selfdrive/updated.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 79b759a906..fc51ae799d 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -240,7 +240,7 @@ def handle_agnos_update() -> None: class Updater: def __init__(self): self.params = Params() - self.branches = defaultdict(lambda: None) + self.branches = defaultdict(lambda: '') @property def target_branch(self) -> str: From de1882429a20e4d7fd37cdcaf67e54b3649a7fde Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 19 Sep 2022 20:40:03 -0700 Subject: [PATCH 151/152] update release notes --- RELEASES.md | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index a749158cb4..5ef2acdd44 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -2,8 +2,12 @@ Version 0.8.17 (2022-XX-XX) ======================== * New driving model * Internal feature space accuracy increased tenfold during training, this makes the model dramatically more accurate. -* torqued - * Learn torque parameters live for each car as opposed to using platform average values, which improves lateral control +* Self-tuning torque lateral controller parameters + * Parameters are learned live for each car + * Enabled only on Toyota Corolla for now +* UI updates + * Matched speeds shown on car's dash + * Improved update experience Version 0.8.16 (2022-08-26) ======================== From d1c95fb0d4e87c35f5eb8b425de0c054da93a3a0 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 19 Sep 2022 20:43:12 -0700 Subject: [PATCH 152/152] add event flagging too --- RELEASES.md | 1 + 1 file changed, 1 insertion(+) diff --git a/RELEASES.md b/RELEASES.md index 5ef2acdd44..6edd900cb2 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -8,6 +8,7 @@ Version 0.8.17 (2022-XX-XX) * UI updates * Matched speeds shown on car's dash * Improved update experience + * Added button to flag events that are shown in comma connect Version 0.8.16 (2022-08-26) ========================