diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index e921cd3d0..598f2c592 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -232,6 +232,7 @@ jobs: ./selfdrive/loggerd/tests/test_logger &&\ ./system/proclogd/tests/test_proclog && \ ./tools/replay/tests/test_replay && \ + ./tools/cabana/tests/test_cabana && \ ./system/camerad/test/ae_gray_test && \ coverage xml" - name: "Upload coverage to Codecov" diff --git a/RELEASES.md b/RELEASES.md index b42425958..744168c8f 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -6,6 +6,7 @@ Version 0.8.17 (2022-XX-XX) * New end-to-end distracted trigger * Self-tuning torque lateral controller parameters * Parameters learned live for each car +* Torque controller used on all Toyota, Lexus, Hyundai, Kia, and Genesis models * UI updates * Multi-language in navigation * Matched speeds shown on car's dash diff --git a/cereal b/cereal index 38133307b..1d25fc3f2 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 38133307b2e6036e76684b39878e79212e545e06 +Subproject commit 1d25fc3f202d5ddeee97848480323e9b14f9bdfa diff --git a/docs/CARS.md b/docs/CARS.md index a03da5ca6..2df2b96e2 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. -# 209 Supported Cars +# 211 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Harness| |---|---|---|:---:|:---:|:---:|:---:|:---:|:---:| @@ -55,8 +55,10 @@ A supported vehicle is one that just works when you install a comma three. All s |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)|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)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| +|Hyundai|Elantra GT 2017-19|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Hyundai|Elantra Hybrid 2021-23|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)|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai J| +|Hyundai|i30 2019|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Hyundai|Ioniq 5 (with HDA II) 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 (without HDA II) 2022|Highway Driving Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| |Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| @@ -120,7 +122,7 @@ A supported vehicle is one that just works when you install a comma three. All s |Lexus|RX Hybrid 2017-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| |Lexus|RX Hybrid 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| |Lexus|UX Hybrid 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Mazda|CX-5 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Mazda| +|Mazda|CX-5 2022-23|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Mazda| |Mazda|CX-9 2021-22|All|Stock|0 mph|28 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Mazda| |Nissan|Altima 2019-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Nissan B| |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| diff --git a/opendbc b/opendbc index 7bd94e3ff..526e21da6 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 7bd94e3ff4a2890eb69118f0dfadb64f9d32d618 +Subproject commit 526e21da666aeeabcf2369c66903a5675fdf933b diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index 7b3140fbb..5114f8d06 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -61,10 +61,10 @@ class FordCarInfo(CarInfo): CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { CAR.ESCAPE_MK4: [ - FordCarInfo("Ford Escape 2020"), - FordCarInfo("Ford Kuga EU", "Driver Assistance Pack"), + FordCarInfo("Ford Escape 2020-21"), + FordCarInfo("Ford Kuga 2020-21", "Driver Assistance Pack"), ], - CAR.EXPLORER_MK6: FordCarInfo("Ford Explorer 2020-21"), + CAR.EXPLORER_MK6: FordCarInfo("Ford Explorer 2020-22"), CAR.FOCUS_MK4: FordCarInfo("Ford Focus EU 2019", "Driver Assistance Pack"), } @@ -87,31 +87,41 @@ FW_QUERY_CONFIG = FwQueryConfig( FW_VERSIONS = { CAR.ESCAPE_MK4: { (Ecu.eps, 0x730, None): [ + b'LX6C-14D003-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.abs, 0x760, None): [ b'LX6C-2D053-NS\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-NY\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-SA\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'LJ6T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LJ6T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x7E0, None): [ + b'LX6A-14C204-BJV\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'LX6A-14C204-ESG\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'MX6A-14C204-BEF\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.shiftByWire, 0x732, None): [ + b'LX6P-14G395-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6P-14G395-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], }, 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', + b'M1MC-14D003-AB\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', + b'L1MC-2D053-KB\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', @@ -123,10 +133,12 @@ FW_VERSIONS = { (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', + b'NB5A-14C204-HB\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', + b'L1MP-14G395-JB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], }, CAR.FOCUS_MK4: { diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index b56b3bfca..a75eb89f2 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -22,6 +22,7 @@ class CarController: self.apply_gas = 0 self.apply_brake = 0 self.frame = 0 + self.last_steer_frame = 0 self.last_button_frame = 0 self.cancel_counter = 0 @@ -46,15 +47,21 @@ class CarController: # Send CAN commands. can_sends = [] - # Steering (50Hz) + # Steering (Active: 50Hz, inactive: 10Hz) + # Attempt to sync with camera on startup at 50Hz, first few msgs are blocked + init_lka_counter = not self.sent_lka_steering_cmd and self.CP.networkLocation == NetworkLocation.fwdCamera + steer_step = self.params.INACTIVE_STEER_STEP + if CC.latActive or init_lka_counter: + steer_step = self.params.ACTIVE_STEER_STEP + # Avoid GM EPS faults when transmitting messages too close together: skip this transmit if we just received the # next Panda loopback confirmation in the current CS frame. if CS.loopback_lka_steering_cmd_updated: self.lka_steering_cmd_counter += 1 self.sent_lka_steering_cmd = True - elif (self.frame % self.params.STEER_STEP) == 0: - # Initialize ASCMLKASteeringCmd counter using the camera - if not self.sent_lka_steering_cmd and self.CP.networkLocation == NetworkLocation.fwdCamera: + elif (self.frame - self.last_steer_frame) >= steer_step: + # Initialize ASCMLKASteeringCmd counter using the camera until we get a msg on the bus + if init_lka_counter: self.lka_steering_cmd_counter = CS.camera_lka_steering_cmd_counter + 1 if CC.latActive: @@ -63,6 +70,7 @@ class CarController: else: apply_steer = 0 + self.last_steer_frame = self.frame self.apply_steer_last = apply_steer idx = self.lka_steering_cmd_counter % 4 can_sends.append(gmcan.create_steering_control(self.packer_pt, CanBus.POWERTRAIN, apply_steer, idx, CC.latActive)) diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index f8f9e7f04..85e291aaf 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -11,7 +11,8 @@ Ecu = car.CarParams.Ecu class CarControllerParams: STEER_MAX = 300 # GM limit is 3Nm. Used by carcontroller to generate LKA output - STEER_STEP = 2 # Control frames per command (50hz) + ACTIVE_STEER_STEP = 2 # Active control frames per command (50hz) + INACTIVE_STEER_STEP = 10 # Inactive control frames per command (10hz) STEER_DELTA_UP = 7 # Delta rates require review due to observed EPS weakness STEER_DELTA_DOWN = 17 STEER_DRIVER_ALLOWANCE = 50 diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 638008934..e0810e0bb 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -446,7 +446,7 @@ FW_VERSIONS = { b'78109-TED-Q510\x00\x00', b'78109-TEG-A310\x00\x00', ], - (Ecu.fwdCamera, 0x18dab0f1, None): [ + (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36161-TBA-A020\x00\x00', b'36161-TBA-A030\x00\x00', b'36161-TBA-A040\x00\x00', @@ -964,7 +964,7 @@ FW_VERSIONS = { b'77959-THR-A110\x00\x00', b'77959-THR-X010\x00\x00', ], - (Ecu.fwdCamera, 0x18dab0f1, None): [ + (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36161-THR-A020\x00\x00', b'36161-THR-A030\x00\x00', b'36161-THR-A110\x00\x00', @@ -1068,7 +1068,7 @@ FW_VERSIONS = { b'39990-TG7-A070\x00\x00', b'39990-TGS-A230\x00\x00', ], - (Ecu.fwdCamera, 0x18dab0f1, None): [ + (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36161-TG7-A310\x00\x00', b'36161-TG7-A520\x00\x00', b'36161-TG7-A630\x00\x00', @@ -1176,7 +1176,7 @@ FW_VERSIONS = { b'57114-TX5-A220\x00\x00', b'57114-TX4-A220\x00\x00', ], - (Ecu.fwdCamera, 0x18dab0f1, None): [ + (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36161-TX5-A030\x00\x00', b'36161-TX4-A030\x00\x00', ], @@ -1273,7 +1273,7 @@ FW_VERSIONS = { b'39990-T6Z-A030\x00\x00', b'39990-T6Z-A050\x00\x00', ], - (Ecu.fwdCamera, 0x18dab0f1, None): [ + (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36161-T6Z-A020\x00\x00', b'36161-T6Z-A310\x00\x00', b'36161-T6Z-A420\x00\x00', diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index e27432e23..2e4cb0d25 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -187,6 +187,9 @@ class CarState(CarStateBase): ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(50, cp.vl["BLINKERS"]["LEFT_LAMP"], cp.vl["BLINKERS"]["RIGHT_LAMP"]) + if self.CP.enableBsm: + ret.leftBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FL_INDICATOR"] != 0 + ret.rightBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FR_INDICATOR"] != 0 ret.cruiseState.available = True self.is_metric = cp.vl["CLUSTER_INFO"]["DISTANCE_UNIT"] != 1 @@ -450,6 +453,15 @@ class CarState(CarStateBase): ("DOORS_SEATBELTS", 4), ] + if CP.enableBsm: + signals += [ + ("FL_INDICATOR", "BLINDSPOTS_REAR_CORNERS"), + ("FR_INDICATOR", "BLINDSPOTS_REAR_CORNERS"), + ] + checks += [ + ("BLINDSPOTS_REAR_CORNERS", 20), + ] + if CP.flags & HyundaiFlags.CANFD_HDA2 and not CP.openpilotLongitudinalControl: signals += [ ("CRUISE_STATUS", "CRUISE_INFO"), @@ -495,7 +507,6 @@ class CarState(CarStateBase): ("ZEROS_5", "CRUISE_INFO"), ("DISTANCE_SETTING", "CRUISE_INFO"), ("SET_SPEED", "CRUISE_INFO"), - ("NEW_SIGNAL_4", "CRUISE_INFO"), ] checks = [ diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index b1fa8d9e1..6a1d741de 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -31,7 +31,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.KIA_OPTIMA_H, CAR.ELANTRA_GT_I30} + ret.dashcamOnly = candidate in {CAR.KIA_OPTIMA_H, } if candidate in CANFD_CAR: # detect HDA2 with ADAS Driving ECU @@ -45,141 +45,92 @@ class CarInterface(CarInterfaceBase): ret.steerActuatorDelay = 0.1 # Default delay ret.steerLimitTimer = 0.4 tire_stiffness_factor = 1. + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) 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 ret.wheelbase = 2.766 # Values from optimizer ret.steerRatio = 16.55 # 13.8 is spec end-to-end tire_stiffness_factor = 0.82 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[9., 22.], [9., 22.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.35], [0.05, 0.09]] elif candidate in (CAR.SONATA, CAR.SONATA_HYBRID): ret.mass = 1513. + STD_CARGO_KG ret.wheelbase = 2.84 ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable tire_stiffness_factor = 0.65 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.SONATA_LF: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 4497. * CV.LB_TO_KG ret.wheelbase = 2.804 ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.PALISADE: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 1999. + STD_CARGO_KG ret.wheelbase = 2.90 ret.steerRatio = 15.6 * 1.15 tire_stiffness_factor = 0.63 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - elif candidate in (CAR.ELANTRA, CAR.ELANTRA_GT_I30): - ret.lateralTuning.pid.kf = 0.00006 + elif candidate == CAR.ELANTRA: ret.mass = 1275. + STD_CARGO_KG ret.wheelbase = 2.7 ret.steerRatio = 15.4 # 14 is Stock | Settled Params Learner values are steerRatio: 15.401566348670535 tire_stiffness_factor = 0.385 # stiffnessFactor settled on 1.0081302973865127 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.ELANTRA_2021: ret.mass = (2800. * CV.LB_TO_KG) + STD_CARGO_KG ret.wheelbase = 2.72 ret.steerRatio = 12.9 tire_stiffness_factor = 0.65 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.ELANTRA_HEV_2021: ret.mass = (3017. * CV.LB_TO_KG) + STD_CARGO_KG ret.wheelbase = 2.72 ret.steerRatio = 12.9 tire_stiffness_factor = 0.65 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.HYUNDAI_GENESIS: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 2060. + STD_CARGO_KG ret.wheelbase = 3.01 ret.steerRatio = 16.5 - ret.lateralTuning.init('indi') - ret.lateralTuning.indi.innerLoopGainBP = [0.] - ret.lateralTuning.indi.innerLoopGainV = [3.5] - ret.lateralTuning.indi.outerLoopGainBP = [0.] - ret.lateralTuning.indi.outerLoopGainV = [2.0] - ret.lateralTuning.indi.timeConstantBP = [0.] - ret.lateralTuning.indi.timeConstantV = [1.4] - ret.lateralTuning.indi.actuatorEffectivenessBP = [0.] - ret.lateralTuning.indi.actuatorEffectivenessV = [2.3] ret.minSteerSpeed = 60 * CV.KPH_TO_MS elif candidate in (CAR.KONA, CAR.KONA_EV, CAR.KONA_HEV, CAR.KONA_EV_2022): ret.mass = {CAR.KONA_EV: 1685., CAR.KONA_HEV: 1425., CAR.KONA_EV_2022: 1743.}.get(candidate, 1275.) + STD_CARGO_KG ret.wheelbase = 2.6 ret.steerRatio = 13.42 # Spec tire_stiffness_factor = 0.385 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate in (CAR.IONIQ, CAR.IONIQ_EV_LTD, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.IONIQ_HEV_2022): - ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1490. + STD_CARGO_KG # weight per hyundai site https://www.hyundaiusa.com/ioniq-electric/specifications.aspx ret.wheelbase = 2.7 ret.steerRatio = 13.73 # Spec tire_stiffness_factor = 0.385 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] if candidate not in (CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.IONIQ_HEV_2022): ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.IONIQ_PHEV_2019: ret.mass = 1550. + STD_CARGO_KG # weight per hyundai site https://www.hyundaiusa.com/us/en/vehicles/2019-ioniq-plug-in-hybrid/compare-specs ret.wheelbase = 2.7 ret.steerRatio = 13.73 - ret.lateralTuning.init('indi') - ret.lateralTuning.indi.innerLoopGainBP = [0.] - ret.lateralTuning.indi.innerLoopGainV = [2.5] - ret.lateralTuning.indi.outerLoopGainBP = [0.] - ret.lateralTuning.indi.outerLoopGainV = [3.5] - ret.lateralTuning.indi.timeConstantBP = [0.] - ret.lateralTuning.indi.timeConstantV = [1.4] - ret.lateralTuning.indi.actuatorEffectivenessBP = [0.] - ret.lateralTuning.indi.actuatorEffectivenessV = [1.8] ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.VELOSTER: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3558. * CV.LB_TO_KG ret.wheelbase = 2.80 ret.steerRatio = 13.75 * 1.15 tire_stiffness_factor = 0.5 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.TUCSON: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3520. * CV.LB_TO_KG ret.wheelbase = 2.67 ret.steerRatio = 14.00 * 1.15 tire_stiffness_factor = 0.385 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.TUCSON_HYBRID_4TH_GEN: ret.mass = 1680. + STD_CARGO_KG # average of all 3 trims ret.wheelbase = 2.756 ret.steerRatio = 16. tire_stiffness_factor = 0.385 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) # Kia elif candidate == CAR.KIA_SORENTO: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 1985. + STD_CARGO_KG ret.wheelbase = 2.78 ret.steerRatio = 14.4 * 1.1 # 10% higher at the center seems reasonable - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate in (CAR.KIA_NIRO_EV, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021): - ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1737. + STD_CARGO_KG ret.wheelbase = 2.7 ret.steerRatio = 13.9 if CAR.KIA_NIRO_HEV_2021 else 13.73 # Spec tire_stiffness_factor = 0.385 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] if candidate == CAR.KIA_NIRO_PHEV: ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.KIA_SELTOS: @@ -187,15 +138,6 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.63 ret.steerRatio = 14.56 tire_stiffness_factor = 1 - ret.lateralTuning.init('indi') - ret.lateralTuning.indi.innerLoopGainBP = [0.] - ret.lateralTuning.indi.innerLoopGainV = [4.] - ret.lateralTuning.indi.outerLoopGainBP = [0.] - ret.lateralTuning.indi.outerLoopGainV = [3.] - ret.lateralTuning.indi.timeConstantBP = [0.] - ret.lateralTuning.indi.timeConstantV = [1.4] - ret.lateralTuning.indi.actuatorEffectivenessBP = [0.] - ret.lateralTuning.indi.actuatorEffectivenessV = [1.8] elif candidate in (CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.KIA_OPTIMA_H): ret.mass = 3558. * CV.LB_TO_KG ret.wheelbase = 2.80 @@ -203,92 +145,58 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.5 if candidate == CAR.KIA_OPTIMA_G4: ret.minSteerSpeed = 32 * CV.MPH_TO_MS - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.KIA_STINGER: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 1825. + STD_CARGO_KG ret.wheelbase = 2.78 ret.steerRatio = 14.4 * 1.15 # 15% higher at the center seems reasonable - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.KIA_FORTE: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3558. * CV.LB_TO_KG ret.wheelbase = 2.80 ret.steerRatio = 13.75 tire_stiffness_factor = 0.5 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.KIA_CEED: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 1450. + STD_CARGO_KG ret.wheelbase = 2.65 ret.steerRatio = 13.75 tire_stiffness_factor = 0.5 - ret.lateralTuning.pid.kf = 0.00005 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.KIA_K5_2021: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3228. * CV.LB_TO_KG ret.wheelbase = 2.85 ret.steerRatio = 13.27 # 2021 Kia K5 Steering Ratio (all trims) tire_stiffness_factor = 0.5 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.KIA_EV6: ret.mass = 2055 + STD_CARGO_KG ret.wheelbase = 2.9 ret.steerRatio = 16. tire_stiffness_factor = 0.65 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.IONIQ_5: ret.mass = 2012 + STD_CARGO_KG ret.wheelbase = 3.0 ret.steerRatio = 16. tire_stiffness_factor = 0.65 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.KIA_SPORTAGE_HYBRID_5TH_GEN: ret.mass = 1767. + STD_CARGO_KG # SX Prestige trim support only ret.wheelbase = 2.756 ret.steerRatio = 13.6 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) # Genesis elif candidate == CAR.GENESIS_G70: - ret.lateralTuning.init('indi') - ret.lateralTuning.indi.innerLoopGainBP = [0.] - ret.lateralTuning.indi.innerLoopGainV = [2.5] - ret.lateralTuning.indi.outerLoopGainBP = [0.] - ret.lateralTuning.indi.outerLoopGainV = [3.5] - ret.lateralTuning.indi.timeConstantBP = [0.] - ret.lateralTuning.indi.timeConstantV = [1.4] - ret.lateralTuning.indi.actuatorEffectivenessBP = [0.] - ret.lateralTuning.indi.actuatorEffectivenessV = [1.8] ret.steerActuatorDelay = 0.1 ret.mass = 1640.0 + STD_CARGO_KG ret.wheelbase = 2.84 ret.steerRatio = 13.56 elif candidate == CAR.GENESIS_G70_2020: - ret.lateralTuning.pid.kf = 0. - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.112], [0.004]] ret.mass = 3673.0 * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.83 ret.steerRatio = 12.9 elif candidate == CAR.GENESIS_G80: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 2060. + STD_CARGO_KG ret.wheelbase = 3.01 ret.steerRatio = 16.5 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.01]] elif candidate == CAR.GENESIS_G90: ret.mass = 2200 ret.wheelbase = 3.15 ret.steerRatio = 12.069 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.01]] # *** longitudinal control *** if candidate in CANFD_CAR: @@ -311,6 +219,13 @@ class CarInterface(CarInterfaceBase): ret.vEgoStarting = 0.1 ret.startAccel = 2.0 + # *** feature detection *** + if candidate in CANFD_CAR: + bus = 5 if ret.flags & HyundaiFlags.CANFD_HDA2 else 4 + ret.enableBsm = 0x1e5 in fingerprint[bus] + else: + ret.enableBsm = 0x58b in fingerprint[0] + # *** panda safety config *** if candidate in CANFD_CAR: ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.noOutput), @@ -321,8 +236,6 @@ class CarInterface(CarInterfaceBase): if ret.flags & HyundaiFlags.CANFD_ALT_BUTTONS: ret.safetyConfigs[1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_ALT_BUTTONS else: - ret.enableBsm = 0x58b in fingerprint[0] - if candidate in LEGACY_SAFETY_MODE_CAR: # these cars require a special panda safety mode due to missing counters and checksums in the messages ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hyundaiLegacy)] diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 1eed03923..98cb72293 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -34,7 +34,7 @@ class CarControllerParams: # 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. - elif CP.carFingerprint in (CAR.GENESIS_G80, CAR.GENESIS_G90, CAR.ELANTRA, CAR.HYUNDAI_GENESIS, CAR.ELANTRA_GT_I30, CAR.IONIQ, + elif CP.carFingerprint in (CAR.GENESIS_G80, CAR.GENESIS_G90, CAR.ELANTRA, CAR.HYUNDAI_GENESIS, CAR.IONIQ, CAR.IONIQ_EV_LTD, CAR.SANTA_FE_PHEV_2022, CAR.SONATA_LF, CAR.KIA_FORTE, CAR.KIA_NIRO_PHEV, CAR.KIA_OPTIMA_H, CAR.KIA_SORENTO): self.STEER_MAX = 255 @@ -54,7 +54,6 @@ class CAR: ELANTRA = "HYUNDAI ELANTRA 2017" ELANTRA_2021 = "HYUNDAI ELANTRA 2021" ELANTRA_HEV_2021 = "HYUNDAI ELANTRA HYBRID 2021" - ELANTRA_GT_I30 = "HYUNDAI I30 N LINE 2019 & GT 2018 DCT" HYUNDAI_GENESIS = "HYUNDAI GENESIS 2015-2016" IONIQ = "HYUNDAI IONIQ HYBRID 2017-2019" IONIQ_HEV_2022 = "HYUNDAI IONIQ HYBRID 2020-2022" @@ -108,13 +107,13 @@ class HyundaiCarInfo(CarInfo): CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { - CAR.ELANTRA: HyundaiCarInfo("Hyundai Elantra 2017-19", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_b), - CAR.ELANTRA_2021: HyundaiCarInfo("Hyundai Elantra 2021-22", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k), - CAR.ELANTRA_HEV_2021: HyundaiCarInfo("Hyundai Elantra Hybrid 2021-23", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k), - CAR.ELANTRA_GT_I30: [ + CAR.ELANTRA: [ + HyundaiCarInfo("Hyundai Elantra 2017-19", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_b), HyundaiCarInfo("Hyundai Elantra GT 2017-19", harness=Harness.hyundai_e), HyundaiCarInfo("Hyundai i30 2019", harness=Harness.hyundai_e), ], + CAR.ELANTRA_2021: HyundaiCarInfo("Hyundai Elantra 2021-22", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k), + CAR.ELANTRA_HEV_2021: HyundaiCarInfo("Hyundai Elantra Hybrid 2021-23", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k), CAR.HYUNDAI_GENESIS: HyundaiCarInfo("Hyundai Genesis 2015-16", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_j), # TODO: check 2015 packages CAR.IONIQ: HyundaiCarInfo("Hyundai Ioniq Hybrid 2017-19", harness=Harness.hyundai_c), CAR.IONIQ_HEV_2022: HyundaiCarInfo("Hyundai Ioniq Hybrid 2020-22", harness=Harness.hyundai_h), # TODO: confirm 2020-21 harness @@ -199,15 +198,6 @@ FINGERPRINTS = { CAR.ELANTRA: [{ 66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 897: 8, 832: 8, 899: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1170: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1314: 8, 1322: 8, 1345: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 2001: 8, 2003: 8, 2004: 8, 2009: 8, 2012: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 }], - CAR.ELANTRA_GT_I30: [{ - 66: 8, 67: 8, 68: 8, 127: 8, 128: 8, 129: 8, 273: 8, 274: 8, 275: 8, 339: 8, 354: 3, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1193: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1356: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1414: 3, 1415: 8, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1952: 8, 1960: 8, 1988: 8, 2000: 8, 2001: 8, 2005: 8, 2008: 8, 2009: 8, 2013: 8, 2017: 8, 2025: 8 - }, - { - 66: 8, 67: 8, 68: 8, 127: 8, 128: 8, 129: 8, 273: 8, 274: 8, 275: 8, 339: 8, 354: 3, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 897: 8, 899: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1356: 8, 1363: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1414: 3, 1415: 8, 1419: 8, 1440: 8, 1456: 4, 1470: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8 - }, - { - 66: 8, 67: 8, 68: 8, 127: 8, 128: 8, 129: 8, 273: 8, 274: 8, 275: 8, 339: 8, 354: 3, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 897: 8, 899: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1356: 8, 1363: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1486: 8, 1487: 8, 1491: 8, 1960: 8, 1990: 8, 1998: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2008: 8, 2009: 8, 2012: 8, 2013: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }], CAR.HYUNDAI_GENESIS: [{ 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 916: 8, 1024: 2, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1342: 6, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 5, 1407: 8, 1419: 8, 1427: 6, 1434: 2, 1456: 4 }, @@ -791,6 +781,7 @@ FW_VERSIONS = { }, CAR.PALISADE: { (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00LX2_ SCC F-CUP 1.00 1.04 99110-S8100 ', b'\xf1\x00LX2_ SCC F-CUP 1.00 1.05 99110-S8100 ', b'\xf1\x00LX2 SCC FHCUP 1.00 1.04 99110-S8100 ', b'\xf1\x00LX2_ SCC FHCU- 1.00 1.05 99110-S8100 ', @@ -804,6 +795,7 @@ FW_VERSIONS = { b'\xf1\x00LX ESC \x01 1031\t\x10 58910-S8360', b'\xf1\x00LX ESC \x0b 101\x19\x03\x17 58910-S8330', b'\xf1\x00LX ESC \x0b 102\x19\x05\x07 58910-S8330', + b'\xf1\x00LX ESC \x0b 103\x19\t\t 58910-S8350', b'\xf1\x00LX ESC \x0b 103\x19\t\x07 58910-S8330', b'\xf1\x00LX ESC \x0b 103\x19\t\x10 58910-S8360', b'\xf1\x00LX ESC \x0b 104 \x10\x16 58910-S8360', @@ -818,6 +810,7 @@ FW_VERSIONS = { ], (Ecu.eps, 0x7d4, None): [ b'\xf1\x00LX2 MDPS C 1,00 1,03 56310-S8020 4LXDC103', + b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8000 4LXDC103', b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8020 4LXDC103', b'\xf1\x00LX2 MDPS C 1.00 1.04 56310-S8020 4LXDC104', b'\xf1\x00ON MDPS C 1.00 1.00 56340-S9000 8B13', @@ -834,6 +827,7 @@ FW_VERSIONS = { ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x00bcsh8p54 U872\x00\x00\x00\x00\x00\x00TON4G38NB1\x96z28', + b'\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', b'\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00TON4G38NB2[v\\\xb6', b'\xf1\x87LBLUFN591307KF25vgvw\x97wwwy\x99\xa7\x99\x99\xaa\xa9\x9af\x88\x96h\x95o\xf7\xff\x99f/\xff\xe4c\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX2G38NB2\xd7\xc1/\xd1', b'\xf1\x87LBLUFN650868KF36\xa9\x98\x89\x88\xa8\x88\x88\x88h\x99\xa6\x89fw\x86gw\x88\x97x\xaa\x7f\xf6\xff\xbb\xbb\x8f\xff+\x82\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX2G38NB3\xd1\xc3\xf8\xa8', @@ -1210,6 +1204,23 @@ FW_VERSIONS = { b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6B8051\x00\x00\xf1\x006T6H0_C2\x00\x006T6B8051\x00\x00TJFSG24NH27\xa7\xc2\xb4', ], }, + CAR.ELANTRA: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00PD LKAS AT USA LHD 1.01 1.01 95740-G3100 A54', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DPD0H16NS0e\x0e\xcd\x8e', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00PD MDPS C 1.00 1.04 56310/G3300 4PDDC104', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00PD ESC \x0b 104\x18\t\x03 58920-G3350', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00PD__ SCC F-CUP 1.00 1.00 96400-G3300 ', + ], + }, CAR.ELANTRA_2021: { (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00CN7_ SCC F-CUP 1.00 1.01 99110-AA000 ', @@ -1368,6 +1379,7 @@ FW_VERSIONS = { CAR.TUCSON_HYBRID_4TH_GEN: { (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9240 14Q', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9220 14K', ], (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00NX4__ 1.00 1.00 99110-N9100 ', @@ -1390,12 +1402,12 @@ CHECKSUM = { FEATURES = { # which message has the gear - "use_cluster_gears": {CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KONA}, + "use_cluster_gears": {CAR.ELANTRA, CAR.KONA}, "use_tcu_gears": {CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.SONATA_LF, CAR.VELOSTER, CAR.TUCSON}, "use_elect_gears": {CAR.KIA_NIRO_EV, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.KONA_EV_2022}, # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 - "use_fca": {CAR.SONATA, CAR.SONATA_HYBRID, CAR.ELANTRA, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KONA_EV, CAR.KIA_FORTE, CAR.KIA_NIRO_EV, CAR.PALISADE, CAR.GENESIS_G70, CAR.GENESIS_G70_2020, CAR.KONA, CAR.SANTA_FE, CAR.KIA_SELTOS, CAR.KONA_HEV, CAR.SANTA_FE_2022, CAR.KIA_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.TUCSON, CAR.KONA_EV_2022}, + "use_fca": {CAR.SONATA, CAR.SONATA_HYBRID, CAR.ELANTRA, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.KIA_STINGER, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KONA_EV, CAR.KIA_FORTE, CAR.KIA_NIRO_EV, CAR.PALISADE, CAR.GENESIS_G70, CAR.GENESIS_G70_2020, CAR.KONA, CAR.SANTA_FE, CAR.KIA_SELTOS, CAR.KONA_HEV, CAR.SANTA_FE_2022, CAR.KIA_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.TUCSON, CAR.KONA_EV_2022}, } CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN} @@ -1415,7 +1427,6 @@ DBC = { CAR.ELANTRA: dbc_dict('hyundai_kia_generic', None), CAR.ELANTRA_2021: dbc_dict('hyundai_kia_generic', None), CAR.ELANTRA_HEV_2021: dbc_dict('hyundai_kia_generic', None), - CAR.ELANTRA_GT_I30: dbc_dict('hyundai_kia_generic', None), CAR.GENESIS_G70: dbc_dict('hyundai_kia_generic', None), CAR.GENESIS_G70_2020: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar_generated'), CAR.GENESIS_G80: dbc_dict('hyundai_kia_generic', None), diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 921dc7a63..129273efe 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -43,7 +43,7 @@ CAR_INFO: Dict[str, Union[MazdaCarInfo, List[MazdaCarInfo]]] = { CAR.MAZDA3: MazdaCarInfo("Mazda 3 2017-18"), CAR.MAZDA6: MazdaCarInfo("Mazda 6 2017-20"), CAR.CX9_2021: MazdaCarInfo("Mazda CX-9 2021-22", video_link="https://youtu.be/dA3duO4a0O4"), - CAR.CX5_2022: MazdaCarInfo("Mazda CX-5 2022"), + CAR.CX5_2022: MazdaCarInfo("Mazda CX-5 2022-23"), } @@ -89,6 +89,7 @@ FW_VERSIONS = { ], (Ecu.fwdCamera, 0x706, None): [ b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.transmission, 0x7e1, None): [ b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index ed364dea1..5838c315a 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -23,7 +23,6 @@ non_tested_cars = [ GM.MALIBU, GM.EQUINOX, GM.BOLT_EV, - HYUNDAI.ELANTRA_GT_I30, HYUNDAI.GENESIS_G90, HYUNDAI.KIA_OPTIMA_H, ] @@ -119,6 +118,7 @@ routes = [ CarTestRoute("34a875f29f69841a|2021-07-29--13-02-09", HYUNDAI.KIA_NIRO_HEV_2021), CarTestRoute("50a2212c41f65c7b|2021-05-24--16-22-06", HYUNDAI.KIA_FORTE), CarTestRoute("c5ac319aa9583f83|2021-06-01--18-18-31", HYUNDAI.ELANTRA), + CarTestRoute("734ef96182ddf940|2022-10-02--16-41-44", HYUNDAI.ELANTRA), # 2019 Elantra GT CarTestRoute("82e9cdd3f43bf83e|2021-05-15--02-42-51", HYUNDAI.ELANTRA_2021), CarTestRoute("715ac05b594e9c59|2021-06-20--16-21-07", HYUNDAI.ELANTRA_HEV_2021), CarTestRoute("7120aa90bbc3add7|2021-08-02--07-12-31", HYUNDAI.SONATA_HYBRID), diff --git a/selfdrive/car/tests/test_fw_fingerprint.py b/selfdrive/car/tests/test_fw_fingerprint.py index b9926301f..2e4310385 100755 --- a/selfdrive/car/tests/test_fw_fingerprint.py +++ b/selfdrive/car/tests/test_fw_fingerprint.py @@ -1,6 +1,7 @@ #!/usr/bin/env python3 import random import unittest +from collections import defaultdict from parameterized import parameterized from cereal import car @@ -44,6 +45,16 @@ class TestFwFingerprint(unittest.TestCase): duplicates = {fw for fw in ecu_fw if ecu_fw.count(fw) > 1} self.assertFalse(len(duplicates), f"{car_model}: Duplicate FW versions: Ecu.{ECU_NAME[ecu[0]]}, {duplicates}") + def test_all_addrs_map_to_one_ecu(self): + for brand, cars in VERSIONS.items(): + addr_to_ecu = defaultdict(set) + for ecus in cars.values(): + for ecu_type, addr, sub_addr in ecus.keys(): + addr_to_ecu[(addr, sub_addr)].add(ecu_type) + ecus_for_addr = addr_to_ecu[(addr, sub_addr)] + ecu_strings = ", ".join([f'Ecu.{ECU_NAME[ecu]}' for ecu in ecus_for_addr]) + self.assertLessEqual(len(ecus_for_addr), 1, f"{brand} has multiple ECUs that map to one address: {ecu_strings} -> ({hex(addr)}, {sub_addr})") + def test_data_collection_ecus(self): # Asserts no extra ECUs are in the fingerprinting database for brand, config in FW_QUERY_CONFIGS.items(): diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index 13a0dae7a..460b9a909 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -21,7 +21,6 @@ FORD FOCUS 4TH GEN: [.nan, 1.5, .nan] COMMA BODY: [.nan, 1000, .nan] # Totally new cars -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] diff --git a/selfdrive/car/torque_data/params.yaml b/selfdrive/car/torque_data/params.yaml index 160f60548..5c828fa66 100644 --- a/selfdrive/car/torque_data/params.yaml +++ b/selfdrive/car/torque_data/params.yaml @@ -35,21 +35,22 @@ HYUNDAI SANTA FE 2019: [3.0787027729757632, 2.6173437483495565, 0.12070193418239 HYUNDAI SANTA FE HYBRID 2022: [3.501877602644835, 2.729064118456137, 0.10384068104538963] HYUNDAI SANTA FE PlUG-IN HYBRID 2022: [1.6953050513611045, 1.5837614296206861, 0.12672855941458458] HYUNDAI SONATA 2019: [2.2200457811703953, 1.2967330275895228, 0.14039920986586393] -HYUNDAI SONATA 2020: [3.284505627881726, 2.1259108157250735, 0.08452048323586728] +HYUNDAI SONATA 2020: [2.9638737459977467, 2.1259108157250735, 0.07813665616927593] HYUNDAI SONATA HYBRID 2021: [2.8990264092395734, 2.061410192222139, 0.0899805488717382] JEEP GRAND CHEROKEE 2019: [1.7321233388827006, 1.289689569171081, 0.15046331002097185] JEEP GRAND CHEROKEE V6 2018: [1.8776598027756923, 1.4057367824262523, 0.11725947414922003] +KIA EV6 2022: [3.2, 3.0, 0.05] KIA K5 2021: [2.405339728085138, 1.460032270828705, 0.11650989850813716] KIA NIRO EV 2020: [2.9215954981365337, 2.1500583840260044, 0.09236802474810267] KIA SORENTO GT LINE 2018: [2.464854685101844, 1.5335274218367956, 0.12056170567599558] KIA STINGER GT2 2018: [2.7499043387418967, 1.849652021986449, 0.12048334239559202] -LEXUS ES 2019: [2.0203086922726112, 2.134803912579666, 0.12757526789308554] -LEXUS ES HYBRID 2019: [2.392442298703042, 1.863360677810788, 0.17690002108856212] +LEXUS ES 2019: [1.935835, 2.134803912579666, 0.093439] +LEXUS ES HYBRID 2019: [2.135678, 1.863360677810788, 0.109627] LEXUS NX 2018: [2.302625600642627, 2.1382378491466625, 0.14986840878892838] LEXUS NX 2020: [2.4331999786982936, 2.1045680431705414, 0.14099899317761067] LEXUS NX HYBRID 2018: [2.4025593501080955, 1.8080446063815507, 0.15349361249519017] LEXUS RX 2016: [1.5876816543130423, 1.0427699298523752, 0.21334066732397142] -LEXUS RX 2020: [1.5228812994274734, 1.431102486563665, 0.2093316728710659] +LEXUS RX 2020: [1.5228812994274734, 1.431102486563665, 0.164117] LEXUS RX HYBRID 2017: [1.6984261557042386, 1.3211501880159107, 0.1820354534928893] LEXUS RX HYBRID 2020: [1.5522309889823778, 1.255230465866663, 0.2220954003055114] MAZDA CX-9 2021: [1.7601682915983443, 1.0889677335154337, 0.17713792194297195] @@ -62,31 +63,31 @@ TOYOTA AVALON 2019: [1.7036141952825095, 1.239619084240008, 0.08459830394899492] TOYOTA AVALON 2022: [2.3154403649717357, 2.7777922854327124, 0.11453999639164605] TOYOTA C-HR 2018: [1.5591084333664578, 1.271271459066948, 0.20259087058453193] TOYOTA C-HR 2021: [1.7678810166088303, 1.3742176337919942, 0.2319674583741509] -TOYOTA CAMRY 2018: [2.1172995371905015, 1.7156177222420887, 0.13519250664782062] -TOYOTA CAMRY 2021: [2.6922769557433055, 2.3476510120007434, 0.1450430192989234] -TOYOTA CAMRY HYBRID 2018: [2.0974120828287774, 1.7996193116697359, 0.13823613467632756] -TOYOTA CAMRY HYBRID 2021: [2.6426668350384457, 2.3901492458927986, 0.16103875108816076] +TOYOTA CAMRY 2018: [2.1172995371905015, 1.7156177222420887, 0.105192506] +TOYOTA CAMRY 2021: [2.446083, 2.3476510120007434, 0.121615] +TOYOTA CAMRY HYBRID 2018: [1.996333, 1.7996193116697359, 0.112565] +TOYOTA CAMRY HYBRID 2021: [2.263582, 2.3901492458927986, 0.115257] TOYOTA COROLLA 2017: [3.117154369115421, 1.8438132575043773, 0.12289685869250652] -TOYOTA COROLLA HYBRID TSS2 2019: [2.3287672277252005, 1.8118712531729109, 0.2215868445753317] -TOYOTA COROLLA TSS2 2019: [2.4204464833010175, 1.9258612322678952, 0.20670411068012526] +TOYOTA COROLLA HYBRID TSS2 2019: [1.9079729107361805, 1.8118712531729109, 0.22251440891543514] +TOYOTA COROLLA TSS2 2019: [2.0742917676766712, 1.9258612322678952, 0.16888685704519352] TOYOTA HIGHLANDER 2017: [1.8696367437248915, 1.626293990451463, 0.17485372210240796] TOYOTA HIGHLANDER 2020: [2.022340166827233, 1.6183134804881791, 0.14592306380054457] -TOYOTA HIGHLANDER HYBRID 2018: [1.9421825202382728, 1.6433903296845025, 0.16928956792275918] -TOYOTA HIGHLANDER HYBRID 2020: [2.103373061114133, 2.104015182965606, 0.14447040132184993] +TOYOTA HIGHLANDER HYBRID 2018: [1.752033, 1.6433903296845025, 0.144600] +TOYOTA HIGHLANDER HYBRID 2020: [1.901174, 2.104015182965606, 0.14447040132184993] TOYOTA MIRAI 2021: [2.506899832157829, 1.7417213930750164, 0.20182618449440565] -TOYOTA PRIUS 2017: [2.0183401513314294, 1.5023147650693636, 0.20856908464957724] -TOYOTA PRIUS TSS2 2021: [2.327639738920072, 1.9104337425537743, 0.2030762265549664] +TOYOTA PRIUS 2017: [1.746445, 1.5023147650693636, 0.151515] +TOYOTA PRIUS TSS2 2021: [1.972600, 1.9104337425537743, 0.170968] TOYOTA RAV4 2017: [2.085695074355425, 2.2142832316984733, 0.13339165270103975] -TOYOTA RAV4 2019: [2.5038362866776835, 2.0993589721530252, 0.1552425356342368] +TOYOTA RAV4 2019: [2.331293, 2.0993589721530252, 0.129822] TOYOTA RAV4 2019 8965: [2.5084506298290377, 2.4216520504763475, 0.11992835265067918] TOYOTA RAV4 2019 x02: [2.7209621987605024, 2.2148637653781593, 0.10862567142268198] TOYOTA RAV4 HYBRID 2017: [1.9796257271652042, 1.7503987331707576, 0.14628860048885406] TOYOTA RAV4 HYBRID 2019: [2.2271858492309153, 2.074844961405639, 0.14382216826893632] TOYOTA RAV4 HYBRID 2019 8965: [2.1077397198131336, 1.8162215166877735, 0.13891369391200137] TOYOTA RAV4 HYBRID 2019 x02: [2.803624333289342, 2.272367966572498, 0.11364569214387774] -TOYOTA RAV4 HYBRID 2022: [2.241883248393209, 1.9304407208090029, 0.1565442715453653] +TOYOTA RAV4 HYBRID 2022: [2.241883248393209, 1.9304407208090029, 0.112174] TOYOTA RAV4 HYBRID 2022 x02: [3.044930631831037, 2.3979189796380918, 0.14023209146703736] -TOYOTA SIENNA 2018: [1.8660896232147548, 1.3208264576110418, 0.18799149615227198] +TOYOTA SIENNA 2018: [1.689726, 1.3208264576110418, 0.140456] VOLKSWAGEN ARTEON 1ST GEN: [1.45136518053819, 1.3639364049316804, 0.23806361745695032] VOLKSWAGEN ATLAS 1ST GEN: [1.4677006726964945, 1.6733266634075656, 0.12959584092073367] VOLKSWAGEN GOLF 7TH GEN: [1.3750394140491293, 1.5814743077200641, 0.2018321939386586] diff --git a/selfdrive/car/torque_data/substitute.yaml b/selfdrive/car/torque_data/substitute.yaml index f5e3d1d61..acd752600 100644 --- a/selfdrive/car/torque_data/substitute.yaml +++ b/selfdrive/car/torque_data/substitute.yaml @@ -26,7 +26,6 @@ KIA SELTOS 2021: HYUNDAI SONATA 2020 KIA NIRO HYBRID 2019: KIA NIRO EV 2020 KIA NIRO HYBRID 2021: KIA NIRO EV 2020 HYUNDAI VELOSTER 2019: HYUNDAI SONATA 2019 -HYUNDAI I30 N LINE 2019 & GT 2018 DCT: HYUNDAI SONATA 2019 HYUNDAI KONA 2020: HYUNDAI KONA ELECTRIC 2019 HYUNDAI KONA HYBRID 2020: HYUNDAI KONA ELECTRIC 2019 HYUNDAI KONA ELECTRIC 2022: HYUNDAI KONA ELECTRIC 2019 diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 28912645a..0d5acbfff 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -2,7 +2,6 @@ from cereal import car from common.conversions import Conversions as CV from panda import Panda -from selfdrive.car.toyota.tunes import LatTunes, LongTunes, set_long_tune, set_lat_tune from selfdrive.car.toyota.values import Ecu, CAR, ToyotaFlags, TSS2_CAR, RADAR_ACC_CAR, NO_DSU_CAR, MIN_ACC_SPEED, EPS_SCALE, EV_HYBRID_CAR, CarControllerParams from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase @@ -74,7 +73,6 @@ class CarInterface(CarInterfaceBase): ret.wheelSpeedFactor = 1.035 tire_stiffness_factor = 0.5533 ret.mass = 4481. * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max - set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate in (CAR.CHR, CAR.CHRH): stop_and_go = True @@ -82,7 +80,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.6 tire_stiffness_factor = 0.7933 ret.mass = 3300. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_F) elif candidate in (CAR.CAMRY, CAR.CAMRYH, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2): stop_and_go = True @@ -90,8 +87,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.7 tire_stiffness_factor = 0.7933 ret.mass = 3400. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid - if candidate not in (CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2): - set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate in (CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2): stop_and_go = True @@ -99,7 +94,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.0 tire_stiffness_factor = 0.8 ret.mass = 4516. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid - set_lat_tune(ret.lateralTuning, LatTunes.PID_G) elif candidate in (CAR.AVALON, CAR.AVALON_2019, CAR.AVALONH_2019, CAR.AVALON_TSS2, CAR.AVALONH_TSS2): # starting from 2019, all Avalon variants have stop and go @@ -109,7 +103,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.8 # Found at https://pressroom.toyota.com/releases/2016+avalon+product+specs.download tire_stiffness_factor = 0.7983 ret.mass = 3505. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid - set_lat_tune(ret.lateralTuning, LatTunes.PID_H) elif candidate in (CAR.RAV4_TSS2, CAR.RAV4_TSS2_2022, CAR.RAV4H_TSS2, CAR.RAV4H_TSS2_2022): stop_and_go = True @@ -117,14 +110,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.3 tire_stiffness_factor = 0.7933 ret.mass = 3585. * CV.LB_TO_KG + STD_CARGO_KG # Average between ICE and Hybrid - set_lat_tune(ret.lateralTuning, LatTunes.PID_D) - - # 2019+ RAV4 TSS2 uses two different steering racks and specific tuning seems to be necessary. - # See https://github.com/commaai/openpilot/pull/21429#issuecomment-873652891 - for fw in car_fw: - if fw.ecu == "eps" and (fw.fwVersion.startswith(b'\x02') or fw.fwVersion in [b'8965B42181\x00\x00\x00\x00\x00\x00']): - set_lat_tune(ret.lateralTuning, LatTunes.PID_I) - break elif candidate in (CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2): stop_and_go = True @@ -139,7 +124,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.0 # not optimized tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 3677. * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max - set_lat_tune(ret.lateralTuning, LatTunes.PID_D) elif candidate == CAR.SIENNA: stop_and_go = True @@ -147,14 +131,12 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 15.5 tire_stiffness_factor = 0.444 ret.mass = 4590. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_J) elif candidate in (CAR.LEXUS_IS, CAR.LEXUS_RC): ret.wheelbase = 2.79908 ret.steerRatio = 13.3 tire_stiffness_factor = 0.444 ret.mass = 3736.8 * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_L) elif candidate == CAR.LEXUS_CTH: stop_and_go = True @@ -162,7 +144,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 18.6 tire_stiffness_factor = 0.517 ret.mass = 3108 * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max - set_lat_tune(ret.lateralTuning, LatTunes.PID_M) elif candidate in (CAR.LEXUS_NX, CAR.LEXUS_NXH, CAR.LEXUS_NX_TSS2, CAR.LEXUS_NXH_TSS2): stop_and_go = True @@ -170,7 +151,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.7 tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 4070 * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate == CAR.PRIUS_TSS2: stop_and_go = True @@ -178,7 +158,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.4 # True steerRatio from older prius tire_stiffness_factor = 0.6371 # hand-tune ret.mass = 3115. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_N) elif candidate == CAR.MIRAI: stop_and_go = True @@ -186,7 +165,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.8 tire_stiffness_factor = 0.8 ret.mass = 4300. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate in (CAR.ALPHARD_TSS2, CAR.ALPHARDH_TSS2): stop_and_go = True @@ -194,7 +172,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.2 tire_stiffness_factor = 0.444 ret.mass = 4305. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_J) ret.centerToFront = ret.wheelbase * 0.44 @@ -230,12 +207,23 @@ 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 + tune = ret.longitudinalTuning if candidate in TSS2_CAR or ret.enableGasInterceptor: - set_long_tune(ret.longitudinalTuning, LongTunes.TSS2) + tune.deadzoneBP = [0., 8.05] + tune.deadzoneV = [.0, .14] + tune.kpBP = [0., 5., 20.] + tune.kpV = [1.3, 1.0, 0.7] + tune.kiBP = [0., 5., 12., 20., 27.] + tune.kiV = [.35, .23, .20, .17, .1] if candidate in TSS2_CAR: ret.stoppingDecelRate = 0.3 # reach stopping target smoothly else: - set_long_tune(ret.longitudinalTuning, LongTunes.TSS) + tune.deadzoneBP = [0., 9.] + tune.deadzoneV = [.0, .15] + tune.kpBP = [0., 5., 35.] + tune.kiBP = [0., 35.] + tune.kpV = [3.6, 2.4, 1.5] + tune.kiV = [0.54, 0.36] return ret diff --git a/selfdrive/car/toyota/tunes.py b/selfdrive/car/toyota/tunes.py deleted file mode 100644 index b73ab4c8c..000000000 --- a/selfdrive/car/toyota/tunes.py +++ /dev/null @@ -1,102 +0,0 @@ -#!/usr/bin/env python3 -from enum import Enum - -class LongTunes(Enum): - TSS2 = 0 - TSS = 1 - -class LatTunes(Enum): - INDI_PRIUS = 0 - LQR_RAV4 = 1 - PID_A = 2 - PID_B = 3 - PID_C = 4 - PID_D = 5 - PID_E = 6 - PID_F = 7 - PID_G = 8 - PID_I = 9 - PID_H = 10 - PID_J = 11 - PID_K = 12 - PID_L = 13 - PID_M = 14 - PID_N = 15 - - -###### LONG ###### -def set_long_tune(tune, name): - # Improved longitudinal tune - if name == LongTunes.TSS2: - tune.deadzoneBP = [0., 8.05] - tune.deadzoneV = [.0, .14] - tune.kpBP = [0., 5., 20.] - tune.kpV = [1.3, 1.0, 0.7] - tune.kiBP = [0., 5., 12., 20., 27.] - tune.kiV = [.35, .23, .20, .17, .1] - # Default longitudinal tune - elif name == LongTunes.TSS: - tune.deadzoneBP = [0., 9.] - tune.deadzoneV = [.0, .15] - tune.kpBP = [0., 5., 35.] - tune.kiBP = [0., 35.] - tune.kpV = [3.6, 2.4, 1.5] - tune.kiV = [0.54, 0.36] - else: - raise NotImplementedError('This longitudinal tune does not exist') - - -###### LAT ###### -def set_lat_tune(tune, name, MAX_LAT_ACCEL=2.5, FRICTION=0.01, steering_angle_deadzone_deg=0.0, use_steering_angle=True): - if 'PID' in str(name): - tune.init('pid') - tune.pid.kiBP = [0.0] - tune.pid.kpBP = [0.0] - if name == LatTunes.PID_A: - tune.pid.kpV = [0.2] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00003 - elif name == LatTunes.PID_C: - tune.pid.kpV = [0.6] - tune.pid.kiV = [0.1] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_D: - tune.pid.kpV = [0.6] - tune.pid.kiV = [0.1] - tune.pid.kf = 0.00007818594 - elif name == LatTunes.PID_F: - tune.pid.kpV = [0.723] - tune.pid.kiV = [0.0428] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_G: - tune.pid.kpV = [0.18] - tune.pid.kiV = [0.015] - tune.pid.kf = 0.00012 - elif name == LatTunes.PID_H: - tune.pid.kpV = [0.17] - tune.pid.kiV = [0.03] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_I: - tune.pid.kpV = [0.15] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00004 - elif name == LatTunes.PID_J: - tune.pid.kpV = [0.19] - tune.pid.kiV = [0.02] - tune.pid.kf = 0.00007818594 - elif name == LatTunes.PID_L: - tune.pid.kpV = [0.3] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_M: - tune.pid.kpV = [0.3] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00007 - elif name == LatTunes.PID_N: - tune.pid.kpV = [0.35] - tune.pid.kiV = [0.15] - tune.pid.kf = 0.00007818594 - else: - raise NotImplementedError('This PID tune does not exist') - else: - raise NotImplementedError('This lateral tune does not exist') diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 819b85d75..07c33d017 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1367,6 +1367,7 @@ FW_VERSIONS = { b'\x01896634AA1000\x00\x00\x00\x00', b'\x01896634A88000\x00\x00\x00\x00', b'\x01896634A89000\x00\x00\x00\x00', + b'\x01896634A89100\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F0R01100\x00\x00\x00\x00', diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 8c679c740..695868452 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -555,6 +555,7 @@ FW_VERSIONS = { b'\xf1\x8703N906026E \xf1\x892114', b'\xf1\x8704E906023AH\xf1\x893379', b'\xf1\x8704L906026ET\xf1\x891990', + b'\xf1\x8704L906026FP\xf1\x892012', b'\xf1\x8704L906026GA\xf1\x892013', b'\xf1\x8704L906026KD\xf1\x894798', b'\xf1\x873G0906264 \xf1\x890004', @@ -562,6 +563,7 @@ FW_VERSIONS = { (Ecu.transmission, 0x7e1, None): [ b'\xf1\x870CW300043H \xf1\x891601', b'\xf1\x870CW300048R \xf1\x890610', + b'\xf1\x870D9300013A \xf1\x894905', b'\xf1\x870D9300014L \xf1\x895002', b'\xf1\x870D9300041A \xf1\x894801', b'\xf1\x870DD300045T \xf1\x891601', @@ -579,6 +581,7 @@ FW_VERSIONS = { ], (Ecu.eps, 0x712, None): [ b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00611A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00711A1', b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0060803', b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0080803', b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521B00606A1', diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index cbc54eadb..1adbba417 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -82,13 +82,13 @@ class Controls: self.log_sock = messaging.sub_sock('androidLog') - params = Params() + self.params = Params() self.sm = sm if self.sm is None: ignore = ['testJoystick'] if SIMULATION: ignore += ['driverCameraState', 'managerState'] - if params.get_bool('WideCameraOnly'): + if self.params.get_bool('WideCameraOnly'): ignore += ['roadCameraState'] self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', 'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman', @@ -105,22 +105,22 @@ class Controls: else: self.CI, self.CP = CI, CI.CP - self.joystick_mode = params.get_bool("JoystickDebugMode") or (self.CP.notCar and sm is None) + self.joystick_mode = self.params.get_bool("JoystickDebugMode") or (self.CP.notCar and sm is None) # set alternative experiences from parameters - self.disengage_on_accelerator = params.get_bool("DisengageOnAccelerator") + self.disengage_on_accelerator = self.params.get_bool("DisengageOnAccelerator") self.CP.alternativeExperience = 0 if not self.disengage_on_accelerator: self.CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS - if self.CP.dashcamOnly and params.get_bool("DashcamOverride"): + if self.CP.dashcamOnly and self.params.get_bool("DashcamOverride"): self.CP.dashcamOnly = False # read params - self.is_metric = params.get_bool("IsMetric") - self.is_ldw_enabled = params.get_bool("IsLdwEnabled") - openpilot_enabled_toggle = params.get_bool("OpenpilotEnabledToggle") - passive = params.get_bool("Passive") or not openpilot_enabled_toggle + self.is_metric = self.params.get_bool("IsMetric") + self.is_ldw_enabled = self.params.get_bool("IsLdwEnabled") + openpilot_enabled_toggle = self.params.get_bool("OpenpilotEnabledToggle") + passive = self.params.get_bool("Passive") or not openpilot_enabled_toggle # detect sound card presence and ensure successful init sounds_available = HARDWARE.get_sound_card_online() @@ -139,15 +139,15 @@ class Controls: # Write CarParams for radard cp_bytes = self.CP.to_bytes() - params.put("CarParams", cp_bytes) + self.params.put("CarParams", cp_bytes) put_nonblocking("CarParamsCache", cp_bytes) put_nonblocking("CarParamsPersistent", cp_bytes) # cleanup old params if not self.CP.experimentalLongitudinalAvailable: - params.remove("ExperimentalLongitudinalEnabled") + self.params.remove("ExperimentalLongitudinalEnabled") if not self.CP.openpilotLongitudinalControl: - params.remove("EndToEndLong") + self.params.remove("EndToEndLong") self.CC = car.CarControl.new_message() self.CS_prev = car.CarState.new_message() @@ -254,8 +254,7 @@ class Controls: self.events.add(EventName.pedalPressed) if CS.gasPressed: - self.events.add(EventName.pedalPressedPreEnable if self.disengage_on_accelerator else - EventName.gasPressedOverride) + self.events.add(EventName.gasPressedOverride) if not self.CP.notCar: self.events.add_from_msg(self.sm['driverMonitoringState'].events) @@ -583,9 +582,9 @@ class Controls: """Given the state, this function returns a CarControl packet""" # Update VehicleModel - params = self.sm['liveParameters'] - x = max(params.stiffnessFactor, 0.1) - sr = max(params.steerRatio, 0.1) + lp = self.sm['liveParameters'] + x = max(lp.stiffnessFactor, 0.1) + sr = max(lp.steerRatio, 0.1) self.VM.update_params(x, sr) # Update Torque Params @@ -628,7 +627,7 @@ class Controls: lat_plan.psis, lat_plan.curvatures, lat_plan.curvatureRates) - actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, params, + actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, lp, self.last_actuators, self.steer_limited, self.desired_curvature, self.desired_curvature_rate, self.sm['liveLocationKalman']) else: @@ -768,10 +767,10 @@ class Controls: (self.state == State.softDisabling) # Curvature & Steering angle - params = self.sm['liveParameters'] + lp = self.sm['liveParameters'] - steer_angle_without_offset = math.radians(CS.steeringAngleDeg - params.angleOffsetDeg) - curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo, params.roll) + steer_angle_without_offset = math.radians(CS.steeringAngleDeg - lp.angleOffsetDeg) + curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo, lp.roll) # controlsState dat = messaging.new_message('controlsState') @@ -856,6 +855,8 @@ class Controls: start_time = sec_since_boot() self.prof.checkpoint("Ratekeeper", ignore=True) + self.is_metric = self.params.get_bool("IsMetric") + # Sample data from sockets and get a carState CS = self.data_sample() cloudlog.timestamp("Data sampled") diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index 2aab4b71a..49eb5988e 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -253,7 +253,8 @@ 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., 0.1, 0.2, 5.0, 0.0, 1.0] + a_change_cost = 40.0 if prev_accel_constraint else 0 + cost_weights = [0., 0.1, 0.2, 5.0, a_change_cost, 1.0] constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 50.0] else: raise NotImplementedError(f'Planner mode {self.mode} not recognized in planner cost set') diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 018136e6f..457065d3b 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -133,7 +133,7 @@ class LongitudinalPlanner: # TODO counter is only needed because radar is glitchy, remove once radar is gone # TODO write fcw in e2e_long mode - self.fcw = self.mpc.mode == 'acc' and self.mpc.crash_cnt > 5 + self.fcw = self.mpc.mode == 'acc' and self.mpc.crash_cnt > 5 and not sm['carState'].standstill if self.fcw: cloudlog.info("FCW triggered") diff --git a/selfdrive/controls/lib/radar_helpers.py b/selfdrive/controls/lib/radar_helpers.py index bf788190c..4bb017926 100644 --- a/selfdrive/controls/lib/radar_helpers.py +++ b/selfdrive/controls/lib/radar_helpers.py @@ -151,7 +151,8 @@ 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.0 and (v_ego < v_ego_stationary) and self.dRel < 25 + # Radar points closer than 0.75, are almost always glitches on toyota radars + return abs(self.yRel) < 1.0 and (v_ego < v_ego_stationary) and (0.75 < self.dRel < 25) def is_potential_fcw(self, model_prob): return model_prob > .9 diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index 9e6536f9b..1c68eb67b 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -31,6 +31,7 @@ INPUTS_NEEDED = 5 # Minimum blocks needed for valid calibration INPUTS_WANTED = 50 # We want a little bit more than we need for stability MAX_ALLOWED_SPREAD = np.radians(2) RPY_INIT = np.array([0.0,0.0,0.0]) +WIDE_FROM_DEVICE_EULER_INIT = np.array([0.0, 0.0, 0.0]) # These values are needed to accommodate biggest modelframe PITCH_LIMITS = np.array([-0.09074112085129739, 0.14907572052989657]) @@ -65,8 +66,8 @@ class Calibrator: # Read saved calibration params = Params() calibration_params = params.get("CalibrationParams") - self.wide_camera = params.get_bool('WideCameraOnly') rpy_init = RPY_INIT + wide_from_device_euler = WIDE_FROM_DEVICE_EULER_INIT valid_blocks = 0 if param_put and calibration_params: @@ -74,24 +75,34 @@ class Calibrator: msg = log.Event.from_bytes(calibration_params) rpy_init = np.array(msg.liveCalibration.rpyCalib) valid_blocks = msg.liveCalibration.validBlocks + wide_from_device_euler = np.array(msg.liveCalibration.wideFromDeviceEuler) except Exception: cloudlog.exception("Error reading cached CalibrationParams") - self.reset(rpy_init, valid_blocks) + self.reset(rpy_init, valid_blocks, wide_from_device_euler) self.update_status() - def reset(self, rpy_init: np.ndarray = RPY_INIT, valid_blocks: int = 0, smooth_from: Optional[np.ndarray] = None) -> None: + def reset(self, rpy_init: np.ndarray = RPY_INIT, + valid_blocks: int = 0, + wide_from_device_euler_init: np.ndarray = WIDE_FROM_DEVICE_EULER_INIT, + smooth_from: Optional[np.ndarray] = None) -> None: if not np.isfinite(rpy_init).all(): self.rpy = RPY_INIT.copy() else: self.rpy = rpy_init.copy() + if not np.isfinite(wide_from_device_euler_init).all() or len(wide_from_device_euler_init) != 3: + self.wide_from_device_euler = WIDE_FROM_DEVICE_EULER_INIT.copy() + else: + self.wide_from_device_euler = wide_from_device_euler_init.copy() + if not np.isfinite(valid_blocks) or valid_blocks < 0: self.valid_blocks = 0 else: self.valid_blocks = valid_blocks self.rpys = np.tile(self.rpy, (INPUTS_WANTED, 1)) + self.wide_from_device_eulers = np.tile(self.wide_from_device_euler, (INPUTS_WANTED, 1)) self.idx = 0 self.block_idx = 0 @@ -113,6 +124,7 @@ class Calibrator: def update_status(self) -> None: valid_idxs = self.get_valid_idxs() if valid_idxs: + self.wide_from_device_euler = np.mean(self.wide_from_device_eulers[valid_idxs], axis=0) rpys = self.rpys[valid_idxs] self.rpy = np.mean(rpys, axis=0) max_rpy_calib = np.array(np.max(rpys, axis=0)) @@ -146,14 +158,14 @@ class Calibrator: else: return self.rpy - def handle_cam_odom(self, trans: List[float], rot: List[float], trans_std: List[float]) -> Optional[np.ndarray]: + def handle_cam_odom(self, trans: List[float], + rot: List[float], + wide_from_device_euler: List[float], + trans_std: List[float]) -> Optional[np.ndarray]: self.old_rpy_weight = min(0.0, self.old_rpy_weight - 1/SMOOTH_CYCLES) straight_and_fast = ((self.v_ego > MIN_SPEED_FILTER) and (trans[0] > MIN_SPEED_FILTER) and (abs(rot[2]) < MAX_YAW_RATE_FILTER)) - if self.wide_camera: - angle_std_threshold = 4*MAX_VEL_ANGLE_STD - else: - angle_std_threshold = MAX_VEL_ANGLE_STD + angle_std_threshold = MAX_VEL_ANGLE_STD certain_if_calib = ((np.arctan2(trans_std[1], trans[0]) < angle_std_threshold) or (self.valid_blocks < INPUTS_NEEDED)) if not (straight_and_fast and certain_if_calib): @@ -165,7 +177,14 @@ class Calibrator: new_rpy = euler_from_rot(rot_from_euler(self.get_smooth_rpy()).dot(rot_from_euler(observed_rpy))) new_rpy = sanity_clip(new_rpy) - self.rpys[self.block_idx] = (self.idx*self.rpys[self.block_idx] + (BLOCK_SIZE - self.idx) * new_rpy) / float(BLOCK_SIZE) + if len(wide_from_device_euler) == 3: + new_wide_from_device_euler = np.array(wide_from_device_euler) + else: + new_wide_from_device_euler = WIDE_FROM_DEVICE_EULER_INIT + self.rpys[self.block_idx] = (self.idx*self.rpys[self.block_idx] + + (BLOCK_SIZE - self.idx) * new_rpy) / float(BLOCK_SIZE) + self.wide_from_device_eulers[self.block_idx] = (self.idx*self.wide_from_device_eulers[self.block_idx] + + (BLOCK_SIZE - self.idx) * new_wide_from_device_euler) / float(BLOCK_SIZE) self.idx = (self.idx + 1) % BLOCK_SIZE if self.idx == 0: self.block_idx += 1 @@ -187,6 +206,7 @@ class Calibrator: liveCalibration.calPerc = min(100 * (self.valid_blocks * BLOCK_SIZE + self.idx) // (INPUTS_NEEDED * BLOCK_SIZE), 100) liveCalibration.rpyCalib = smooth_rpy.tolist() liveCalibration.rpyCalibSpread = self.calib_spread.tolist() + liveCalibration.wideFromDeviceEuler = self.wide_from_device_euler.tolist() if self.not_car: liveCalibration.validBlocks = INPUTS_NEEDED @@ -223,6 +243,7 @@ def calibrationd_thread(sm: Optional[messaging.SubMaster] = None, pm: Optional[m calibrator.handle_v_ego(sm['carState'].vEgo) new_rpy = calibrator.handle_cam_odom(sm['cameraOdometry'].trans, sm['cameraOdometry'].rot, + sm['cameraOdometry'].wideFromDeviceEuler, sm['cameraOdometry'].transStd) if DEBUG and new_rpy is not None: diff --git a/selfdrive/locationd/torqued.py b/selfdrive/locationd/torqued.py index 66af23459..42dff6008 100755 --- a/selfdrive/locationd/torqued.py +++ b/selfdrive/locationd/torqued.py @@ -16,7 +16,9 @@ from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY HISTORY = 5 # secs POINTS_PER_BUCKET = 1500 MIN_POINTS_TOTAL = 4000 +MIN_POINTS_TOTAL_QLOG = 800 FIT_POINTS_TOTAL = 2000 +FIT_POINTS_TOTAL_QLOG = 800 MIN_VEL = 15 # m/s FRICTION_FACTOR = 1.5 # ~85% of data coverage FACTOR_SANITY = 0.3 @@ -26,7 +28,7 @@ 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] +MIN_BUCKET_POINTS = np.array([100, 300, 500, 500, 500, 500, 300, 100]) MAX_RESETS = 5.0 MAX_INVALID_THRESHOLD = 10 MIN_ENGAGE_BUFFER = 2 # secs @@ -58,10 +60,11 @@ class NPQueue: class PointBuckets: - def __init__(self, x_bounds, min_points): + def __init__(self, x_bounds, min_points, min_points_total): 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)} + self.min_points_total = min_points_total def bucket_lengths(self): return [len(v) for v in self.buckets.values()] @@ -70,7 +73,7 @@ class PointBuckets: 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) + return all(len(v) >= min_pts for v, min_pts in zip(self.buckets.values(), self.buckets_min_points.values())) and (self.__len__() >= self.min_points_total) def add_point(self, x, y): for bound_min, bound_max in self.x_bounds: @@ -90,9 +93,17 @@ class PointBuckets: class TorqueEstimator: - def __init__(self, CP): + def __init__(self, CP, decimated=False): self.hist_len = int(HISTORY / DT_MDL) self.lag = CP.steerActuatorDelay + .2 # from controlsd + if decimated: + self.min_bucket_points = MIN_BUCKET_POINTS / 10 + self.min_points_total = MIN_POINTS_TOTAL_QLOG + self.fit_points = FIT_POINTS_TOTAL_QLOG + else: + self.min_bucket_points = MIN_BUCKET_POINTS + self.min_points_total = MIN_POINTS_TOTAL + self.fit_points = FIT_POINTS_TOTAL self.offline_friction = 0.0 self.offline_latAccelFactor = 0.0 @@ -157,10 +168,10 @@ class TorqueEstimator: 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) + self.filtered_points = PointBuckets(x_bounds=STEER_BUCKET_BOUNDS, min_points=self.min_bucket_points, min_points_total=self.min_points_total) def estimate_params(self): - points = self.filtered_points.get_points(FIT_POINTS_TOTAL) + points = self.filtered_points.get_points(self.fit_points) # 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: diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index 21602ea70..243223eab 100644 --- a/selfdrive/modeld/models/supercombo.onnx +++ b/selfdrive/modeld/models/supercombo.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:9c119aa811a929b3a442dbe8e462a9d88e8bfb9f5809a4e737687fb7380d7e05 -size 45922882 +oid sha256:dcfad22cecf37275d01a339d96174800c109e9a70f853fdef3e4ef62ed3f4bbe +size 45922983 diff --git a/selfdrive/sensord/rawgps/rawgpsd.py b/selfdrive/sensord/rawgps/rawgpsd.py index 5a6827a75..1c6505166 100755 --- a/selfdrive/sensord/rawgps/rawgpsd.py +++ b/selfdrive/sensord/rawgps/rawgpsd.py @@ -87,16 +87,24 @@ def try_setup_logs(diag, log_types): else: raise Exception(f"setup logs failed, {log_types=}") -def mmcli(cmd: str) -> None: +def at_cmd(cmd: str) -> None: for _ in range(5): try: - subprocess.check_call(f"mmcli -m any --timeout 30 {cmd}", shell=True) + subprocess.check_call(f"mmcli -m any --timeout 30 --command='{cmd}'", shell=True) break except subprocess.CalledProcessError: cloudlog.exception("rawgps.mmcli_command_failed") else: raise Exception(f"failed to execute mmcli command {cmd=}") + +def gps_enabled() -> bool: + try: + p = subprocess.check_output("mmcli -m any --command=\"AT+QGPS?\"", shell=True) + return b"QGPS: 1" in p + except subprocess.CalledProcessError as exc: + raise Exception("failed to execute QGPS mmcli command") from exc + def setup_quectel(diag: ModemDiag): # enable OEMDRE in the NV # TODO: it has to reboot for this to take effect @@ -108,11 +116,17 @@ def setup_quectel(diag: ModemDiag): setup_logs(diag, LOG_TYPES) + if gps_enabled(): + at_cmd("AT+QGPSEND") + # disable DPO power savings for more accuracy - mmcli("--command='AT+QGPSCFG=\"dpoenable\",0'") + at_cmd("AT+QGPSCFG=\"dpoenable\",0") # don't automatically turn on GNSS on powerup - mmcli("--command='AT+QGPSCFG=\"autogps\",0'") - mmcli("--location-enable-gps-raw --location-enable-gps-nmea") + at_cmd("AT+QGPSCFG=\"autogps\",0") + + at_cmd("AT+QGPSSUPLURL=\"supl.google.com:7275\"") + at_cmd("AT+QGPSCFG=\"outport\",\"usbnmea\"") + at_cmd("AT+QGPS=1") # enable OEMDRE mode DIAG_SUBSYS_CMD_F = 75 @@ -134,7 +148,9 @@ def setup_quectel(diag: ModemDiag): )) def teardown_quectel(diag): - mmcli("--location-disable-gps-raw --location-disable-gps-nmea") + at_cmd("AT+QGPSCFG=\"outport\",\"none\"") + if gps_enabled(): + at_cmd("AT+QGPSEND") try_setup_logs(diag, []) @@ -156,7 +172,7 @@ def main() -> NoReturn: # wait for ModemManager to come up cloudlog.warning("waiting for modem to come up") while True: - ret = subprocess.call("mmcli -m any --timeout 10 --location-status", stdout=subprocess.DEVNULL, stderr=subprocess.DEVNULL, shell=True) + ret = subprocess.call("mmcli -m any --timeout 10 --command=\"AT+QGPS?\"", stdout=subprocess.DEVNULL, stderr=subprocess.DEVNULL, shell=True) if ret == 0: break time.sleep(0.1) diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index b5fd11fee..d13ced3a5 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -46cb9c522e942d8b25deac90ffdee89efff60ce9 +49ea844254883ac61caa2ac425f453799aeb28a6 diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 9d37be4a5..bc55e33cb 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -456,6 +456,9 @@ def setup_env(simulation=False, CP=None, cfg=None, controlsState=None): os.environ['SKIP_FW_QUERY'] = "1" os.environ['FINGERPRINT'] = CP.carFingerprint + if CP.openpilotLongitudinalControl: + params.put_bool("ExperimentalLongitudinalEnabled", True) + def python_replay_process(cfg, lr, fingerprint=None): sub_sockets = [s for _, sub in cfg.pub_sub.items() for s in sub] diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 230e81d94..c7d81c349 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -f5a352666728344ca5065bb44c47c1f5650b4243 +e56c5a6ac5b87ee6083c9f92921e7198591f7b5d diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index cecabd8a3..5c754d931 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -24,10 +24,11 @@ source_segments = [ ("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 + ("CHRYSLER", "4deb27de11bee626|2021-02-20--11-28-55--8"), # CHRYSLER.PACIFICA_2018_HYBRID ("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 + ("GM2", "376bf99325883932|2022-10-27--13-41-22--1"), # GM.BOLT_EUV ("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--4"), # MAZDA.CX9_2021 @@ -50,6 +51,7 @@ segments = [ ("RAM", "regen20490083AE7|2022-09-27--15-53-15--0"), ("SUBARU", "regen1E72BBDCED5|2022-09-27--15-55-31--0"), ("GM", "regen45B05A80EF6|2022-09-27--15-57-22--0"), + ("GM2", "376bf99325883932|2022-10-27--13-41-22--1"), ("NISSAN", "regenC19D899B46D|2022-09-27--15-59-13--0"), ("VOLKSWAGEN", "regenD8F7AC4BD0D|2022-09-27--16-41-45--0"), ("MAZDA", "regenFC3F9ECBB64|2022-09-27--16-03-09--0"), diff --git a/selfdrive/ui/qt/home.cc b/selfdrive/ui/qt/home.cc index 78bc6aab4..3fe00e6ed 100644 --- a/selfdrive/ui/qt/home.cc +++ b/selfdrive/ui/qt/home.cc @@ -1,11 +1,9 @@ #include "selfdrive/ui/qt/home.h" -#include #include #include #include -#include "common/params.h" #include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/widgets/drive_stats.h" #include "selfdrive/ui/qt/widgets/prime.h" @@ -109,22 +107,20 @@ OffroadHome::OffroadHome(QWidget* parent) : QFrame(parent) { header_layout->setContentsMargins(15, 15, 15, 0); header_layout->setSpacing(16); - date = new QLabel(); - header_layout->addWidget(date, 1, Qt::AlignHCenter | Qt::AlignLeft); - update_notif = new QPushButton(tr("UPDATE")); update_notif->setVisible(false); update_notif->setStyleSheet("background-color: #364DEF;"); QObject::connect(update_notif, &QPushButton::clicked, [=]() { center_layout->setCurrentIndex(1); }); - header_layout->addWidget(update_notif, 0, Qt::AlignHCenter | Qt::AlignRight); + header_layout->addWidget(update_notif, 0, Qt::AlignHCenter | Qt::AlignLeft); alert_notif = new QPushButton(); alert_notif->setVisible(false); alert_notif->setStyleSheet("background-color: #E22C2C;"); QObject::connect(alert_notif, &QPushButton::clicked, [=] { center_layout->setCurrentIndex(2); }); - header_layout->addWidget(alert_notif, 0, Qt::AlignHCenter | Qt::AlignRight); + header_layout->addWidget(alert_notif, 0, Qt::AlignHCenter | Qt::AlignLeft); - header_layout->addWidget(new QLabel(getBrandVersion()), 0, Qt::AlignHCenter | Qt::AlignRight); + version = new ElidedLabel(); + header_layout->addWidget(version, 0, Qt::AlignHCenter | Qt::AlignRight); main_layout->addLayout(header_layout); @@ -184,9 +180,7 @@ void OffroadHome::hideEvent(QHideEvent *event) { } void OffroadHome::refresh() { - QString locale_name = QString(uiState()->language).replace("main_", ""); - QString dateString = QLocale(locale_name).toString(QDateTime::currentDateTime(), "dddd, MMMM d"); - date->setText(dateString); + version->setText(getBrand() + " " + QString::fromStdString(params.get("UpdaterCurrentDescription"))); bool updateAvailable = update_widget->refresh(); int alerts = alerts_widget->refresh(); diff --git a/selfdrive/ui/qt/home.h b/selfdrive/ui/qt/home.h index 94f133010..6636da56e 100644 --- a/selfdrive/ui/qt/home.h +++ b/selfdrive/ui/qt/home.h @@ -7,10 +7,12 @@ #include #include +#include "common/params.h" #include "selfdrive/ui/qt/offroad/driverview.h" #include "selfdrive/ui/qt/body.h" #include "selfdrive/ui/qt/onroad.h" #include "selfdrive/ui/qt/sidebar.h" +#include "selfdrive/ui/qt/widgets/controls.h" #include "selfdrive/ui/qt/widgets/offroad_alerts.h" #include "selfdrive/ui/ui.h" @@ -25,8 +27,10 @@ private: void hideEvent(QHideEvent *event) override; void refresh(); + Params params; + QTimer* timer; - QLabel* date; + ElidedLabel* version; QStackedLayout* center_layout; UpdateAlert *update_widget; OffroadAlert* alerts_widget; diff --git a/selfdrive/ui/qt/offroad/software_settings.cc b/selfdrive/ui/qt/offroad/software_settings.cc index 4f048241c..e08a02a4d 100644 --- a/selfdrive/ui/qt/offroad/software_settings.cc +++ b/selfdrive/ui/qt/offroad/software_settings.cc @@ -145,11 +145,11 @@ void SoftwarePanel::updateLabels() { targetBranchBtn->setValue(QString::fromStdString(params.get("UpdaterTargetBranch"))); // current + new versions - versionLbl->setText(QString::fromStdString(params.get("UpdaterCurrentDescription")).left(40)); + versionLbl->setText(QString::fromStdString(params.get("UpdaterCurrentDescription"))); versionLbl->setDescription(QString::fromStdString(params.get("UpdaterCurrentReleaseNotes"))); installBtn->setVisible(!is_onroad && params.getBool("UpdateAvailable")); - installBtn->setValue(QString::fromStdString(params.get("UpdaterNewDescription")).left(35)); + installBtn->setValue(QString::fromStdString(params.get("UpdaterNewDescription"))); installBtn->setDescription(QString::fromStdString(params.get("UpdaterNewReleaseNotes"))); update(); diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 1f677fc92..346cb3ab9 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -100,10 +100,6 @@ void OnroadWindow::offroadTransition(bool offroad) { #endif alerts->updateAlert({}, bg); - - // update stream type - bool wide_cam = Params().getBool("WideCameraOnly"); - nvg->setStreamType(wide_cam ? VISION_STREAM_WIDE_ROAD : VISION_STREAM_ROAD); } void OnroadWindow::paintEvent(QPaintEvent *event) { @@ -232,8 +228,10 @@ void AnnotatedCameraWidget::updateState(const UIState &s) { setProperty("rightHandDM", sm["driverMonitoringState"].getDriverMonitoringState().getIsRHD()); } + setStreamType(s.scene.wide_cam ? VISION_STREAM_WIDE_ROAD : VISION_STREAM_ROAD); if (s.scene.calibration_valid) { - CameraWidget::updateCalibration(s.scene.view_from_calib); + auto calib = s.scene.wide_cam ? s.scene.view_from_wide_calib : s.scene.view_from_calib; + CameraWidget::updateCalibration(calib); } else { CameraWidget::updateCalibration(DEFAULT_CALIBRATION); } diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc index c5697c104..59903e337 100644 --- a/selfdrive/ui/qt/util.cc +++ b/selfdrive/ui/qt/util.cc @@ -21,10 +21,6 @@ QString getBrand() { return Params().getBool("Passive") ? QObject::tr("dashcam") : QObject::tr("openpilot"); } -QString getBrandVersion() { - return getBrand() + " v" + getVersion().left(14).trimmed(); -} - QString getUserAgent() { return "openpilot-" + getVersion(); } diff --git a/selfdrive/ui/qt/util.h b/selfdrive/ui/qt/util.h index 209f05196..61a27a866 100644 --- a/selfdrive/ui/qt/util.h +++ b/selfdrive/ui/qt/util.h @@ -11,7 +11,6 @@ QString getVersion(); QString getBrand(); -QString getBrandVersion(); QString getUserAgent(); std::optional getDongleId(); QMap getSupportedLanguages(); diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 200257235..d7591633c 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -96,8 +96,8 @@ mat4 get_fit_view_transform(float widget_aspect_ratio, float frame_aspect_ratio) CameraWidget::CameraWidget(std::string stream_name, VisionStreamType type, bool zoom, QWidget* parent) : stream_name(stream_name), stream_type(type), zoomed_view(zoom), QOpenGLWidget(parent) { setAttribute(Qt::WA_OpaquePaintEvent); - connect(this, &CameraWidget::vipcThreadConnected, this, &CameraWidget::vipcConnected, Qt::BlockingQueuedConnection); - connect(this, &CameraWidget::vipcThreadFrameReceived, this, &CameraWidget::vipcFrameReceived); + QObject::connect(this, &CameraWidget::vipcThreadConnected, this, &CameraWidget::vipcConnected, Qt::BlockingQueuedConnection); + QObject::connect(this, &CameraWidget::vipcThreadFrameReceived, this, &CameraWidget::vipcFrameReceived, Qt::QueuedConnection); } CameraWidget::~CameraWidget() { @@ -162,13 +162,13 @@ void CameraWidget::initializeGL() { } void CameraWidget::showEvent(QShowEvent *event) { - frames.clear(); if (!vipc_thread) { vipc_thread = new QThread(); connect(vipc_thread, &QThread::started, [=]() { vipcThread(); }); connect(vipc_thread, &QThread::finished, vipc_thread, &QObject::deleteLater); vipc_thread->start(); } + clearFrames(); } void CameraWidget::hideEvent(QHideEvent *event) { @@ -178,6 +178,7 @@ void CameraWidget::hideEvent(QHideEvent *event) { vipc_thread->wait(); vipc_thread = nullptr; } + clearFrames(); } void CameraWidget::updateFrameMat() { @@ -187,12 +188,17 @@ void CameraWidget::updateFrameMat() { if (stream_type == VISION_STREAM_DRIVER) { frame_mat = get_driver_view_transform(w, h, stream_width, stream_height); } else { - intrinsic_matrix = (stream_type == VISION_STREAM_WIDE_ROAD) ? ecam_intrinsic_matrix : fcam_intrinsic_matrix; - zoom = (stream_type == VISION_STREAM_WIDE_ROAD) ? 2.5 : 1.1; - // Project point at "infinity" to compute x and y offsets // to ensure this ends up in the middle of the screen + // for narrow come and a little lower for wide cam. // TODO: use proper perspective transform? + if (stream_type == VISION_STREAM_WIDE_ROAD) { + intrinsic_matrix = ecam_intrinsic_matrix; + zoom = 2.0; + } else { + intrinsic_matrix = fcam_intrinsic_matrix; + zoom = 1.1; + } const vec3 inf = {{1000., 0., 0.}}; const vec3 Ep = matvecmul3(calibration, inf); const vec3 Kep = matvecmul3(intrinsic_matrix, Ep); @@ -233,45 +239,37 @@ void CameraWidget::paintGL() { glClearColor(bg.redF(), bg.greenF(), bg.blueF(), bg.alphaF()); glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); - if (frames.empty()) return; - - int frame_idx = frames.size() - 1; + std::lock_guard lk(frame_lock); - // Always draw latest frame until sync logic is more stable - // for (frame_idx = 0; frame_idx < frames.size() - 1; frame_idx++) { - // if (frames[frame_idx].first == draw_frame_id) break; - // } - - // Log duplicate/dropped frames - if (frames[frame_idx].first == prev_frame_id) { - qDebug() << "Drawing same frame twice" << frames[frame_idx].first; - } else if (frames[frame_idx].first != prev_frame_id + 1) { - qDebug() << "Skipped frame" << frames[frame_idx].first; + // use previous texture if update() is called without new frame. + VisionBuf *frame = nullptr; + if (!frames.empty()) { + frame = frames.front().second; + frames.pop_front(); } - prev_frame_id = frames[frame_idx].first; glViewport(0, 0, width(), height()); glBindVertexArray(frame_vao); glUseProgram(program->programId()); glPixelStorei(GL_UNPACK_ALIGNMENT, 1); - VisionBuf *frame = frames[frame_idx].second; - #ifdef QCOM2 glActiveTexture(GL_TEXTURE0); - glEGLImageTargetTexture2DOES(GL_TEXTURE_EXTERNAL_OES, egl_images[frame->idx]); - assert(glGetError() == GL_NO_ERROR); + if (frame) { + glEGLImageTargetTexture2DOES(GL_TEXTURE_EXTERNAL_OES, egl_images[frame->idx]); + assert(glGetError() == GL_NO_ERROR); + } #else glPixelStorei(GL_UNPACK_ROW_LENGTH, stream_stride); glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, textures[0]); - glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, stream_width, stream_height, GL_RED, GL_UNSIGNED_BYTE, frame->y); + if (frame) glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, stream_width, stream_height, GL_RED, GL_UNSIGNED_BYTE, frame->y); assert(glGetError() == GL_NO_ERROR); glPixelStorei(GL_UNPACK_ROW_LENGTH, stream_stride/2); glActiveTexture(GL_TEXTURE0 + 1); glBindTexture(GL_TEXTURE_2D, textures[1]); - glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, stream_width/2, stream_height/2, GL_RG, GL_UNSIGNED_BYTE, frame->uv); + if (frame) glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, stream_width/2, stream_height/2, GL_RG, GL_UNSIGNED_BYTE, frame->uv); assert(glGetError() == GL_NO_ERROR); #endif @@ -288,7 +286,6 @@ void CameraWidget::paintGL() { void CameraWidget::vipcConnected(VisionIpcClient *vipc_client) { makeCurrent(); - frames.clear(); stream_width = vipc_client->buffers[0].width; stream_height = vipc_client->buffers[0].height; stream_stride = vipc_client->buffers[0].stride; @@ -339,11 +336,7 @@ void CameraWidget::vipcConnected(VisionIpcClient *vipc_client) { updateFrameMat(); } -void CameraWidget::vipcFrameReceived(VisionBuf *buf, uint32_t frame_id) { - frames.push_back(std::make_pair(frame_id, buf)); - while (frames.size() > FRAME_BUFFER_SIZE) { - frames.pop_front(); - } +void CameraWidget::vipcFrameReceived() { update(); } @@ -354,11 +347,13 @@ void CameraWidget::vipcThread() { while (!QThread::currentThread()->isInterruptionRequested()) { if (!vipc_client || cur_stream_type != stream_type) { + clearFrames(); cur_stream_type = stream_type; vipc_client.reset(new VisionIpcClient(stream_name, cur_stream_type, false)); } if (!vipc_client->connected) { + clearFrames(); if (!vipc_client->connect(false)) { QThread::msleep(100); continue; @@ -367,7 +362,15 @@ void CameraWidget::vipcThread() { } if (VisionBuf *buf = vipc_client->recv(&meta_main, 1000)) { - emit vipcThreadFrameReceived(buf, meta_main.frame_id); + { + std::lock_guard lk(frame_lock); + frames.push_back(std::make_pair(meta_main.frame_id, buf)); + while (frames.size() > FRAME_BUFFER_SIZE) { + qDebug() << "Skipped frame" << frames.front().first; + frames.pop_front(); + } + } + emit vipcThreadFrameReceived(); } } @@ -378,3 +381,8 @@ void CameraWidget::vipcThread() { egl_images.clear(); #endif } + +void CameraWidget::clearFrames() { + std::lock_guard lk(frame_lock); + frames.clear(); +} diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index 9bcad935c..aff3abc83 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -1,6 +1,7 @@ #pragma once #include +#include #include #include @@ -37,7 +38,7 @@ public: signals: void clicked(); void vipcThreadConnected(VisionIpcClient *); - void vipcThreadFrameReceived(VisionBuf *, quint32); + void vipcThreadFrameReceived(); protected: void paintGL() override; @@ -49,6 +50,7 @@ protected: virtual void updateFrameMat(); void updateCalibration(const mat3 &calib); void vipcThread(); + void clearFrames(); bool zoomed_view; GLuint frame_vao, frame_vbo, frame_ibo; @@ -76,11 +78,11 @@ protected: mat3 calibration = DEFAULT_CALIBRATION; mat3 intrinsic_matrix = fcam_intrinsic_matrix; + std::mutex frame_lock; std::deque> frames; uint32_t draw_frame_id = 0; - uint32_t prev_frame_id = 0; protected slots: void vipcConnected(VisionIpcClient *vipc_client); - void vipcFrameReceived(VisionBuf *vipc_client, uint32_t frame_id); + void vipcFrameReceived(); }; diff --git a/selfdrive/ui/qt/widgets/controls.cc b/selfdrive/ui/qt/widgets/controls.cc index a1ebf57b0..d3b77935d 100644 --- a/selfdrive/ui/qt/widgets/controls.cc +++ b/selfdrive/ui/qt/widgets/controls.cc @@ -41,7 +41,7 @@ AbstractControl::AbstractControl(const QString &title, const QString &desc, cons hlayout->addWidget(title_label); // value next to control button - value = new QLabel(); + value = new ElidedLabel(); value->setAlignment(Qt::AlignRight | Qt::AlignVCenter); value->setStyleSheet("color: #aaaaaa"); hlayout->addWidget(value); @@ -70,7 +70,7 @@ AbstractControl::AbstractControl(const QString &title, const QString &desc, cons } void AbstractControl::hideEvent(QHideEvent *e) { - if(description != nullptr) { + if (description != nullptr) { description->hide(); } } diff --git a/selfdrive/ui/qt/widgets/controls.h b/selfdrive/ui/qt/widgets/controls.h index c42716828..f11f9baf5 100644 --- a/selfdrive/ui/qt/widgets/controls.h +++ b/selfdrive/ui/qt/widgets/controls.h @@ -65,7 +65,7 @@ protected: QPushButton *title_label; private: - QLabel *value; + ElidedLabel *value; QLabel *description = nullptr; }; diff --git a/selfdrive/ui/qt/widgets/scrollview.cc b/selfdrive/ui/qt/widgets/scrollview.cc index bd4309d8d..553659301 100644 --- a/selfdrive/ui/qt/widgets/scrollview.cc +++ b/selfdrive/ui/qt/widgets/scrollview.cc @@ -3,6 +3,8 @@ #include #include +// TODO: disable horizontal scrolling and resize + ScrollView::ScrollView(QWidget *w, QWidget *parent) : QScrollArea(parent) { setWidget(w); setWidgetResizable(true); diff --git a/selfdrive/ui/translations/main_ar.ts b/selfdrive/ui/translations/main_ar.ts index a94d2fbc0..3c47e6e8e 100644 --- a/selfdrive/ui/translations/main_ar.ts +++ b/selfdrive/ui/translations/main_ar.ts @@ -4,17 +4,14 @@ AbstractAlert - Close أغلق - Snooze Update تأخير التحديث - Reboot and Update إعادة التشغيل والتحديث @@ -22,67 +19,84 @@ 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 اتركه فارغا للتكوين التلقائي + + Cellular Metered + + + + Prevent large data uploads when on a metered connection + + + + + AnnotatedCameraWidget + + km/h + km/h + + + mph + mph + + + MAX + الأعلى + + + SPEED + سرعة + + + LIMIT + حد + ConfirmationDialog - - Ok موافق - Cancel إلغاء @@ -90,17 +104,14 @@ DeclinePage - You must accept the Terms and Conditions in order to use openpilot. يجب عليك قبول الشروط والأحكام من أجل استخدام openpilot. - Back خلف - Decline, uninstall %1 رفض ، قم بإلغاء تثبيت %1 @@ -108,152 +119,122 @@ DevicePanel - 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 درجات لأسفل. يقوم برنامج 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 +242,26 @@ DriveStats - Drives أرقام القيادة - Hours ساعات - ALL TIME في كل وقت - PAST WEEK الأسبوع الماضي - KM كم - Miles اميال @@ -294,7 +269,6 @@ DriverViewScene - camera starting بدء تشغيل الكاميرا @@ -302,12 +276,10 @@ InputDialog - Cancel إلغاء - Need at least %n character(s)! تحتاج على الأقل %n حرف! @@ -322,22 +294,18 @@ Installer - Installing... جارٍ التثبيت ... - Receiving objects: استقبال الكائنات: - Resolving deltas: حل دلتا: - Updating files: جارٍ تحديث الملفات: @@ -345,27 +313,22 @@ MapETA - eta eta - min دق - hr سع - km كم - mi مل @@ -373,22 +336,18 @@ MapInstructions - km كم - m م - mi مل - ft قد @@ -396,48 +355,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 لا توجد وجهات حديثة @@ -445,12 +396,10 @@ location set MapWindow - Map Loading تحميل الخريطة - Waiting for GPS في انتظار GPS @@ -458,12 +407,10 @@ location set MultiOptionDialog - Select اختر - Cancel إلغاء @@ -471,72 +418,33 @@ location set Networking - Advanced متقدم - Enter password أدخل كلمة المرور - - for "%1" ل "%1" - Wrong password كلمة مرور خاطئة - - AnnotatedCameraWidget - - - km/h - km/h - - - - mph - mph - - - - - MAX - الأعلى - - - - - SPEED - سرعة - - - - - LIMIT - حد - - OffroadHome - UPDATE تحديث - ALERTS تنبيهات - ALERT تنبيه @@ -544,22 +452,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 على شاشتك الرئيسية لاستخدامه مثل أي تطبيق @@ -567,32 +471,26 @@ location set PrimeAdWidget - Upgrade Now قم بالترقية الآن - Become a comma prime member at connect.comma.ai كن عضوًا comme prime في connect.comma.ai - PRIME FEATURES: ميزات PRIME: - Remote access الوصول عن بعد - 1 year of storage سنة واحدة من التخزين - Developer perks امتيازات المطور @@ -600,22 +498,18 @@ location set PrimeUserWidget - ✓ SUBSCRIBED ✓ مشترك - comma prime comma prime - CONNECT.COMMA.AI CONNECT.COMMA.AI - COMMA POINTS COMMA POINTS @@ -623,27 +517,22 @@ location set QObject - Reboot اعادة التشغيل - Exit أغلق - dashcam dashcam - openpilot openpilot - %n minute(s) ago منذ %n دقيقة @@ -655,7 +544,6 @@ location set - %n hour(s) ago منذ %n ساعة @@ -667,7 +555,6 @@ location set - %n day(s) ago منذ %n يوم @@ -682,47 +569,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. تعذر تحميل قسم البيانات. اضغط على تأكيد لإعادة ضبط جهازك. @@ -730,7 +608,6 @@ location set RichTextDialog - Ok موافق @@ -738,33 +615,26 @@ location set SettingsWindow - × x - Device جهاز - - Network شبكة الاتصال - Toggles التبديل - Software برمجة - Navigation ملاحة @@ -772,105 +642,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 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 ابدأ من جديد @@ -878,17 +725,14 @@ location set SetupWidget - Finish Setup إنهاء الإعداد - Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. قم بإقران جهازك بفاصلة connect (connect.comma.ai) واطلب عرض comma prime الخاص بك. - Pair device إقران الجهاز @@ -896,106 +740,82 @@ location set Sidebar - - CONNECT الاتصال - OFFLINE غير متصل - - ONLINE متصل - ERROR خطأ - - - TEMP درجة الحرارة - HIGH عالي - GOOD جيد - OK موافق - VEHICLE مركبة - NO لا - PANDA PANDA - GPS GPS - SEARCH بحث - -- -- - Wi-Fi Wi-Fi - ETH ETH - 2G 2G - 3G 3G - LTE LTE - 5G 5G @@ -1003,138 +823,141 @@ location set SoftwarePanel - Git Branch - Git Branch + Git Branch - Git Commit - 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. - آخر مرة نجح برنامج openpilot في التحقق من التحديث. يعمل المحدث فقط أثناء إيقاف تشغيل السيارة. + آخر مرة نجح برنامج 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 تأكد الان + + Updates are only downloaded while the car is off. + + + + Current Version + + + + Download + + + + Install Update + + + + INSTALL + + + + Target Branch + + + + SELECT + + + + Select a branch + + SshControl - SSH Keys SSH Keys - 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 اسم المستخدم '%1' غير موجود على GitHub @@ -1142,7 +965,6 @@ location set SshToggle - Enable SSH تفعيل SSH @@ -1150,22 +972,18 @@ location set TermsPage - Terms & Conditions البنود و الظروف - Decline انحدار - Scroll to accept قم بالتمرير للقبول - Agree موافق @@ -1173,125 +991,125 @@ 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. استخدم نظام الطيار المفتوح للتحكم التكيفي في ثبات السرعة والحفاظ على مساعدة السائق. انتباهك مطلوب في جميع الأوقات لاستخدام هذه الميزة. يسري تغيير هذا الإعداد عند إيقاف تشغيل السيارة. - 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 ميلاً في الساعة (50 كم / ساعة). - Use Metric System استخدم النظام المتري - Display speed in km/h instead of mph. عرض السرعة بالكيلو متر في الساعة بدلاً من ميل في الساعة. - Record and Upload Driver Camera تسجيل وتحميل كاميرا السائق - Upload data from the driver facing camera and help improve the driver monitoring algorithm. قم بتحميل البيانات من الكاميرا المواجهة للسائق وساعد في تحسين خوارزمية مراقبة السائق. - Disengage On Accelerator Pedal فك الارتباط على دواسة التسريع - When enabled, pressing the accelerator pedal will disengage openpilot. عند التمكين ، سيؤدي الضغط على دواسة الوقود إلى فصل الطيار المفتوح. - Show ETA in 24h Format إظهار الوقت المقدر للوصول بتنسيق 24 ساعة - Use 24h format instead of 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 التحكم الطولي - openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! - سوف يقوم برنامج openpilot بتعطيل رادار السيارة وسيتولى التحكم في الغاز والمكابح. تحذير: هذا يعطل AEB! + سوف يقوم برنامج openpilot بتعطيل رادار السيارة وسيتولى التحكم في الغاز والمكابح. تحذير: هذا يعطل AEB! + + + 🌮 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 longitudinal control is not currently available for this car. + + + + Enable experimental longitudinal control to enable this. + 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 للحصول على أسرع تجربة تحديث. حجم التنزيل 1 غيغابايت تقريبًا. - Connect to Wi-Fi اتصل بشبكة Wi-Fi - Install ثبيت - Back خلف - Loading... جار التحميل... - Reboot اعادة التشغيل - Update failed فشل التحديث @@ -1299,23 +1117,18 @@ location set WifiUI - - Scanning for networks... جارٍ البحث عن شبكات ... - CONNECTING... جارٍ الاتصال ... - FORGET نزع - Forget Wi-Fi Network "%1"? نزع شبكة اWi-Fi "%1"? diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 314a6b833..a11333a54 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -56,7 +56,7 @@ leave blank for automatic configuration - 空白のままにして、自動設定にします + 自動で設定するには、空白のままにしてください。 Cellular Metered @@ -136,7 +136,7 @@ PREVIEW - 見る + プレビュー Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) @@ -156,7 +156,7 @@ Review Training Guide - 入門書を見る + 使い方の確認 REVIEW @@ -168,7 +168,7 @@ Are you sure you want to review the training guide? - 入門書を見てもよろしいですか? + 使い方の確認をしますか? Regulatory @@ -200,11 +200,11 @@ 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の本体は、左右4°以内、上5°、下8°以内の角度で取付ける必要があります。継続してキャリブレーションを続けているので、手動でリセットを行う必要はほぼありません。 Your device is pointed %1° %2 and %3° %4. - このデバイスは%2の%1°、%4の%3°に向けます。 + このデバイスは%2 %1°、%4 %3°の向きに設置されています。 down @@ -309,7 +309,7 @@ MapETA eta - 予定到着時間 + 到着予定時間 min @@ -452,15 +452,15 @@ location set Go to https://connect.comma.ai on your phone - モバイルデバイスで「connect.comma.ai」にアクセスして + スマートフォンで「https://connect.comma.ai」にアクセスしてください。 Click "add new device" and scan the QR code on the right - 「新しいデバイスを追加」を押すと、右側のQRコードをスキャンしてください + 「新しいデバイスを追加」を押し、右側のQRコードをスキャンしてください。 Bookmark connect.comma.ai to your home screen to use it like an app - 「connect.comma.ai」をホーム画面に追加して、アプリのように使うことができます + 「connect.comma.ai」をホーム画面に追加して、アプリのように使うことができます。 @@ -608,7 +608,7 @@ location set Toggles - 切り替え + 機能設定 Software @@ -627,7 +627,7 @@ location set Power your device in a car with a harness or proceed at your own risk. - 自己責任でハーネスから電源を供給してください。 + 自己責任で実行を継続するか、ハーネスから電源を供給してください。 Power off @@ -643,7 +643,7 @@ location set Before we get on the road, let’s finish installation and cover some details. - その前に、インストールを完了し、いくつかの詳細を説明します。 + 道路に向かう前に、インストールを完了して使い方を確認しましょう。 Connect to Wi-Fi @@ -655,7 +655,7 @@ location set Continue without Wi-Fi - Wi-Fi に未接続で続行 + Wi-Fi に接続せずに続行 Waiting for internet @@ -663,7 +663,7 @@ location set Choose Software to Install - インストールするソフトウェアを選びます + インストールするソフトウェアを選択してください Dashcam @@ -710,7 +710,7 @@ location set Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. - デバイスを comma connect (connect.comma.ai)でペアリングし comma prime 特典を申請してください。 + デバイスを comma connect (connect.comma.ai)でペアリングし、comma primeの特典を申請してください。 Pair device @@ -836,7 +836,7 @@ location set UNINSTALL - アンインストール + 実行 Uninstall %1 @@ -859,7 +859,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 のユーザー名を入力しないでください。コンマのスタッフが GitHub のユーザー名を追加するようお願いすることはありません。 + 警告: これは、GitHub の設定にあるすべての公開鍵への SSH アクセスを許可するものです。自分以外の GitHub のユーザー名を入力しないでください。commaのスタッフが GitHub のユーザー名を追加するようお願いすることはありません。 ADD @@ -871,7 +871,7 @@ location set LOADING - ローディング + 読み込み中 REMOVE @@ -924,7 +924,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によるアダプティブクルーズコントロールとレーンキーピングドライバーアシストを利用します。この機能を利用する際は、常に前方への注意が必要です。この設定を変更すると、車の電源が切れた時に反映されます。 Enable Lane Departure Warnings @@ -932,11 +932,11 @@ 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)を超えるスピードで走行中、ウインカーを作動させずに検出された車線ライン上に車両が触れた場合、手動で車線内に戻るように警告を行います。 Use Metric System - メートル法を有効化 + メートル法を使用 Display speed in km/h instead of mph. @@ -952,7 +952,7 @@ location set 🌮 End-to-end longitudinal (extremely alpha) 🌮 - 🌮 エンドツーエンドのアクセル制御 (超アルファ版) 🌮 + 🌮 エンドツーエンドのアクセル制御 (超α版) 🌮 Experimental openpilot longitudinal control @@ -976,11 +976,11 @@ location set Disengage On Accelerator Pedal - アクセル踏むと openpilot をキャンセル + アクセルを踏むと openpilot を中断 When enabled, pressing the accelerator pedal will disengage openpilot. - 有効な場合は、アクセルを踏むと openpilot をキャンセルします。 + この機能を有効化すると、openpilotを利用中にアクセルを踏むとopenpilotによる運転サポートを中断します。 Show ETA in 24h Format @@ -1003,11 +1003,11 @@ 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 です。 + オペレーティングシステムのアップデートが必要です。Wi-Fi に接続してアップデートする事をお勧めします。ダウンロードサイズは約 1GB です。 Connect to Wi-Fi diff --git a/selfdrive/ui/translations/main_nl.ts b/selfdrive/ui/translations/main_nl.ts index 21bb66d35..24d2031f3 100644 --- a/selfdrive/ui/translations/main_nl.ts +++ b/selfdrive/ui/translations/main_nl.ts @@ -4,17 +4,14 @@ AbstractAlert - Close Sluit - Snooze Update Update uitstellen - Reboot and Update Opnieuw Opstarten en Updaten @@ -22,67 +19,84 @@ AdvancedNetworking - Back Terug - Enable Tethering Tethering Inschakelen - Tethering Password Tethering Wachtwoord - - EDIT AANPASSEN - Enter new tethering password Voer nieuw tethering wachtwoord in - IP Address IP Adres - Enable Roaming Roaming Inschakelen - APN Setting APN Instelling - Enter APN Voer APN in - leave blank for automatic configuration laat leeg voor automatische configuratie + + Cellular Metered + + + + Prevent large data uploads when on a metered connection + + + + + AnnotatedCameraWidget + + km/h + km/u + + + mph + mph + + + MAX + MAX + + + SPEED + SPEED + + + LIMIT + LIMIT + ConfirmationDialog - - Ok Ok - Cancel Annuleren @@ -90,17 +104,14 @@ DeclinePage - You must accept the Terms and Conditions in order to use openpilot. U moet de Algemene Voorwaarden accepteren om openpilot te gebruiken. - Back Terug - Decline, uninstall %1 Afwijzen, verwijder %1 @@ -108,152 +119,122 @@ DevicePanel - Dongle ID Dongle ID - N/A Nvt - Serial Serienummer - Driver Camera Bestuurders Camera - PREVIEW BEKIJKEN - Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) Bekijk de naar de bestuurder gerichte camera om ervoor te zorgen dat het monitoren van de bestuurder goed zicht heeft. (Voertuig moet uitgschakeld zijn) - Reset Calibration Kalibratie Resetten - RESET RESET - Are you sure you want to reset calibration? Weet u zeker dat u de kalibratie wilt resetten? - Review Training Guide Doorloop de Training Opnieuw - REVIEW BEKIJKEN - Review the rules, features, and limitations of openpilot Bekijk de regels, functies en beperkingen van openpilot - Are you sure you want to review the training guide? Weet u zeker dat u de training opnieuw wilt doorlopen? - Regulatory Regelgeving - VIEW BEKIJKEN - Change Language Taal Wijzigen - CHANGE WIJZIGEN - Select a language Selecteer een taal - Reboot Opnieuw Opstarten - Power Off Uitschakelen - 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 vereist dat het apparaat binnen 4° links of rechts en binnen 5° omhoog of 8° omlaag wordt gemonteerd. openpilot kalibreert continu, resetten is zelden nodig. - Your device is pointed %1° %2 and %3° %4. Uw apparaat is gericht op %1° %2 en %3° %4. - down omlaag - up omhoog - left links - right rechts - Are you sure you want to reboot? Weet u zeker dat u opnieuw wilt opstarten? - Disengage to Reboot Deactiveer openpilot om opnieuw op te starten - Are you sure you want to power off? Weet u zeker dat u wilt uitschakelen? - Disengage to Power Off Deactiveer openpilot om uit te schakelen @@ -261,32 +242,26 @@ DriveStats - Drives Ritten - Hours Uren - ALL TIME TOTAAL - PAST WEEK AFGELOPEN WEEK - KM Km - Miles Mijl @@ -294,7 +269,6 @@ DriverViewScene - camera starting Camera wordt gestart @@ -302,12 +276,10 @@ InputDialog - Cancel Annuleren - Need at least %n character(s)! Heeft minstens %n karakter nodig! @@ -318,22 +290,18 @@ Installer - Installing... Installeren... - Receiving objects: Objecten ontvangen: - Resolving deltas: Deltas verwerken: - Updating files: Bestanden bijwerken: @@ -341,27 +309,22 @@ MapETA - eta eta - min min - hr uur - km km - mi mi @@ -369,22 +332,18 @@ MapInstructions - km km - m m - mi mi - ft ft @@ -392,48 +351,40 @@ MapPanel - Current Destination Huidige Bestemming - CLEAR LEEGMAKEN - Recent Destinations Recente Bestemmingen - Try the Navigation Beta Probeer de Navigatie Bèta - Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai Krijg stapsgewijze routebeschrijving en meer met een comma prime abonnement. Meld u nu aan: https://connect.comma.ai - No home location set Geen thuislocatie ingesteld - No work location set Geen werklocatie ingesteld - no recent destinations geen recente bestemmingen @@ -441,12 +392,10 @@ ingesteld MapWindow - Map Loading Kaart wordt geladen - Waiting for GPS Wachten op GPS @@ -454,12 +403,10 @@ ingesteld MultiOptionDialog - Select Selecteer - Cancel Annuleren @@ -467,72 +414,33 @@ ingesteld Networking - Advanced Geavanceerd - Enter password Voer wachtwoord in - - for "%1" voor "%1" - Wrong password Verkeerd wachtwoord - - AnnotatedCameraWidget - - - km/h - km/u - - - - mph - mph - - - - - MAX - MAX - - - - - SPEED - SPEED - - - - - LIMIT - LIMIT - - OffroadHome - UPDATE UPDATE - ALERTS WAARSCHUWINGEN - ALERT WAARSCHUWING @@ -540,22 +448,18 @@ ingesteld PairingPopup - Pair your device to your comma account Koppel uw apparaat aan uw comma-account - Go to https://connect.comma.ai on your phone Ga naar https://connect.comma.ai op uw telefoon - Click "add new device" and scan the QR code on the right Klik op "add new device" en scan de QR-code aan de rechterkant - Bookmark connect.comma.ai to your home screen to use it like an app Voeg connect.comma.ai toe op uw startscherm om het als een app te gebruiken @@ -563,32 +467,26 @@ ingesteld PrimeAdWidget - Upgrade Now Upgrade nu - Become a comma prime member at connect.comma.ai Word een comma prime lid op connect.comma.ai - PRIME FEATURES: PRIME BEVAT: - Remote access Toegang op afstand - 1 year of storage 1 jaar lang opslag - Developer perks Voordelen voor ontwikkelaars @@ -596,22 +494,18 @@ ingesteld PrimeUserWidget - ✓ SUBSCRIBED ✓ GEABONNEERD - comma prime comma prime - CONNECT.COMMA.AI CONNECT.COMMA.AI - COMMA POINTS COMMA PUNTEN @@ -619,27 +513,22 @@ ingesteld QObject - Reboot Opnieuw Opstarten - Exit Afsluiten - dashcam dashcam - openpilot openpilot - %n minute(s) ago %n minuut geleden @@ -647,7 +536,6 @@ ingesteld - %n hour(s) ago %n uur geleden @@ -655,7 +543,6 @@ ingesteld - %n day(s) ago %n dag geleden @@ -666,47 +553,38 @@ ingesteld Reset - Reset failed. Reboot to try again. Opnieuw instellen mislukt. Start opnieuw op om opnieuw te proberen. - Are you sure you want to reset your device? Weet u zeker dat u uw apparaat opnieuw wilt instellen? - Resetting device... Apparaat opnieuw instellen... - System Reset Systeemreset - System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. Systeemreset geactiveerd. Druk op bevestigen om alle inhoud en instellingen te wissen. Druk op Annuleren om het opstarten te hervatten. - Cancel Annuleren - Reboot Opnieuw Opstarten - Confirm Bevestigen - Unable to mount data partition. Press confirm to reset your device. Kan gegevenspartitie niet koppelen. Druk op bevestigen om uw apparaat te resetten. @@ -714,7 +592,6 @@ ingesteld RichTextDialog - Ok Ok @@ -722,33 +599,26 @@ ingesteld SettingsWindow - × × - Device Apparaat - - Network Netwerk - Toggles Opties - Software Software - Navigation Navigatie @@ -756,105 +626,82 @@ ingesteld Setup - WARNING: Low Voltage WAARCHUWING: Lage Spanning - Power your device in a car with a harness or proceed at your own risk. Voorzie uw apparaat van stroom in een auto met een harnas (car harness) of ga op eigen risico verder. - Power off Uitschakelen - - - Continue Doorgaan - Getting Started Aan de slag - Before we get on the road, let’s finish installation and cover some details. Laten we, voordat we op pad gaan, de installatie afronden en enkele details bespreken. - Connect to Wi-Fi Maak verbinding met Wi-Fi - - Back Terug - Continue without Wi-Fi Doorgaan zonder Wi-Fi - Waiting for internet Wachten op internet - Choose Software to Install Kies Software om te Installeren - Dashcam Dashcam - Custom Software Andere Software - Enter URL Voer URL in - for Custom Software voor Andere Software - Downloading... Downloaden... - Download Failed Downloaden Mislukt - Ensure the entered URL is valid, and the device’s internet connection is good. Zorg ervoor dat de ingevoerde URL geldig is en dat de internetverbinding van het apparaat goed is. - Reboot device Apparaat opnieuw opstarten - Start over Begin opnieuw @@ -862,17 +709,14 @@ ingesteld SetupWidget - Finish Setup Installatie voltooien - Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. Koppel uw apparaat met comma connect (connect.comma.ai) en claim uw comma prime-aanbieding. - Pair device Apparaat koppelen @@ -880,106 +724,82 @@ ingesteld Sidebar - - CONNECT VERBINDING - OFFLINE OFFLINE - - ONLINE ONLINE - ERROR FOUT - - - TEMP TEMP - HIGH HOOG - GOOD GOED - OK OK - VEHICLE VOERTUIG - NO GEEN - PANDA PANDA - GPS GPS - SEARCH ZOEKEN - -- -- - Wi-Fi Wi-Fi - ETH ETH - 2G 2G - 3G 3G - LTE 4G - 5G 5G @@ -987,138 +807,141 @@ ingesteld SoftwarePanel - Git Branch - Git Branch + Git Branch - Git Commit - Git Commit + Git Commit - OS Version - OS Versie + OS Versie - Version - Versie + Versie - Last Update Check - Laatste Updatecontrole + Laatste Updatecontrole - The last time openpilot successfully checked for an update. The updater only runs while the car is off. - De laatste keer dat openpilot met succes heeft gecontroleerd op een update. De updater werkt alleen als de auto is uitgeschakeld. + De laatste keer dat openpilot met succes heeft gecontroleerd op een update. De updater werkt alleen als de auto is uitgeschakeld. - Check for Update - Controleer op Updates + Controleer op Updates - CHECKING - CONTROLEER + CONTROLEER - Switch Branch - Branch Verwisselen + Branch Verwisselen - ENTER - INVOEREN + INVOEREN - - The new branch will be pulled the next time the updater runs. - Tijdens de volgende update wordt de nieuwe branch opgehaald. + Tijdens de volgende update wordt de nieuwe branch opgehaald. - Enter branch name - Voer branch naam in + Voer branch naam in - Uninstall %1 Verwijder %1 - UNINSTALL VERWIJDER - Are you sure you want to uninstall? Weet u zeker dat u de installatie ongedaan wilt maken? - failed to fetch update - ophalen van update mislukt + ophalen van update mislukt - - CHECK CONTROLEER + + Updates are only downloaded while the car is off. + + + + Current Version + + + + Download + + + + Install Update + + + + INSTALL + + + + Target Branch + + + + SELECT + + + + Select a branch + + SshControl - SSH Keys SSH Sleutels - 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. Waarschuwing: dit geeft SSH toegang tot alle openbare sleutels in uw GitHub-instellingen. Voer nooit een andere GitHub-gebruikersnaam in dan die van uzelf. Een medewerker van comma zal u NOOIT vragen om zijn GitHub-gebruikersnaam toe te voegen. - - ADD TOEVOEGEN - Enter your GitHub username Voer uw GitHub gebruikersnaam in - LOADING LADEN - REMOVE VERWIJDEREN - Username '%1' has no keys on GitHub Gebruikersnaam '%1' heeft geen SSH sleutels op GitHub - Request timed out Time-out van aanvraag - Username '%1' doesn't exist on GitHub Gebruikersnaam '%1' bestaat niet op GitHub @@ -1126,7 +949,6 @@ ingesteld SshToggle - Enable SSH SSH Inschakelen @@ -1134,22 +956,18 @@ ingesteld TermsPage - Terms & Conditions Algemene Voorwaarden - Decline Afwijzen - Scroll to accept Scroll om te accepteren - Agree Akkoord @@ -1157,125 +975,125 @@ ingesteld TogglesPanel - Enable openpilot openpilot Inschakelen - 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. Gebruik het openpilot-systeem voor adaptieve cruisecontrol en rijstrookassistentie. Uw aandacht is te allen tijde vereist om deze functie te gebruiken. Het wijzigen van deze instelling wordt van kracht wanneer de auto wordt uitgeschakeld. - Enable Lane Departure Warnings Waarschuwingen bij Verlaten Rijstrook Inschakelen - 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). Ontvang waarschuwingen om terug naar de rijstrook te sturen wanneer uw voertuig over een gedetecteerde rijstrookstreep drijft zonder dat de richtingaanwijzer wordt geactiveerd terwijl u harder rijdt dan 50 km/u (31 mph). - Use Metric System Gebruik Metrisch Systeem - Display speed in km/h instead of mph. Geef snelheid weer in km/u in plaats van mph. - Record and Upload Driver Camera Opnemen en Uploaden van de Bestuurders Camera - Upload data from the driver facing camera and help improve the driver monitoring algorithm. Upload gegevens van de bestuurders camera en help het algoritme voor het monitoren van de bestuurder te verbeteren. - Disengage On Accelerator Pedal Deactiveren Met Gaspedaal - When enabled, pressing the accelerator pedal will disengage openpilot. Indien ingeschakeld, zal het indrukken van het gaspedaal openpilot deactiveren. - Show ETA in 24h Format Toon verwachte aankomsttijd in 24-uurs formaat - Use 24h format instead of am/pm Gebruik 24-uurs formaat in plaats van AM en PM - Show Map on Left Side of UI Toon kaart aan linkerkant van het scherm - Show map on left side when in split screen view. Toon kaart links in gesplitste schermweergave. - openpilot Longitudinal Control - openpilot Longitudinale Controle + openpilot Longitudinale Controle - openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! - openpilot zal de radar van de auto uitschakelen en de controle over gas en remmen overnemen. Waarschuwing: hierdoor wordt AEB (automatische noodrem) uitgeschakeld! + openpilot zal de radar van de auto uitschakelen en de controle over gas en remmen overnemen. Waarschuwing: hierdoor wordt AEB (automatische noodrem) uitgeschakeld! + + + 🌮 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 longitudinal control is not currently available for this car. + + + + Enable experimental longitudinal control to enable this. + Updater - Update Required Update Vereist - An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. Een update van het besturingssysteem is vereist. Verbind je apparaat met Wi-Fi voor de snelste update-ervaring. De downloadgrootte is ongeveer 1 GB. - Connect to Wi-Fi Maak verbinding met Wi-Fi - Install Installeer - Back Terug - Loading... Aan het laden... - Reboot Opnieuw Opstarten - Update failed Update mislukt @@ -1283,23 +1101,18 @@ ingesteld WifiUI - - Scanning for networks... Scannen naar netwerken... - CONNECTING... VERBINDEN... - FORGET VERGETEN - Forget Wi-Fi Network "%1"? Vergeet Wi-Fi Netwerk "%1"? diff --git a/selfdrive/ui/translations/main_pl.ts b/selfdrive/ui/translations/main_pl.ts index 92902d04a..bdce18137 100644 --- a/selfdrive/ui/translations/main_pl.ts +++ b/selfdrive/ui/translations/main_pl.ts @@ -4,17 +4,14 @@ AbstractAlert - Close Zamknij - Snooze Update Zaktualizuj później - Reboot and Update Uruchom ponownie i zaktualizuj @@ -22,67 +19,84 @@ AdvancedNetworking - Back Wróć - Enable Tethering Włącz hotspot osobisty - Tethering Password Hasło do hotspotu - - EDIT EDYTUJ - Enter new tethering password Wprowadź nowe hasło do hotspotu - IP Address Adres IP - Enable Roaming Włącz roaming danych - APN Setting Ustawienia APN - Enter APN Wprowadź APN - leave blank for automatic configuration Pozostaw puste, aby użyć domyślnej konfiguracji + + Cellular Metered + + + + Prevent large data uploads when on a metered connection + + + + + AnnotatedCameraWidget + + km/h + km/h + + + mph + mph + + + MAX + MAX + + + SPEED + PRĘDKOŚĆ + + + LIMIT + OGRANICZENIE + ConfirmationDialog - - Ok Ok - Cancel Anuluj @@ -90,17 +104,14 @@ DeclinePage - You must accept the Terms and Conditions in order to use openpilot. Aby korzystać z openpilota musisz zaakceptować regulamin. - Back Wróć - Decline, uninstall %1 Odrzuć, odinstaluj %1 @@ -108,152 +119,122 @@ DevicePanel - Dongle ID ID adaptera - N/A N/A - Serial Numer seryjny - Driver Camera Kamera kierowcy - PREVIEW PODGLĄD - Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) Wyświetl podgląd z kamery skierowanej na kierowcę, aby upewnić się, że monitoring kierowcy ma dobry zakres widzenia. (pojazd musi być wyłączony) - Reset Calibration Zresetuj kalibrację - RESET ZRESETUJ - Are you sure you want to reset calibration? Czy na pewno chcesz zresetować kalibrację? - Review Training Guide Zapoznaj się z samouczkiem - REVIEW ZAPOZNAJ SIĘ - Review the rules, features, and limitations of openpilot Zapoznaj się z zasadami, funkcjami i ograniczeniami openpilota - Are you sure you want to review the training guide? Czy na pewno chcesz się zapoznać z samouczkiem? - Regulatory Regulacja - VIEW WIDOK - Change Language Zmień język - CHANGE ZMIEŃ - Select a language Wybierz język - Reboot Uruchom ponownie - Power Off Wyłącz - 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 wymaga, aby urządzenie było zamontowane z maksymalnym odchyłem 4° poziomo, 5° w górę oraz 8° w dół. openpilot jest ciągle kalibrowany, rzadko konieczne jest resetowania urządzenia. - Your device is pointed %1° %2 and %3° %4. Twoje urządzenie jest skierowane %1° %2 oraz %3° %4. - down w dół - up w górę - left w lewo - right w prawo - Are you sure you want to reboot? Czy na pewno chcesz uruchomić ponownie urządzenie? - Disengage to Reboot Aby uruchomić ponownie, odłącz sterowanie - Are you sure you want to power off? Czy na pewno chcesz wyłączyć urządzenie? - Disengage to Power Off Aby wyłączyć urządzenie, odłącz sterowanie @@ -261,32 +242,26 @@ DriveStats - Drives Przejazdy - Hours Godziny - ALL TIME CAŁKOWICIE - PAST WEEK OSTATNI TYDZIEŃ - KM KM - Miles Mile @@ -294,7 +269,6 @@ DriverViewScene - camera starting uruchamianie kamery @@ -302,12 +276,10 @@ InputDialog - Cancel Anuluj - Need at least %n character(s)! Wpisana wartość powinna składać się przynajmniej z %n znaku! @@ -319,22 +291,18 @@ Installer - Installing... Instalowanie... - Receiving objects: Odbieranie obiektów: - Resolving deltas: Rozwiązywanie różnic: - Updating files: Aktualizacja plików: @@ -342,27 +310,22 @@ MapETA - eta przewidywany czas - min min - hr godz - km km - mi mi @@ -370,22 +333,18 @@ MapInstructions - km km - m m - mi mi - ft ft @@ -393,48 +352,40 @@ MapPanel - Current Destination Miejsce docelowe - CLEAR WYCZYŚĆ - Recent Destinations Ostatnie miejsca docelowe - Try the Navigation Beta Wypróbuj nawigację w wersji beta - Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai Odblokuj nawigację zakręt po zakęcie i wiele więcej subskrybując comma prime. Zarejestruj się teraz: https://connect.comma.ai - No home location set Lokalizacja domu nie została ustawiona - No work location set Miejsce pracy nie zostało ustawione - no recent destinations brak ostatnich miejsc docelowych @@ -442,12 +393,10 @@ nie zostało ustawione MapWindow - Map Loading Ładowanie Mapy - Waiting for GPS Oczekiwanie na sygnał GPS @@ -455,12 +404,10 @@ nie zostało ustawione MultiOptionDialog - Select Wybierz - Cancel Anuluj @@ -468,72 +415,33 @@ nie zostało ustawione Networking - Advanced Zaawansowane - Enter password Wprowadź hasło - - for "%1" do "%1" - Wrong password Niepoprawne hasło - - AnnotatedCameraWidget - - - km/h - km/h - - - - mph - mph - - - - - MAX - MAX - - - - - SPEED - PRĘDKOŚĆ - - - - - LIMIT - OGRANICZENIE - - OffroadHome - UPDATE UAKTUALNIJ - ALERTS ALERTY - ALERT ALERT @@ -541,22 +449,18 @@ nie zostało ustawione PairingPopup - Pair your device to your comma account Sparuj swoje urzadzenie ze swoim kontem comma - Go to https://connect.comma.ai on your phone Wejdź na stronę https://connect.comma.ai na swoim telefonie - Click "add new device" and scan the QR code on the right Kliknij "add new device" i zeskanuj kod QR znajdujący się po prawej stronie - Bookmark connect.comma.ai to your home screen to use it like an app Dodaj connect.comma.ai do zakładek na swoim ekranie początkowym, aby korzystać z niej jak z aplikacji @@ -564,32 +468,26 @@ nie zostało ustawione PrimeAdWidget - Upgrade Now Uaktualnij teraz - Become a comma prime member at connect.comma.ai Zostań członkiem comma prime na connect.comma.ai - PRIME FEATURES: FUNKCJE PRIME: - Remote access Zdalny dostęp - 1 year of storage 1 rok przechowywania danych - Developer perks Udogodnienia dla programistów @@ -597,22 +495,18 @@ nie zostało ustawione PrimeUserWidget - ✓ SUBSCRIBED ✓ ZASUBSKRYBOWANO - comma prime comma prime - CONNECT.COMMA.AI CONNECT.COMMA.AI - COMMA POINTS COMMA POINTS @@ -620,27 +514,22 @@ nie zostało ustawione QObject - Reboot Uruchom Ponownie - Exit Wyjdź - dashcam wideorejestrator - openpilot openpilot - %n minute(s) ago %n minutę temu @@ -649,7 +538,6 @@ nie zostało ustawione - %n hour(s) ago % godzinę temu @@ -658,7 +546,6 @@ nie zostało ustawione - %n day(s) ago %n dzień temu @@ -670,47 +557,38 @@ nie zostało ustawione Reset - Reset failed. Reboot to try again. Wymazywanie zakończone niepowodzeniem. Aby spróbować ponownie, uruchom ponownie urządzenie. - Are you sure you want to reset your device? Czy na pewno chcesz wymazać urządzenie? - Resetting device... Wymazywanie urządzenia... - System Reset Przywróć do ustawień fabrycznych - System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. Przywracanie do ustawień fabrycznych. Wciśnij potwierdź, aby usunąć wszystkie dane oraz ustawienia. Wciśnij anuluj, aby wznowić uruchamianie. - Cancel Anuluj - Reboot Uruchom ponownie - Confirm Potwiedź - Unable to mount data partition. Press confirm to reset your device. Partycja nie została zamontowana poprawnie. Wciśnij potwierdź, aby uruchomić ponownie urządzenie. @@ -718,7 +596,6 @@ nie zostało ustawione RichTextDialog - Ok Ok @@ -726,33 +603,26 @@ nie zostało ustawione SettingsWindow - × x - Device Urządzenie - - Network Sieć - Toggles Przełączniki - Software Oprogramowanie - Navigation Nawigacja @@ -760,105 +630,82 @@ nie zostało ustawione Setup - WARNING: Low Voltage OSTRZEŻENIE: Niskie Napięcie - Power your device in a car with a harness or proceed at your own risk. Podłącz swoje urządzenie do zasilania poprzez podłączenienie go do pojazdu lub kontynuuj na własną odpowiedzialność. - Power off Wyłącz - - - Continue Kontynuuj - Getting Started Zacznij - Before we get on the road, let’s finish installation and cover some details. Zanim ruszysz w drogę, dokończ instalację i podaj kilka szczegółów. - Connect to Wi-Fi Połącz z Wi-Fi - - Back Wróć - Continue without Wi-Fi Kontynuuj bez połączenia z Wif-Fi - Waiting for internet Oczekiwanie na połączenie sieciowe - Choose Software to Install Wybierz oprogramowanie do instalacji - Dashcam Wideorejestrator - Custom Software Własne oprogramowanie - Enter URL Wprowadź adres URL - for Custom Software do własnego oprogramowania - Downloading... Pobieranie... - Download Failed Pobieranie nie powiodło się - Ensure the entered URL is valid, and the device’s internet connection is good. Upewnij się, że wpisany adres URL jest poprawny, a połączenie internetowe działa poprawnie. - Reboot device Uruchom ponownie - Start over Zacznij od początku @@ -866,17 +713,14 @@ nie zostało ustawione SetupWidget - Finish Setup Zakończ konfigurację - Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. Sparuj swoje urządzenie z comma connect (connect.comma.ai) i wybierz swoją ofertę comma prime. - Pair device Sparuj urządzenie @@ -884,106 +728,82 @@ nie zostało ustawione Sidebar - - CONNECT POŁĄCZENIE - OFFLINE OFFLINE - - ONLINE ONLINE - ERROR BŁĄD - - - TEMP TEMP - HIGH WYSOKA - GOOD DOBRA - OK OK - VEHICLE POJAZD - NO BRAK - PANDA PANDA - GPS GPS - SEARCH SZUKAJ - -- -- - Wi-Fi Wi-FI - ETH ETH - 2G 2G - 3G 3G - LTE LTE - 5G 5G @@ -991,138 +811,141 @@ nie zostało ustawione SoftwarePanel - Git Branch - Gałąź Git + Gałąź Git - Git Commit - Git commit + Git commit - OS Version - Wersja systemu + Wersja systemu - Version - Wersja + Wersja - Last Update Check - Ostatnie sprawdzenie aktualizacji + Ostatnie sprawdzenie aktualizacji - The last time openpilot successfully checked for an update. The updater only runs while the car is off. - Ostatni raz kiedy openpilot znalazł aktualizację. Aktualizator może być uruchomiony wyłącznie wtedy, kiedy pojazd jest wyłączony. + Ostatni raz kiedy openpilot znalazł aktualizację. Aktualizator może być uruchomiony wyłącznie wtedy, kiedy pojazd jest wyłączony. - Check for Update - Sprawdź uaktualnienia + Sprawdź uaktualnienia - CHECKING - SPRAWDZANIE + SPRAWDZANIE - Switch Branch - Zmień gąłąź + Zmień gąłąź - ENTER - WPROWADŹ + WPROWADŹ - - The new branch will be pulled the next time the updater runs. - Nowa gałąź będzie pobrana przy następnym uruchomieniu aktualizatora. + Nowa gałąź będzie pobrana przy następnym uruchomieniu aktualizatora. - Enter branch name - Wprowadź nazwę gałęzi + Wprowadź nazwę gałęzi - Uninstall %1 Odinstaluj %1 - UNINSTALL ODINSTALUJ - Are you sure you want to uninstall? Czy na pewno chcesz odinstalować? - failed to fetch update - pobieranie aktualizacji zakończone niepowodzeniem + pobieranie aktualizacji zakończone niepowodzeniem - - CHECK SPRAWDŹ + + Updates are only downloaded while the car is off. + + + + Current Version + + + + Download + + + + Install Update + + + + INSTALL + + + + Target Branch + + + + SELECT + + + + Select a branch + + SshControl - SSH Keys Klucze 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. Ostrzeżenie: To spowoduje przekazanie dostępu do wszystkich Twoich publicznych kuczy z ustawień GitHuba. Nigdy nie wprowadzaj nazwy użytkownika innej niż swoja. Pracownik comma NIGDY nie poprosi o dodanie swojej nazwy uzytkownika. - - ADD DODAJ - Enter your GitHub username Wpisz swoją nazwę użytkownika GitHub - LOADING ŁADOWANIE - REMOVE USUŃ - Username '%1' has no keys on GitHub Użytkownik '%1' nie posiada żadnych kluczy na GitHubie - Request timed out Limit czasu rządania - Username '%1' doesn't exist on GitHub Użytkownik '%1' nie istnieje na GitHubie @@ -1130,7 +953,6 @@ nie zostało ustawione SshToggle - Enable SSH Włącz SSH @@ -1138,22 +960,18 @@ nie zostało ustawione TermsPage - Terms & Conditions Regulamin - Decline Odrzuć - Scroll to accept Przewiń w dół, aby zaakceptować - Agree Zaakceptuj @@ -1161,125 +979,125 @@ nie zostało ustawione TogglesPanel - Enable openpilot Włącz openpilota - 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. Użyj openpilota do zachowania bezpiecznego odstępu między pojazdami i do asystowania w utrzymywaniu pasa ruchu. Twoja pełna uwaga jest wymagana przez cały czas korzystania z tej funkcji. Ustawienie to może być wdrożone wyłącznie wtedy, gdy pojazd jest wyłączony. - Enable Lane Departure Warnings Włącz ostrzeganie przed zmianą pasa ruchu - 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). Otrzymuj alerty o powrocie na właściwy pas, kiedy Twój pojazd przekroczy linię bez włączonego kierunkowskazu jadąc powyżej 50 km/h (31 mph). - Use Metric System Korzystaj z systemu metrycznego - Display speed in km/h instead of mph. Wyświetl prędkość w km/h zamiast mph. - Record and Upload Driver Camera Nagraj i prześlij nagranie z kamery kierowcy - Upload data from the driver facing camera and help improve the driver monitoring algorithm. Prześlij dane z kamery skierowanej na kierowcę i pomóż poprawiać algorytm monitorowania kierowcy. - Disengage On Accelerator Pedal Odłącz poprzez naciśnięcie gazu - When enabled, pressing the accelerator pedal will disengage openpilot. Po włączeniu, naciśnięcie na pedał gazu odłączy openpilota. - Show ETA in 24h Format Pokaż oczekiwany czas dojazdu w formacie 24-godzinnym - Use 24h format instead of am/pm Korzystaj z formatu 24-godzinnego zamiast 12-godzinnego - Show Map on Left Side of UI Pokaż mapę po lewej stronie ekranu - Show map on left side when in split screen view. Pokaż mapę po lewej stronie kiedy ekran jest podzielony. - openpilot Longitudinal Control - Kontrola wzdłużna openpilota + Kontrola wzdłużna openpilota - openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! - openpilot wyłączy radar samochodu i przejmie kontrolę nad gazem i hamulcem. Ostrzeżenie: wyłączony zostanie system AEB! + openpilot wyłączy radar samochodu i przejmie kontrolę nad gazem i hamulcem. Ostrzeżenie: wyłączony zostanie system AEB! + + + 🌮 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 longitudinal control is not currently available for this car. + + + + Enable experimental longitudinal control to enable this. + Updater - Update Required Wymagana Aktualizacja - An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. Wymagana aktualizacja systemu operacyjnego. Aby przyspieszyć proces aktualizacji połącz swoje urzeądzenie do Wi-Fi. Rozmiar pobieranej paczki wynosi około 1GB. - Connect to Wi-Fi Połącz się z Wi-Fi - Install Zainstaluj - Back Wróć - Loading... Ładowanie... - Reboot Uruchom ponownie - Update failed Aktualizacja nie powiodła się @@ -1287,23 +1105,18 @@ nie zostało ustawione WifiUI - - Scanning for networks... Wyszukiwanie sieci... - CONNECTING... ŁĄCZENIE... - FORGET ZAPOMNIJ - Forget Wi-Fi Network "%1"? Czy chcesz zapomnieć sieć "%1"? diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts index d502c3fce..95880e69c 100644 --- a/selfdrive/ui/translations/main_th.ts +++ b/selfdrive/ui/translations/main_th.ts @@ -4,17 +4,14 @@ AbstractAlert - Close ปิด - Snooze Update เลื่อนการอัปเดต - Reboot and Update รีบูตและอัปเดต @@ -22,67 +19,84 @@ AdvancedNetworking - Back ย้อนกลับ - Enable Tethering ปล่อยฮอตสปอต - Tethering Password รหัสผ่านฮอตสปอต - - EDIT แก้ไข - Enter new tethering password ป้อนรหัสผ่านฮอตสปอตใหม่ - IP Address หมายเลขไอพี - Enable Roaming เปิดใช้งานโรมมิ่ง - APN Setting ตั้งค่า APN - Enter APN ป้อนค่า APN - leave blank for automatic configuration เว้นว่างเพื่อตั้งค่าอัตโนมัติ + + Cellular Metered + ลดการส่งข้อมูลผ่านเซลลูล่าร์ + + + Prevent large data uploads when on a metered connection + ปิดการอัพโหลดข้อมูลขนาดใหญ่เมื่อเชื่อมต่อผ่านเซลลูล่าร์ + + + + AnnotatedCameraWidget + + km/h + กม./ชม. + + + mph + ไมล์/ชม. + + + MAX + สูงสุด + + + SPEED + ความเร็ว + + + LIMIT + จำกัด + ConfirmationDialog - - Ok ตกลง - Cancel ยกเลิก @@ -90,17 +104,14 @@ DeclinePage - You must accept the Terms and Conditions in order to use openpilot. คุณต้องยอมรับเงื่อนไขและข้อตกลง เพื่อใช้งาน openpilot - Back ย้อนกลับ - Decline, uninstall %1 ปฏิเสธ และถอนการติดตั้ง %1 @@ -108,152 +119,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° openpilot ทำการคาลิเบรทอย่างต่อเนื่อง แทบจะไม่จำเป็นต้องทำการรีเซ็ตการคาลิเบรท - 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 +242,26 @@ DriveStats - Drives การขับขี่ - Hours ชั่วโมง - ALL TIME ทั้งหมด - PAST WEEK สัปดาห์ที่ผ่านมา - KM กิโลเมตร - Miles ไมล์ @@ -294,7 +269,6 @@ DriverViewScene - camera starting กำลังเปิดกล้อง @@ -302,12 +276,10 @@ InputDialog - Cancel ยกเลิก - Need at least %n character(s)! ต้องการอย่างน้อย %n ตัวอักษร! @@ -317,22 +289,18 @@ Installer - Installing... กำลังติดตั้ง... - Receiving objects: กำลังรับข้อมูล: - Resolving deltas: การแก้ไขเดลต้า: - Updating files: กำลังอัปเดตไฟล์: @@ -340,27 +308,22 @@ MapETA - eta eta - min นาที - hr ชม. - km กม. - mi ไมล์ @@ -368,22 +331,18 @@ MapInstructions - km กม. - m ม. - mi ไมล์ - ft ฟุต @@ -391,48 +350,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 +391,10 @@ location set MapWindow - Map Loading กำลังโหลดแผนที่ - Waiting for GPS กำลังรอสัญญาณ GPS @@ -453,12 +402,10 @@ location set MultiOptionDialog - Select เลือก - Cancel ยกเลิก @@ -466,72 +413,33 @@ location set Networking - Advanced ขั้นสูง - Enter password ใส่รหัสผ่าน - - for "%1" สำหรับ "%1" - Wrong password รหัสผ่านผิด - - AnnotatedCameraWidget - - - km/h - กม./ชม. - - - - mph - ไมล์/ชม. - - - - - MAX - สูงสุด - - - - - SPEED - ความเร็ว - - - - - LIMIT - จำกัด - - OffroadHome - UPDATE อัปเดต - ALERTS การแจ้งเตือน - ALERT การแจ้งเตือน @@ -539,22 +447,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 โดยการเพิ่มไปยังหน้าจอโฮม เพื่อใช้งานเหมือนเป็นแอปพลิเคชัน @@ -562,32 +466,26 @@ location set PrimeAdWidget - Upgrade Now อัพเกรดเดี๋ยวนี้ - Become a comma prime member at connect.comma.ai สมัครสมาชิก comma prime ได้ที่ connect.comma.ai - PRIME FEATURES: คุณสมบัติของ PRIME: - Remote access การเข้าถึงระยะไกล - 1 year of storage จัดเก็บข้อมูลนาน 1 ปี - Developer perks สิทธิพิเศษสำหรับนักพัฒนา @@ -595,22 +493,18 @@ location set PrimeUserWidget - ✓ SUBSCRIBED ✓ สมัครสำเร็จ - comma prime comma prime - CONNECT.COMMA.AI CONNECT.COMMA.AI - COMMA POINTS คะแนน COMMA @@ -618,41 +512,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 +549,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 +588,6 @@ location set RichTextDialog - Ok ตกลง @@ -718,33 +595,26 @@ location set SettingsWindow - × × - Device อุปกรณ์ - - Network เครือข่าย - Toggles ตัวเลือก - Software ซอฟต์แวร์ - Navigation การนำทาง @@ -752,105 +622,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 +705,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 +720,82 @@ location set Sidebar - - CONNECT เชื่อมต่อ - OFFLINE ออฟไลน์ - - ONLINE ออนไลน์ - ERROR เกิดข้อผิดพลาด - - - TEMP อุณหภูมิ - HIGH สูง - GOOD ดี - OK พอใช้ - VEHICLE รถยนต์ - NO ไม่พบ - PANDA PANDA - GPS จีพีเอส - SEARCH ค้นหา - -- -- - Wi-Fi Wi-Fi - ETH ETH - 2G 2G - 3G 3G - LTE LTE - 5G 5G @@ -983,138 +803,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. - ครั้งสุดท้ายที่ openpilot ตรวจสอบการอัปเดตสำเร็จ ตัวอัปเดตจะทำงานในขณะที่รถดับเครื่องอยู่เท่านั้น + Uninstall %1 + ถอนการติดตั้ง %1 - - Check for Update - ตรวจสอบการอัปเดต + UNINSTALL + ถอนการติดตั้ง - - CHECKING - กำลังตรวจสอบ + Are you sure you want to uninstall? + คุณแน่ใจหรือไม่ว่าต้องการถอนการติดตั้ง? - - Switch Branch - เปลี่ยน Branch + CHECK + ตรวจสอบ - - ENTER - เปลี่ยน + Updates are only downloaded while the car is off. + ตัวอัปเดตจะดำเนินการดาวน์โหลดเมื่อรถดับเครื่องยนต์อยู่เท่านั้น - - - The new branch will be pulled the next time the updater runs. - Branch ใหม่จะถูกติดตั้งในครั้งต่อไปที่ตัวอัปเดตทำงาน + Current Version + เวอร์ชั่นปัจจุบัน - - Enter branch name - ใส่ชื่อ Branch + Download + ดาวน์โหลด - - Uninstall %1 - ถอนการติดตั้ง %1 + Install Update + ติดตั้งตัวอัปเดต - - UNINSTALL - ถอนการติดตั้ง + INSTALL + ติดตั้ง - - Are you sure you want to uninstall? - คุณแน่ใจหรือไม่ว่าต้องการถอนการติดตั้ง? + Target Branch + Branch ที่เลือก - - failed to fetch update - โหลดข้อมูลอัปเดตไม่สำเร็จ + SELECT + เลือก - - - CHECK - ตรวจสอบ + Select a branch + เลือก Branch 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 ไม่พบชื่อผู้ใช้ '%1' บน GitHub @@ -1122,7 +893,6 @@ location set SshToggle - Enable SSH เปิดใช้งาน SSH @@ -1130,22 +900,18 @@ location set TermsPage - Terms & Conditions ข้อตกลงและเงื่อนไข - Decline ปฏิเสธ - Scroll to accept เลื่อนเพื่อตอบรับข้อตกลง - Agree ยอมรับ @@ -1153,125 +919,117 @@ 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 ไมล์ต่อชั่วโมง (50 กม./ชม) - Use Metric System ใช้ระบบเมตริก - Display speed in km/h instead of mph. แสดงความเร็วเป็น กม./ชม. แทน ไมล์/ชั่วโมง - Record and Upload Driver Camera บันทึกและอัปโหลดภาพจากกล้องคนขับ - Upload data from the driver facing camera and help improve the driver monitoring algorithm. อัปโหลดข้อมูลจากกล้องที่หันหน้าไปทางคนขับ และช่วยปรับปรุงอัลกอริธึมการตรวจสอบผู้ขับขี่ - Disengage On Accelerator Pedal ยกเลิกระบบช่วยขับเมื่อเหยียบคันเร่ง - When enabled, pressing the accelerator pedal will disengage openpilot. เมื่อเปิดใช้งาน การกดแป้นคันเร่งจะเป็นการยกเลิกระบบช่วยขับโดย openpilot - Show ETA in 24h Format แสดงเวลา ETA ในรูปแบบ 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 การควบคุมการเร่งและลดความเร็ว + 🌮 End-to-end longitudinal (extremely alpha) 🌮 + 🌮 ควบคุมเร่ง/เบรคแบบ End-to-end (อยู่ขั้นพัฒนา) 🌮 + + + 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 ควบคุมการเร่ง/เบรคแบบ end-to-end โดย openpilot จะขับอย่างที่มนุษย์คิด ระบบยังอยู่ในขั้นทดลอง + + + openpilot longitudinal control is not currently available for this car. + ขณะนี้ยังไม่มีระบบควบคุมการเร่ง/เบรคโดย openpilot สำหรับรถคันนี้ - - openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! - openpilot จะปิดการใช้งานเรดาร์ของรถ และจะเข้าควบคุมการเร่งและเบรก คำเตือน: สิ่งนี้จะปิดระบบ AEB! + Enable experimental longitudinal control to enable this. + เปิดใช้งานระบบควบคุมการเร่ง/เบรคขั้นทดลอง เพื่อเปิดใช้งานสิ่งนี้ 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 การอัปเดตล้มเหลว @@ -1279,23 +1037,18 @@ location set WifiUI - - Scanning for networks... กำลังสแกนหาเครือข่าย... - CONNECTING... กำลังเชื่อมต่อ... - FORGET เลิกใช้ - Forget Wi-Fi Network "%1"? เลิกใช้เครือข่าย Wi-Fi "%1"? diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 1a6027bf7..d1d72b4da 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -23,8 +23,8 @@ static bool calib_frame_to_full_frame(const UIState *s, float in_x, float in_y, const QRectF clip_region{-margin, -margin, s->fb_w + 2 * margin, s->fb_h + 2 * margin}; const vec3 pt = (vec3){{in_x, in_y, in_z}}; - const vec3 Ep = matvecmul3(s->scene.view_from_calib, pt); - const vec3 KEp = matvecmul3(s->wide_camera ? ecam_intrinsic_matrix : fcam_intrinsic_matrix, Ep); + const vec3 Ep = matvecmul3(s->scene.wide_cam ? s->scene.view_from_wide_calib : s->scene.view_from_calib, pt); + const vec3 KEp = matvecmul3(s->scene.wide_cam ? ecam_intrinsic_matrix : fcam_intrinsic_matrix, Ep); // Project. QPointF point = s->car_space_transform.map(QPointF{KEp.v[0] / KEp.v[2], KEp.v[1] / KEp.v[2]}); @@ -121,17 +121,23 @@ static void update_state(UIState *s) { if (sm.updated("liveCalibration")) { auto rpy_list = sm["liveCalibration"].getLiveCalibration().getRpyCalib(); + auto wfde_list = sm["liveCalibration"].getLiveCalibration().getWideFromDeviceEuler(); Eigen::Vector3d rpy; - rpy << rpy_list[0], rpy_list[1], rpy_list[2]; + Eigen::Vector3d wfde; + if (rpy_list.size() == 3) rpy << rpy_list[0], rpy_list[1], rpy_list[2]; + if (wfde_list.size() == 3) wfde << wfde_list[0], wfde_list[1], wfde_list[2]; Eigen::Matrix3d device_from_calib = euler2rot(rpy); + Eigen::Matrix3d wide_from_device = euler2rot(wfde); Eigen::Matrix3d view_from_device; view_from_device << 0,1,0, 0,0,1, 1,0,0; Eigen::Matrix3d view_from_calib = view_from_device * device_from_calib; + Eigen::Matrix3d view_from_wide_calib = view_from_device * wide_from_device * device_from_calib ; for (int i = 0; i < 3; i++) { for (int j = 0; j < 3; j++) { scene.view_from_calib.v[i*3 + j] = view_from_calib(i,j); + scene.view_from_wide_calib.v[i*3 + j] = view_from_wide_calib(i,j); } } scene.calibration_valid = sm["liveCalibration"].getLiveCalibration().getCalStatus() == 1; @@ -167,6 +173,17 @@ static void update_state(UIState *s) { scene.light_sensor = std::max(100.0f - scale * sm["wideRoadCameraState"].getWideRoadCameraState().getExposureValPercent(), 0.0f); } scene.started = sm["deviceState"].getDeviceState().getStarted() && scene.ignition; + + if (sm.updated("carState")) { + float v_ego = sm["carState"].getCarState().getVEgo(); + // TODO: support replays without ecam by using fcam + // Wide or narrow cam dependent on speed + if ((v_ego < 10) || s->wide_cam_only) { + scene.wide_cam = true; + } else if (v_ego > 15) { + scene.wide_cam = false; + } + } } void ui_update_params(UIState *s) { @@ -197,7 +214,7 @@ void UIState::updateStatus() { if (scene.started) { status = STATUS_DISENGAGED; scene.started_frame = sm->frame; - wide_camera = Params().getBool("WideCameraOnly"); + wide_cam_only = Params().getBool("WideCameraOnly"); } started_prev = scene.started; emit offroadTransition(!scene.started); @@ -219,7 +236,7 @@ UIState::UIState(QObject *parent) : QObject(parent) { }); Params params; - wide_camera = params.getBool("WideCameraOnly"); + wide_cam_only = params.getBool("WideCameraOnly"); prime_type = std::atoi(params.get("PrimeType").c_str()); language = QString::fromStdString(params.get("LanguageSetting")); diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index f60c26b59..5a51dda8f 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -87,7 +87,9 @@ const QColor bg_colors [] = { typedef struct UIScene { bool calibration_valid = false; + bool wide_cam = true; mat3 view_from_calib = DEFAULT_CALIBRATION; + mat3 view_from_wide_calib = DEFAULT_CALIBRATION; cereal::PandaState::PandaType pandaType; // modelV2 @@ -130,7 +132,7 @@ public: QString language; QTransform car_space_transform; - bool wide_camera; + bool wide_cam_only; signals: void uiUpdate(const UIState &s); diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 57f957cff..c261a92a8 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -280,17 +280,25 @@ class Updater: # Write out current and new version info def get_description(basedir: str) -> str: + if not os.path.exists(basedir): + return "" + version = "" branch = "" commit = "" + commit_date = "" try: branch = self.get_branch(basedir) - commit = self.get_commit_hash(basedir) + commit = self.get_commit_hash(basedir)[:7] with open(os.path.join(basedir, "common", "version.h")) as f: version = f.read().split('"')[1] + + commit_unix_ts = run(["git", "show", "-s", "--format=%ct", "HEAD"], basedir).rstrip() + dt = datetime.datetime.fromtimestamp(int(commit_unix_ts)) + commit_date = dt.strftime("%b %d") except Exception: - pass - return f"{version} / {branch} / {commit[:7]}" + cloudlog.exception("updater.get_description") + return f"{version} / {branch} / {commit} / {commit_date}" self.params.put("UpdaterCurrentDescription", get_description(BASEDIR)) self.params.put("UpdaterCurrentReleaseNotes", parse_release_notes(BASEDIR)) self.params.put("UpdaterNewDescription", get_description(FINALIZED)) diff --git a/tools/cabana/.gitignore b/tools/cabana/.gitignore index d7a552eab..73879ab05 100644 --- a/tools/cabana/.gitignore +++ b/tools/cabana/.gitignore @@ -4,4 +4,4 @@ moc_* _cabana settings car_fingerprint_to_dbc.json - +tests/_test_cabana diff --git a/tools/cabana/SConscript b/tools/cabana/SConscript index 4e4e11dbd..b7321e1f8 100644 --- a/tools/cabana/SConscript +++ b/tools/cabana/SConscript @@ -18,5 +18,9 @@ cabana_env = qt_env.Clone() prev_moc_path = cabana_env['QT_MOCHPREFIX'] cabana_env['QT_MOCHPREFIX'] = os.path.dirname(prev_moc_path) + '/cabana/moc_' cabana_env.Execute('./generate_dbc_json.py --out car_fingerprint_to_dbc.json') -cabana_env.Program('_cabana', ['cabana.cc', 'mainwin.cc', 'binaryview.cc', 'chartswidget.cc', 'historylog.cc', 'videowidget.cc', 'signaledit.cc', 'dbcmanager.cc', +cabana_lib = cabana_env.Library("cabana_lib", ['mainwin.cc', 'binaryview.cc', 'chartswidget.cc', 'historylog.cc', 'videowidget.cc', 'signaledit.cc', 'dbcmanager.cc', 'canmessages.cc', 'messageswidget.cc', 'settings.cc', 'detailwidget.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks) +cabana_env.Program('_cabana', ['cabana.cc', cabana_lib], LIBS=cabana_libs, FRAMEWORKS=base_frameworks) + +if GetOption('test'): + cabana_env.Program('tests/_test_cabana', ['tests/test_runner.cc', 'tests/test_cabana.cc', cabana_lib], LIBS=[cabana_libs]) diff --git a/tools/cabana/binaryview.cc b/tools/cabana/binaryview.cc index eee3f9098..91353e972 100644 --- a/tools/cabana/binaryview.cc +++ b/tools/cabana/binaryview.cc @@ -13,12 +13,6 @@ const int CELL_HEIGHT = 30; -static std::pair getSignalRange(const Signal *s) { - int from = s->is_little_endian ? s->start_bit : bigEndianBitIndex(s->start_bit); - int to = from + s->size - 1; - return {from, to}; -} - BinaryView::BinaryView(QWidget *parent) : QTableView(parent) { model = new BinaryViewModel(this); setModel(model); @@ -26,13 +20,15 @@ BinaryView::BinaryView(QWidget *parent) : QTableView(parent) { setItemDelegate(delegate); horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); horizontalHeader()->hide(); - verticalHeader()->setSectionResizeMode(QHeaderView::Stretch); + verticalHeader()->setSectionResizeMode(QHeaderView::ResizeToContents); setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); setMouseTracking(true); + setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Minimum); +} - QObject::connect(model, &QAbstractItemModel::modelReset, [this]() { - setFixedHeight((CELL_HEIGHT + 1) * std::min(model->rowCount(), 8) + 2); - }); +QSize BinaryView::sizeHint() const { + QSize sz = QTableView::sizeHint(); + return {sz.width(), model->rowCount() <= 8 ? ((CELL_HEIGHT + 1) * model->rowCount() + 2) : sz.height()}; } void BinaryView::highlight(const Signal *sig) { @@ -76,9 +72,10 @@ void BinaryView::mousePressEvent(QMouseEvent *event) { void BinaryView::mouseMoveEvent(QMouseEvent *event) { if (auto index = indexAt(event->pos()); index.isValid()) { auto item = (BinaryViewModel::Item *)index.internalPointer(); - highlight(item->sig); - item->sig ? QToolTip::showText(event->globalPos(), item->sig->name.c_str(), this, rect()) - : QToolTip::hideText(); + const Signal *sig = item->sigs.isEmpty() ? nullptr : item->sigs.back(); + highlight(sig); + sig ? QToolTip::showText(event->globalPos(), sig->name.c_str(), this, rect()) + : QToolTip::hideText(); } QTableView::mouseMoveEvent(event); } @@ -92,7 +89,8 @@ void BinaryView::mouseReleaseEvent(QMouseEvent *event) { if (auto sig = getResizingSignal()) { auto [sig_from, sig_to] = getSignalRange(sig); if (from >= sig_from && to <= sig_to) { // reduce size - emit(from == sig_from ? resizeSignal(sig, to, sig_to) : resizeSignal(sig, sig_from, from)); + emit(from == sig_from ? resizeSignal(sig, std::min(to + 1, sig_to), sig_to) + : resizeSignal(sig, sig_from, std::max(from - 1, sig_from))); } else { // increase size emit resizeSignal(sig, std::min(from, sig_from), std::max(to, sig_to)); } @@ -112,9 +110,9 @@ void BinaryView::leaveEvent(QEvent *event) { void BinaryView::setMessage(const QString &message_id) { msg_id = message_id; model->setMessage(message_id); - resizeRowsToContents(); clearSelection(); updateState(); + updateGeometry(); } void BinaryView::updateState() { @@ -124,16 +122,32 @@ void BinaryView::updateState() { const Signal *BinaryView::getResizingSignal() const { if (anchor_index.isValid()) { auto item = (const BinaryViewModel::Item *)anchor_index.internalPointer(); - if (item && item->sig) { + if (item && item->sigs.size() > 0) { int archor_pos = anchor_index.row() * 8 + anchor_index.column(); - auto [sig_from, sig_to] = getSignalRange(item->sig); - if (archor_pos == sig_from || archor_pos == sig_to) - return item->sig; + for (auto s : item->sigs) { + auto [sig_from, sig_to] = getSignalRange(s); + if (archor_pos == sig_from || archor_pos == sig_to) + return s; + } } } return nullptr; } +QSet BinaryView::getOverlappingSignals() const { + QSet overlapping; + for (int i = 0; i < model->rowCount(); ++i) { + for (int j = 0; j < model->columnCount() - 1; ++j) { + auto item = (const BinaryViewModel::Item *)model->index(i, j).internalPointer(); + if (item && item->sigs.size() > 1) { + for (auto s : item->sigs) + overlapping.insert(s); + } + } + } + return overlapping; +} + // BinaryViewModel void BinaryViewModel::setMessage(const QString &message_id) { @@ -162,7 +176,7 @@ void BinaryViewModel::setMessage(const QString &message_id) { sig.is_little_endian ? items[idx].is_msb = true : items[idx].is_lsb = true; } items[idx].bg_color = getColor(i); - items[idx].sig = &dbc_msg->sigs[i]; + items[idx].sigs.push_back(&dbc_msg->sigs[i]); } } } @@ -212,7 +226,7 @@ void BinaryViewModel::updateState() { QVariant BinaryViewModel::headerData(int section, Qt::Orientation orientation, int role) const { if (orientation == Qt::Vertical) { switch (role) { - case Qt::DisplayRole: return section + 1; + case Qt::DisplayRole: return section; case Qt::SizeHintRole: return QSize(30, CELL_HEIGHT); case Qt::TextAlignmentRole: return Qt::AlignCenter; } @@ -240,7 +254,8 @@ void BinaryItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &op BinaryView *bin_view = (BinaryView *)parent(); painter->save(); - bool hover = item->sig && bin_view->hoveredSignal() == item->sig; + bool hover = std::find_if(item->sigs.begin(), item->sigs.end(), [=](auto s) { return s == bin_view->hoveredSignal(); }) != + item->sigs.end(); // background QColor bg_color = hover ? hoverColor(item->bg_color) : item->bg_color; if (option.state & QStyle::State_Selected) { diff --git a/tools/cabana/binaryview.h b/tools/cabana/binaryview.h index 8c1a58201..060a2eef7 100644 --- a/tools/cabana/binaryview.h +++ b/tools/cabana/binaryview.h @@ -1,5 +1,7 @@ #pragma once +#include +#include #include #include @@ -38,7 +40,7 @@ public: bool is_msb = false; bool is_lsb = false; QString val = "0"; - const Signal *sig = nullptr; + QList sigs; }; private: @@ -58,6 +60,8 @@ public: void updateState(); void highlight(const Signal *sig); const Signal *hoveredSignal() const { return hovered_sig; } + QSet getOverlappingSignals() const; + QSize sizeHint() const override; signals: void signalHovered(const Signal *sig); diff --git a/tools/cabana/canmessages.cc b/tools/cabana/canmessages.cc index defeacd75..3ffc29916 100644 --- a/tools/cabana/canmessages.cc +++ b/tools/cabana/canmessages.cc @@ -28,7 +28,7 @@ bool CANMessages::loadRoute(const QString &route, const QString &data_dir, bool replay = new Replay(route, {"can", "roadEncodeIdx", "carParams"}, {}, nullptr, use_qcam ? REPLAY_FLAG_QCAMERA : 0, data_dir, this); replay->setSegmentCacheLimit(settings.cached_segment_limit); replay->installEventFilter(event_filter, this); - QObject::connect(replay, &Replay::segmentsMerged, this, &CANMessages::segmentsMerged); + QObject::connect(replay, &Replay::segmentsMerged, this, &CANMessages::eventsMerged); if (replay->load()) { replay->start(); return true; @@ -54,50 +54,35 @@ QList CANMessages::findSignalValues(const QString &id, const Signal *si double val = get_raw_value((uint8_t *)c.getDat().begin(), c.getDat().size(), *signal); if ((flag == EQ && val == value) || (flag == LT && val < value) || (flag == GT && val > value)) { ret.push_back({(evt->mono_time / (double)1e9) - can->routeStartTime(), val}); + if (ret.size() >= max_count) + return ret; } - if (ret.size() >= max_count) - return ret; } } } return ret; } -void CANMessages::process(QHash> *messages) { +void CANMessages::process(QHash *messages) { for (auto it = messages->begin(); it != messages->end(); ++it) { - auto &msgs = can_msgs[it.key()]; - const auto &new_msgs = it.value(); - if (new_msgs.size() == settings.can_msg_log_size || msgs.empty()) { - msgs = std::move(new_msgs); - } else { - msgs.insert(msgs.begin(), std::make_move_iterator(new_msgs.begin()), std::make_move_iterator(new_msgs.end())); - while (msgs.size() >= settings.can_msg_log_size) { - msgs.pop_back(); - } - } + can_msgs[it.key()] = it.value(); } delete messages; - - if (current_sec < begin_sec || current_sec > end_sec) { - // loop replay in selected range. - seekTo(begin_sec); - } else { - emit updated(); - } + emit updated(); } bool CANMessages::eventFilter(const Event *event) { - static double prev_update_sec = 0; - // drop packets when the GUI thread is calling seekTo. to make sure the current_sec is accurate. - if (!seeking && event->which == cereal::Event::Which::CAN) { - if (!received_msgs) { - received_msgs.reset(new QHash>); - received_msgs->reserve(1000); + static std::unique_ptr> new_msgs; + static double prev_update_ts = 0; + + if (event->which == cereal::Event::Which::CAN) { + if (!new_msgs) { + new_msgs.reset(new QHash); + new_msgs->reserve(1000); } - current_sec = (event->mono_time - replay->routeStartTime()) / (double)1e9; - if (counters_begin_sec > current_sec) { - // clear counters + double current_sec = replay->currentSeconds(); + if (counters_begin_sec == 0) { counters.clear(); counters_begin_sec = current_sec; } @@ -105,8 +90,10 @@ bool CANMessages::eventFilter(const Event *event) { auto can_events = event->event.getCan(); for (const auto &c : can_events) { QString id = QString("%1:%2").arg(c.getSrc()).arg(c.getAddress(), 1, 16); - auto &list = (*received_msgs)[id]; - while (list.size() >= settings.can_msg_log_size) { + + std::lock_guard lk(lock); + auto &list = received_msgs[id]; + while (list.size() > settings.can_msg_log_size) { list.pop_back(); } CanData &data = list.emplace_front(); @@ -119,48 +106,27 @@ bool CANMessages::eventFilter(const Event *event) { if (double delta = (current_sec - counters_begin_sec); delta > 0) { data.freq = count / delta; } + (*new_msgs)[id] = data; } - if (current_sec < prev_update_sec || (current_sec - prev_update_sec) > 1.0 / settings.fps) { - prev_update_sec = current_sec; + double ts = millis_since_boot(); + if ((ts - prev_update_ts) > (1000.0 / settings.fps)) { + prev_update_ts = ts; // use pointer to avoid data copy in queued connection. - emit received(received_msgs.release()); + emit received(new_msgs.release()); } } return true; } -void CANMessages::seekTo(double ts) { - seeking = true; - replay->seekTo(ts, false); - seeking = false; +const std::deque CANMessages::messages(const QString &id) { + std::lock_guard lk(lock); + return received_msgs[id]; } -void CANMessages::setRange(double min, double max) { - if (begin_sec != min || end_sec != max) { - begin_sec = min; - end_sec = max; - is_zoomed = begin_sec != event_begin_sec || end_sec != event_end_sec; - emit rangeChanged(min, max); - } -} - -void CANMessages::segmentsMerged() { - auto events = replay->events(); - if (!events || events->empty()) return; - - auto it = std::find_if(events->begin(), events->end(), [=](const Event *e) { return e->which == cereal::Event::Which::CAN; }); - event_begin_sec = it == events->end() ? 0 : ((*it)->mono_time - replay->routeStartTime()) / (double)1e9; - event_end_sec = double(events->back()->mono_time - replay->routeStartTime()) / 1e9; - if (!is_zoomed) { - begin_sec = event_begin_sec; - end_sec = event_end_sec; - } - emit eventsMerged(); -} - -void CANMessages::resetRange() { - setRange(event_begin_sec, event_end_sec); +void CANMessages::seekTo(double ts) { + replay->seekTo(ts, false); + counters_begin_sec = 0; } void CANMessages::settingChanged() { diff --git a/tools/cabana/canmessages.h b/tools/cabana/canmessages.h index d1bb1b73b..5fbccdbe1 100644 --- a/tools/cabana/canmessages.h +++ b/tools/cabana/canmessages.h @@ -2,7 +2,7 @@ #include #include -#include +#include #include #include @@ -29,20 +29,16 @@ public: ~CANMessages(); bool loadRoute(const QString &route, const QString &data_dir, bool use_qcam); void seekTo(double ts); - void resetRange(); - void setRange(double min, double max); QList findSignalValues(const QString&id, const Signal* signal, double value, FindFlags flag, int max_count); bool eventFilter(const Event *event); - inline std::pair range() const { return {begin_sec, end_sec}; } inline QString route() const { return routeName; } inline QString carFingerprint() const { return replay->carFingerprint().c_str(); } inline double totalSeconds() const { return replay->totalSeconds(); } inline double routeStartTime() const { return replay->routeStartTime() / (double)1e9; } - inline double currentSec() const { return current_sec; } - inline bool isZoomed() const { return is_zoomed; } - inline const std::deque &messages(const QString &id) { return can_msgs[id]; } - inline const CanData &lastMessage(const QString &id) { return can_msgs[id].front(); } + inline double currentSec() const { return replay->currentSeconds(); } + const std::deque messages(const QString &id); + inline const CanData &lastMessage(const QString &id) { return can_msgs[id]; } inline const std::vector *events() const { return replay->events(); } inline void setSpeed(float speed) { replay->setSpeed(speed); } @@ -52,32 +48,23 @@ public: signals: void eventsMerged(); - void rangeChanged(double min, double max); void updated(); - void received(QHash> *); + void received(QHash *); public: - QMap> can_msgs; - std::unique_ptr>> received_msgs = nullptr; + QMap can_msgs; protected: - void process(QHash> *); - void segmentsMerged(); + void process(QHash *); void settingChanged(); - std::atomic current_sec = 0.; - std::atomic seeking = false; - - double begin_sec = 0; - double end_sec = 0; - double event_begin_sec = 0; - double event_end_sec = 0; - bool is_zoomed = false; QString routeName; Replay *replay = nullptr; - double counters_begin_sec = std::numeric_limits::max(); + std::mutex lock; + std::atomic counters_begin_sec = 0; QHash counters; + QHash> received_msgs; }; inline QString toHex(const QByteArray &dat) { diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index f0bef36f4..21fd71b8e 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -1,6 +1,7 @@ #include "tools/cabana/chartswidget.h" #include +#include #include #include #include @@ -57,74 +58,117 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) { QObject::connect(dbc(), &DBCManager::DBCFileChanged, [this]() { removeAll(nullptr); }); QObject::connect(dbc(), &DBCManager::signalRemoved, this, &ChartsWidget::removeAll); - QObject::connect(dbc(), &DBCManager::signalUpdated, [this](const Signal *sig) { - for (auto chart : charts) { - if (chart->signal == sig) { - chart->chart_view->updateSeries(); - } - } - }); - QObject::connect(dbc(), &DBCManager::msgUpdated, [this](const QString &id) { - for (auto chart : charts) { - if (chart->id == id) - chart->updateTitle(); + QObject::connect(dbc(), &DBCManager::signalUpdated, this, &ChartsWidget::signalUpdated); + QObject::connect(dbc(), &DBCManager::msgUpdated, [this](const QString &msg_id) { + for (auto c : charts) { + if (c->id == msg_id) c->updateTitle(); } }); - - QObject::connect(can, &CANMessages::rangeChanged, [this]() { updateTitleBar(); }); - QObject::connect(reset_zoom_btn, &QPushButton::clicked, can, &CANMessages::resetRange); + QObject::connect(can, &CANMessages::eventsMerged, this, &ChartsWidget::eventsMerged); + QObject::connect(can, &CANMessages::updated, this, &ChartsWidget::updateState); QObject::connect(remove_all_btn, &QPushButton::clicked, [this]() { removeAll(); }); + QObject::connect(reset_zoom_btn, &QPushButton::clicked, this, &ChartsWidget::zoomReset); QObject::connect(dock_btn, &QPushButton::clicked, [this]() { emit dock(!docking); docking = !docking; updateTitleBar(); }); - QObject::connect(&settings, &Settings::changed, [this]() { - for (auto chart : charts) { - chart->setHeight(settings.chart_height); +} + +void ChartsWidget::eventsMerged() { + if (auto events = can->events(); events && !events->empty()) { + auto it = std::find_if(events->begin(), events->end(), [=](const Event *e) { return e->which == cereal::Event::Which::CAN; }); + event_range.first = it == events->end() ? 0 : (*it)->mono_time / (double)1e9 - can->routeStartTime(); + event_range.second = it == events->end() ? 0 : events->back()->mono_time / (double)1e9 - can->routeStartTime(); + if (display_range.first == 0 && event_range.second == 0) { + display_range.first = event_range.first; + display_range.second = std::min(event_range.first + settings.max_chart_x_range, event_range.second); } - }); + } +} + +void ChartsWidget::zoomIn(double min, double max) { + zoomed_range = {min, max}; + is_zoomed = zoomed_range != display_range; + updateTitleBar(); + emit rangeChanged(min, max, is_zoomed); + updateState(); +} + +void ChartsWidget::zoomReset() { + zoomIn(display_range.first, display_range.second); +} + +void ChartsWidget::updateState() { + if (charts.isEmpty()) return; + + const double current_sec = can->currentSec(); + if (is_zoomed) { + if (current_sec < zoomed_range.first || current_sec >= zoomed_range.second) { + can->seekTo(zoomed_range.first); + } + } else { + auto prev_range = display_range; + if (current_sec < display_range.first || current_sec >= (display_range.second - 5)) { + // line marker reached the end, or seeked to a timestamp out of range. + display_range.first = current_sec - 5; + } + display_range.first = std::max(display_range.first, event_range.first); + display_range.second = std::min(display_range.first + settings.max_chart_x_range, event_range.second); + if (prev_range != display_range) { + for (auto c : charts) + c->chart_view->updateSeries(display_range); + } + } + + const auto &range = is_zoomed ? zoomed_range : display_range; + for (auto c : charts) { + c->chart_view->setRange(range.first, range.second); + c->chart_view->updateLineMarker(current_sec); + } } void ChartsWidget::updateTitleBar() { title_bar->setVisible(!charts.isEmpty()); if (charts.isEmpty()) return; - // show select range - range_label->setVisible(can->isZoomed()); - reset_zoom_btn->setEnabled(can->isZoomed()); - if (can->isZoomed()) { - auto [min, max] = can->range(); - range_label->setText(tr("%1 - %2").arg(min, 0, 'f', 2).arg(max, 0, 'f', 2)); + range_label->setVisible(is_zoomed); + reset_zoom_btn->setEnabled(is_zoomed); + if (is_zoomed) { + range_label->setText(tr("%1 - %2").arg(zoomed_range.first, 0, 'f', 2).arg(zoomed_range.second, 0, 'f', 2)); } - title_label->setText(tr("Charts (%1)").arg(charts.size())); dock_btn->setText(docking ? "⬈" : "⬋"); dock_btn->setToolTip(docking ? tr("Undock charts") : tr("Dock charts")); } -void ChartsWidget::addChart(const QString &id, const Signal *sig) { +void ChartsWidget::showChart(const QString &id, const Signal *sig, bool show) { auto it = std::find_if(charts.begin(), charts.end(), [=](auto c) { return c->id == id && c->signal == sig; }); - if (it == charts.end()) { + if (it != charts.end()) { + if (!show) removeChart((*it)); + } else if (show) { auto chart = new ChartWidget(id, sig, this); - QObject::connect(chart, &ChartWidget::remove, this, &ChartsWidget::removeChart); + chart->chart_view->updateSeries(display_range); + QObject::connect(chart, &ChartWidget::remove, [=]() { removeChart(chart); }); + QObject::connect(chart->chart_view, &ChartView::zoomIn, this, &ChartsWidget::zoomIn); + QObject::connect(chart->chart_view, &ChartView::zoomReset, this, &ChartsWidget::zoomReset); charts_layout->insertWidget(0, chart); charts.push_back(chart); + emit chartOpened(chart->id, chart->signal); } updateTitleBar(); } -void ChartsWidget::removeChart(const QString &msg_id, const Signal *sig) { - QMutableListIterator it(charts); - while (it.hasNext()) { - auto c = it.next(); - if (c->id == msg_id && c->signal == sig) { - c->deleteLater(); - it.remove(); - break; - } - } +bool ChartsWidget::isChartOpened(const QString &id, const Signal *sig) { + auto it = std::find_if(charts.begin(), charts.end(), [=](auto c) { return c->id == id && c->signal == sig; }); + return it != charts.end(); +} + +void ChartsWidget::removeChart(ChartWidget *chart) { + charts.removeOne(chart); + chart->deleteLater(); updateTitleBar(); + emit chartClosed(chart->id, chart->signal); } void ChartsWidget::removeAll(const Signal *sig) { @@ -133,12 +177,23 @@ void ChartsWidget::removeAll(const Signal *sig) { auto c = it.next(); if (sig == nullptr || c->signal == sig) { c->deleteLater(); + emit chartClosed(c->id, c->signal); it.remove(); } } updateTitleBar(); } +void ChartsWidget::signalUpdated(const Signal *sig) { + for (auto c : charts) { + if (c->signal == sig) { + c->updateTitle(); + c->chart_view->updateSeries(display_range); + c->chart_view->setRange(display_range.first, display_range.second, true); + } + } +} + bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) { if (obj != this && event->type() == QEvent::Close) { emit dock_btn->clicked(); @@ -154,31 +209,45 @@ ChartWidget::ChartWidget(const QString &id, const Signal *sig, QWidget *parent) main_layout->setSpacing(0); main_layout->setContentsMargins(0, 0, 0, 0); - QWidget *header = new QWidget(this); - header->setStyleSheet("background-color:white"); - QHBoxLayout *header_layout = new QHBoxLayout(header); + header = new QWidget(this); + QGridLayout *header_layout = new QGridLayout(header); header_layout->setContentsMargins(11, 11, 11, 0); - title = new QLabel(tr("%1 %2").arg(dbc()->msg(id)->name.c_str()).arg(id)); - header_layout->addWidget(title); - header_layout->addStretch(); - - QPushButton *remove_btn = new QPushButton("✖", this); - remove_btn->setFixedSize(30, 30); + msg_name_label = new QLabel(this); + msg_name_label->setTextFormat(Qt::RichText); + header_layout->addWidget(msg_name_label, 0, 0, Qt::AlignLeft); + sig_name_label = new QLabel(this); + header_layout->addWidget(sig_name_label, 0, 1, Qt::AlignCenter); //, 0, Qt::AlignCenter); + + remove_btn = new QPushButton("✖", this); + remove_btn->setFixedSize(20, 20); remove_btn->setToolTip(tr("Remove chart")); - QObject::connect(remove_btn, &QPushButton::clicked, [=]() { emit remove(id, sig); }); - header_layout->addWidget(remove_btn); + header_layout->addWidget(remove_btn, 0, 2, Qt::AlignRight); main_layout->addWidget(header); chart_view = new ChartView(id, sig, this); - chart_view->setFixedHeight(settings.chart_height); main_layout->addWidget(chart_view); main_layout->addStretch(); setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Fixed); + updateTitle(); + updateFromSettings(); + + QObject::connect(remove_btn, &QPushButton::clicked, [=]() { emit remove(id, sig); }); + QObject::connect(&settings, &Settings::changed, this, &ChartWidget::updateFromSettings); } void ChartWidget::updateTitle() { - title->setText(tr("%1 %2").arg(dbc()->msg(id)->name.c_str()).arg(id)); + msg_name_label->setText(tr("%1 %2").arg(dbc()->msg(id)->name.c_str()).arg(id)); + sig_name_label->setText(signal->name.c_str()); +} + +void ChartWidget::updateFromSettings() { + header->setStyleSheet(settings.chart_theme == 0 ? "background-color:white" : "background-color:#23242c"); + QString color_style = settings.chart_theme == 0 ? "color:black" : "color:white"; + sig_name_label->setStyleSheet("font-weight:bold;" + color_style); + msg_name_label->setStyleSheet(color_style); + remove_btn->setStyleSheet(color_style); + chart_view->updateFromSettings(); } // ChartView @@ -186,24 +255,24 @@ void ChartWidget::updateTitle() { ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent) : id(id), signal(sig), QChartView(nullptr, parent) { QLineSeries *series = new QLineSeries(); - series->setUseOpenGL(true); QChart *chart = new QChart(); - chart->setTitle(sig->name.c_str()); + chart->setBackgroundRoundness(0); chart->addSeries(series); chart->createDefaultAxes(); chart->legend()->hide(); - QFont font; - font.setBold(true); - chart->setTitleFont(font); chart->setMargins({0, 0, 0, 0}); chart->layout()->setContentsMargins(0, 0, 0, 0); track_line = new QGraphicsLineItem(chart); - track_line->setPen(QPen(Qt::gray, 1, Qt::DashLine)); - value_text = new QGraphicsSimpleTextItem(chart); - value_text->setBrush(Qt::gray); + track_line->setZValue(chart->zValue() + 10); + track_line->setPen(QPen(Qt::darkGray, 1, Qt::DashLine)); + track_ellipse = new QGraphicsEllipseItem(chart); + track_ellipse->setZValue(chart->zValue() + 10); + track_ellipse->setBrush(Qt::darkGray); + value_text = new QGraphicsTextItem(chart); + value_text->setZValue(chart->zValue() + 10); line_marker = new QGraphicsLineItem(chart); - line_marker->setPen(QPen(Qt::black, 2)); + line_marker->setZValue(chart->zValue() + 10); setChart(chart); @@ -220,16 +289,24 @@ ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent) timer->setSingleShot(true); timer->callOnTimeout(this, &ChartView::adjustChartMargins); - QObject::connect(can, &CANMessages::updated, this, &ChartView::updateState); - QObject::connect(can, &CANMessages::rangeChanged, this, &ChartView::rangeChanged); - QObject::connect(can, &CANMessages::eventsMerged, this, &ChartView::updateSeries); - QObject::connect(dynamic_cast(chart->axisX()), &QValueAxis::rangeChanged, can, &CANMessages::setRange); QObject::connect(chart, &QChart::plotAreaChanged, [=](const QRectF &plotArea) { // use a singleshot timer to avoid recursion call. timer->start(); }); +} + +void ChartView::updateFromSettings() { + setFixedHeight(settings.chart_height); + chart()->setTheme(settings.chart_theme == 0 ? QChart::ChartThemeLight : QChart::QChart::ChartThemeDark); + line_marker->setPen(QPen(settings.chart_theme == 0 ? Qt::black : Qt::white, 2)); +} - updateSeries(); +void ChartView::setRange(double min, double max, bool force_update) { + auto axis_x = dynamic_cast(chart()->axisX()); + if (force_update || (min != axis_x->min() || max != axis_x->max())) { + axis_x->setRange(min, max); + updateAxisY(); + } } void ChartView::adjustChartMargins() { @@ -241,18 +318,17 @@ void ChartView::adjustChartMargins() { } } -void ChartWidget::setHeight(int height) { - chart_view->setFixedHeight(height); -} - -void ChartView::updateState() { +void ChartView::updateLineMarker(double current_sec) { auto axis_x = dynamic_cast(chart()->axisX()); - int x = chart()->plotArea().left() + chart()->plotArea().width() * (can->currentSec() - axis_x->min()) / (axis_x->max() - axis_x->min()); - line_marker->setLine(x, 0, x, height()); + int x = chart()->plotArea().left() + + chart()->plotArea().width() * (current_sec - axis_x->min()) / (axis_x->max() - axis_x->min()); + if (int(line_marker->line().x1()) != x) { + line_marker->setLine(x, 0, x, height()); + chart()->update(); + } } -void ChartView::updateSeries() { - chart()->setTitle(signal->name.c_str()); +void ChartView::updateSeries(const std::pair &range) { auto events = can->events(); if (!events) return; @@ -261,15 +337,18 @@ void ChartView::updateSeries() { uint32_t address = l[1].toUInt(nullptr, 16); vals.clear(); - vals.reserve(3 * 60 * 100); - uint64_t route_start_time = can->routeStartTime(); - for (auto &evt : *events) { - if (evt->which == cereal::Event::Which::CAN) { - for (auto c : evt->event.getCan()) { + vals.reserve((range.second - range.first) * 100); // [n]minutes * 100hz + double route_start_time = can->routeStartTime(); + Event begin_event(cereal::Event::Which::INIT_DATA, (route_start_time + range.first) * 1e9); + auto begin = std::lower_bound(events->begin(), events->end(), &begin_event, Event::lessThan()); + double end_ns = (route_start_time + range.second) * 1e9; + for (auto it = begin; it != events->end() && (*it)->mono_time <= end_ns; ++it) { + if ((*it)->which == cereal::Event::Which::CAN) { + for (auto c : (*it)->event.getCan()) { if (bus == c.getSrc() && address == c.getAddress()) { auto dat = c.getDat(); double value = get_raw_value((uint8_t *)dat.begin(), dat.size(), *signal); - double ts = (evt->mono_time / (double)1e9) - route_start_time; // seconds + double ts = ((*it)->mono_time / (double)1e9) - route_start_time; // seconds vals.push_back({ts, value}); } } @@ -277,101 +356,82 @@ void ChartView::updateSeries() { } QLineSeries *series = (QLineSeries *)chart()->series()[0]; series->replace(vals); - series->setPointLabelsColor(Qt::black); - auto [begin, end] = can->range(); - chart()->axisX()->setRange(begin, end); - updateAxisY(); -} - -void ChartView::rangeChanged(qreal min, qreal max) { - auto axis_x = dynamic_cast(chart()->axisX()); - if (axis_x->min() != min || axis_x->max() != max) { - axis_x->setRange(min, max); - } - updateAxisY(); } // auto zoom on yaxis void ChartView::updateAxisY() { const auto axis_x = dynamic_cast(chart()->axisX()); const auto axis_y = dynamic_cast(chart()->axisY()); - // vals is a sorted list auto begin = std::lower_bound(vals.begin(), vals.end(), axis_x->min(), [](auto &p, double x) { return p.x() < x; }); if (begin == vals.end()) return; auto end = std::upper_bound(vals.begin(), vals.end(), axis_x->max(), [](double x, auto &p) { return x < p.x(); }); const auto [min, max] = std::minmax_element(begin, end, [](auto &p1, auto &p2) { return p1.y() < p2.y(); }); - if (min->y() == max->y()) { - if (max->y() < 0) { - axis_y->setRange(max->y(), 0); - } else { - axis_y->setRange(0, max->y() == 0 ? 1 : max->y()); - } - } else { - axis_y->setRange(min->y(), max->y()); - } + (min->y() == max->y()) ? axis_y->setRange(min->y() - 1, max->y() + 1) + : axis_y->setRange(min->y(), max->y()); } void ChartView::enterEvent(QEvent *event) { track_line->setVisible(true); value_text->setVisible(true); + track_ellipse->setVisible(true); QChartView::enterEvent(event); } void ChartView::leaveEvent(QEvent *event) { track_line->setVisible(false); value_text->setVisible(false); + track_ellipse->setVisible(false); QChartView::leaveEvent(event); } void ChartView::mouseReleaseEvent(QMouseEvent *event) { auto rubber = findChild(); if (event->button() == Qt::LeftButton && rubber && rubber->isVisible()) { - auto [begin, end] = can->range(); + rubber->hide(); + QRectF rect = rubber->geometry().normalized(); + rect.translate(-chart()->plotArea().topLeft()); + const auto axis_x = dynamic_cast(chart()->axisX()); + double min = axis_x->min() + (rect.left() / chart()->plotArea().width()) * (axis_x->max() - axis_x->min()); + double max = axis_x->min() + (rect.right() / chart()->plotArea().width()) * (axis_x->max() - axis_x->min()); if (rubber->width() <= 0) { - double seek_to = begin + ((event->pos().x() - chart()->plotArea().x()) / chart()->plotArea().width()) * (end - begin); - can->seekTo(seek_to); - } else if (((double)rubber->width() / chart()->plotArea().width()) * (end - begin) < 0.5) { - // don't zoom if selected range is less than 0.5s - rubber->hide(); - event->accept(); - return; + // no rubber dragged, seek to mouse position + can->seekTo(min); + } else if ((max - min) >= 0.5) { + // zoom in if selected range is greater than 0.5s + emit zoomIn(min, max); } } else if (event->button() == Qt::RightButton) { - // reset zoom - if (can->isZoomed()) { - can->resetRange(); - event->accept(); - return; - } + emit zoomReset(); } - QChartView::mouseReleaseEvent(event); - line_marker->setVisible(true); + event->accept(); } void ChartView::mouseMoveEvent(QMouseEvent *ev) { auto rubber = findChild(); - bool show = !(rubber && rubber->isVisible()); - - if (show) { + bool is_zooming = rubber && rubber->isVisible(); + if (!is_zooming) { const auto plot_area = chart()->plotArea(); - float x = std::clamp((float)ev->pos().x(), (float)plot_area.left(), (float)plot_area.right()); - track_line->setLine(x, plot_area.top(), x, plot_area.bottom()); - - auto [begin, end] = can->range(); - double sec = begin + ((x - plot_area.x()) / plot_area.width()) * (end - begin); - auto value = std::lower_bound(vals.begin(), vals.end(), sec, [](auto &p, double x) { return p.x() < x; }); - value_text->setPos(x + 6, plot_area.bottom() - 25); + auto axis_x = dynamic_cast(chart()->axisX()); + double x = std::clamp((double)ev->pos().x(), plot_area.left(), plot_area.right()-1); + double sec = axis_x->min() + (axis_x->max() - axis_x->min()) * (x - plot_area.left()) / plot_area.width(); + auto value = std::upper_bound(vals.begin(), vals.end(), sec, [](double x, auto &p) { return x < p.x(); }); if (value != vals.end()) { - value_text->setText(QString("(%1, %2)").arg(value->x(), 0, 'f', 3).arg(value->y())); - } else { - value_text->setText("(--, --)"); + QPointF pos = chart()->mapToPosition((*value)); + track_line->setLine(pos.x(), plot_area.top(), pos.x(), plot_area.bottom()); + track_ellipse->setRect(pos.x() - 5, pos.y() - 5, 10, 10); + value_text->setHtml(tr("
%1, %2)
") + .arg(value->x(), 0, 'f', 3).arg(value->y())); + int text_x = pos.x() + 8; + if ((text_x + value_text->boundingRect().width()) > plot_area.right()) { + text_x = pos.x() - value_text->boundingRect().width() - 8; + } + value_text->setPos(text_x, pos.y() - 10); } + track_line->setVisible(value != vals.end()); + value_text->setVisible(value != vals.end()); + track_ellipse->setVisible(value != vals.end()); } - - value_text->setVisible(show); - track_line->setVisible(show); - line_marker->setVisible(show); QChartView::mouseMoveEvent(ev); } diff --git a/tools/cabana/chartswidget.h b/tools/cabana/chartswidget.h index 5adbdfcd0..602d50ca0 100644 --- a/tools/cabana/chartswidget.h +++ b/tools/cabana/chartswidget.h @@ -3,8 +3,9 @@ #include #include +#include #include -#include +#include #include #include #include @@ -20,7 +21,14 @@ class ChartView : public QChartView { public: ChartView(const QString &id, const Signal *sig, QWidget *parent = nullptr); - void updateSeries(); + void updateSeries(const std::pair &range); + void setRange(double min, double max, bool force_update = false); + void updateLineMarker(double current_sec); + void updateFromSettings(); + +signals: + void zoomIn(double min, double max); + void zoomReset(); private: void mouseReleaseEvent(QMouseEvent *event) override; @@ -28,13 +36,11 @@ private: void enterEvent(QEvent *event) override; void leaveEvent(QEvent *event) override; void adjustChartMargins(); - - void rangeChanged(qreal min, qreal max); void updateAxisY(); - void updateState(); QGraphicsLineItem *track_line; - QGraphicsSimpleTextItem *value_text; + QGraphicsEllipseItem *track_ellipse; + QGraphicsTextItem *value_text; QGraphicsLineItem *line_marker; QList vals; QString id; @@ -47,7 +53,7 @@ Q_OBJECT public: ChartWidget(const QString &id, const Signal *sig, QWidget *parent); void updateTitle(); - void setHeight(int height); + void updateFromSettings(); signals: void remove(const QString &msg_id, const Signal *sig); @@ -55,7 +61,10 @@ signals: public: QString id; const Signal *signal; - QLabel *title; + QWidget *header; + QLabel *msg_name_label; + QLabel *sig_name_label; + QPushButton *remove_btn; ChartView *chart_view = nullptr; }; @@ -64,17 +73,25 @@ class ChartsWidget : public QWidget { public: ChartsWidget(QWidget *parent = nullptr); - void addChart(const QString &id, const Signal *sig); - void removeChart(const QString &id, const Signal *sig); + void showChart(const QString &id, const Signal *sig, bool show); + void removeChart(ChartWidget *chart); + bool isChartOpened(const QString &id, const Signal *sig); signals: void dock(bool floating); + void rangeChanged(double min, double max, bool is_zommed); + void chartOpened(const QString &id, const Signal *sig); + void chartClosed(const QString &id, const Signal *sig); private: + void eventsMerged(); void updateState(); + void zoomIn(double min, double max); + void zoomReset(); + void signalUpdated(const Signal *sig); void updateTitleBar(); void removeAll(const Signal *sig = nullptr); - bool eventFilter(QObject *obj, QEvent *event); + bool eventFilter(QObject *obj, QEvent *event) override; QWidget *title_bar; QLabel *title_label; @@ -85,4 +102,9 @@ private: QPushButton *remove_all_btn; QVBoxLayout *charts_layout; QList charts; + + bool is_zoomed = false; + std::pair event_range; + std::pair display_range; + std::pair zoomed_range; }; diff --git a/tools/cabana/dbcmanager.cc b/tools/cabana/dbcmanager.cc index fc40fc58e..479b14afe 100644 --- a/tools/cabana/dbcmanager.cc +++ b/tools/cabana/dbcmanager.cc @@ -28,8 +28,25 @@ void DBCManager::open(const QString &name, const QString &content) { emit DBCFileChanged(); } -void save(const QString &dbc_file_name) { - // TODO: save DBC to file +QString DBCManager::generateDBC() { + if (!dbc) return {}; + + QString dbc_string; + for (auto &m : dbc->msgs) { + dbc_string += QString("BO_ %1 %2: %3 XXX\n").arg(m.address).arg(m.name.c_str()).arg(m.size); + for (auto &sig : m.sigs) { + dbc_string += QString(" SG_ %1 : %2|%3@%4%5 (%6,%7) [0|0] \"\" XXX\n") + .arg(sig.name.c_str()) + .arg(sig.start_bit) + .arg(sig.size) + .arg(sig.is_little_endian ? '1' : '0') + .arg(sig.is_signed ? '-' : '+') + .arg(sig.factor, 0, 'g', 20) + .arg(sig.offset); + } + dbc_string += "\n"; + } + return dbc_string; } void DBCManager::updateMsg(const QString &id, const QString &name, uint32_t size) { @@ -121,3 +138,21 @@ double get_raw_value(uint8_t *data, size_t data_size, const Signal &sig) { double value = val * sig.factor + sig.offset; return value; } + +void updateSigSizeParamsFromRange(Signal &s, int from, int to) { + s.start_bit = s.is_little_endian ? from : bigEndianBitIndex(from); + s.size = to - from + 1; + if (s.is_little_endian) { + s.lsb = s.start_bit; + s.msb = s.start_bit + s.size - 1; + } else { + s.lsb = bigEndianStartBitsIndex(bigEndianBitIndex(s.start_bit) + s.size - 1); + s.msb = s.start_bit; + } +} + +std::pair getSignalRange(const Signal *s) { + int from = s->is_little_endian ? s->start_bit : bigEndianBitIndex(s->start_bit); + int to = from + s->size - 1; + return {from, to}; +} diff --git a/tools/cabana/dbcmanager.h b/tools/cabana/dbcmanager.h index 74d935119..913445d44 100644 --- a/tools/cabana/dbcmanager.h +++ b/tools/cabana/dbcmanager.h @@ -13,8 +13,7 @@ public: void open(const QString &dbc_file_name); void open(const QString &name, const QString &content); - void save(const QString &dbc_file_name); - + QString generateDBC(); void addSignal(const QString &id, const Signal &sig); void updateSignal(const QString &id, const QString &sig_name, const Signal &sig); void removeSignal(const QString &id, const QString &sig_name); @@ -24,6 +23,7 @@ public: inline QString name() const { return dbc_name; } void updateMsg(const QString &id, const QString &name, uint32_t size); + inline const DBC *getDBC() const { return dbc; } inline const Msg *msg(const QString &id) const { return msg(addressFromId(id)); } inline const Msg *msg(uint32_t address) const { auto it = msg_map.find(address); @@ -47,5 +47,7 @@ private: double get_raw_value(uint8_t *data, size_t data_size, const Signal &sig); int bigEndianStartBitsIndex(int start_bit); int bigEndianBitIndex(int index); +void updateSigSizeParamsFromRange(Signal &s, int from, int to); +std::pair getSignalRange(const Signal *s); DBCManager *dbc(); diff --git a/tools/cabana/detailwidget.cc b/tools/cabana/detailwidget.cc index 039a7c4e5..57a391030 100644 --- a/tools/cabana/detailwidget.cc +++ b/tools/cabana/detailwidget.cc @@ -2,6 +2,7 @@ #include #include +#include #include #include @@ -11,25 +12,39 @@ // DetailWidget -DetailWidget::DetailWidget(QWidget *parent) : QWidget(parent) { - QVBoxLayout *main_layout = new QVBoxLayout(this); +DetailWidget::DetailWidget(ChartsWidget *charts, QWidget *parent) : charts(charts), QWidget(parent) { + main_layout = new QHBoxLayout(this); main_layout->setContentsMargins(0, 0, 0, 0); - main_layout->setSpacing(0); + right_column = new QVBoxLayout(); + main_layout->addLayout(right_column); + + binary_view_container = new QWidget(this); + binary_view_container->setMinimumWidth(500); + binary_view_container->setSizePolicy(QSizePolicy::Minimum, QSizePolicy::Preferred); + QVBoxLayout *bin_layout = new QVBoxLayout(binary_view_container); + bin_layout->setContentsMargins(0, 0, 0, 0); + bin_layout->setSpacing(0); // tabbar tabbar = new QTabBar(this); tabbar->setTabsClosable(true); tabbar->setDrawBase(false); tabbar->setUsesScrollButtons(true); tabbar->setAutoHide(true); - main_layout->addWidget(tabbar); + tabbar->setContextMenuPolicy(Qt::CustomContextMenu); + bin_layout->addWidget(tabbar); - // message title - QFrame *title_frame = new QFrame(); - main_layout->addWidget(title_frame); - QVBoxLayout *frame_layout = new QVBoxLayout(title_frame); + TitleFrame *title_frame = new TitleFrame(this); title_frame->setFrameShape(QFrame::StyledPanel); + title_frame->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Fixed); + QVBoxLayout *frame_layout = new QVBoxLayout(title_frame); + + // message title QHBoxLayout *title_layout = new QHBoxLayout(); + split_btn = new QPushButton("⬅", this); + split_btn->setFixedSize(20, 20); + split_btn->setToolTip(tr("Split to two columns")); + title_layout->addWidget(split_btn); title_layout->addWidget(new QLabel("time:")); time_label = new QLabel(this); time_label->setStyleSheet("font-weight:bold"); @@ -48,16 +63,18 @@ DetailWidget::DetailWidget(QWidget *parent) : QWidget(parent) { warning_widget = new QWidget(this); QHBoxLayout *warning_hlayout = new QHBoxLayout(warning_widget); QLabel *warning_icon = new QLabel(this); - warning_icon->setPixmap(style()->standardIcon(QStyle::SP_MessageBoxWarning).pixmap({16, 16})); - warning_hlayout->addWidget(warning_icon); + warning_icon->setPixmap(style()->standardPixmap(QStyle::SP_MessageBoxWarning)); + warning_hlayout->addWidget(warning_icon, 0, Qt::AlignTop); warning_label = new QLabel(this); warning_hlayout->addWidget(warning_label, 1, Qt::AlignLeft); warning_widget->hide(); frame_layout->addWidget(warning_widget); + bin_layout->addWidget(title_frame); // binary view binary_view = new BinaryView(this); - main_layout->addWidget(binary_view, 0, Qt::AlignTop); + bin_layout->addWidget(binary_view); + right_column->addWidget(binary_view_container); // signals signals_container = new QWidget(this); @@ -68,33 +85,61 @@ DetailWidget::DetailWidget(QWidget *parent) : QWidget(parent) { scroll->setWidget(signals_container); scroll->setWidgetResizable(true); scroll->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); - main_layout->addWidget(scroll); + right_column->addWidget(scroll); // history log history_log = new HistoryLog(this); - main_layout->addWidget(history_log); + right_column->addWidget(history_log); + QObject::connect(split_btn, &QPushButton::clicked, this, &DetailWidget::moveBinaryView); + QObject::connect(title_frame, &TitleFrame::doubleClicked, this, &DetailWidget::moveBinaryView); QObject::connect(edit_btn, &QPushButton::clicked, this, &DetailWidget::editMsg); QObject::connect(binary_view, &BinaryView::resizeSignal, this, &DetailWidget::resizeSignal); QObject::connect(binary_view, &BinaryView::addSignal, this, &DetailWidget::addSignal); QObject::connect(can, &CANMessages::updated, this, &DetailWidget::updateState); - QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &DetailWidget::dbcMsgChanged); - QObject::connect(tabbar, &QTabBar::currentChanged, [this](int index) { setMessage(messages[index]); }); - QObject::connect(tabbar, &QTabBar::tabCloseRequested, [=](int index) { - messages.removeAt(index); - tabbar->removeTab(index); - setMessage(messages.isEmpty() ? "" : messages[0]); + QObject::connect(dbc(), &DBCManager::DBCFileChanged, [this]() { dbcMsgChanged(); }); + QObject::connect(tabbar, &QTabBar::customContextMenuRequested, this, &DetailWidget::showTabBarContextMenu); + QObject::connect(tabbar, &QTabBar::currentChanged, [this](int index) { + if (index != -1 && tabbar->tabText(index) != msg_id) { + setMessage(tabbar->tabText(index)); + } }); + QObject::connect(tabbar, &QTabBar::tabCloseRequested, tabbar, &QTabBar::removeTab); + QObject::connect(charts, &ChartsWidget::chartOpened, [this](const QString &id, const Signal *sig) { updateChartState(id, sig, true); }); + QObject::connect(charts, &ChartsWidget::chartClosed, [this](const QString &id, const Signal *sig) { updateChartState(id, sig, false); }); +} + +void DetailWidget::showTabBarContextMenu(const QPoint &pt) { + int index = tabbar->tabAt(pt); + if (index >= 0) { + QMenu menu(this); + menu.addAction(tr("Close Other Tabs")); + if (menu.exec(tabbar->mapToGlobal(pt))) { + tabbar->setCurrentIndex(index); + // remove all tabs before the one to keep + for (int i = 0; i < index; ++i) { + tabbar->removeTab(0); + } + // remove all tabs after the one to keep + while (tabbar->count() > 1) { + tabbar->removeTab(1); + } + } + } } void DetailWidget::setMessage(const QString &message_id) { if (message_id.isEmpty()) return; - int index = messages.indexOf(message_id); + int index = -1; + for (int i = 0; i < tabbar->count(); ++i) { + if (tabbar->tabText(i) == message_id) { + index = i; + break; + } + } if (index == -1) { - messages.push_back(message_id); - tabbar->addTab(message_id); - index = tabbar->count() - 1; + index = tabbar->addTab(message_id); auto msg = dbc()->msg(message_id); tabbar->setTabToolTip(index, msg ? msg->name.c_str() : "untitled"); } @@ -103,34 +148,49 @@ void DetailWidget::setMessage(const QString &message_id) { dbcMsgChanged(); } -void DetailWidget::dbcMsgChanged() { +void DetailWidget::dbcMsgChanged(int show_form_idx) { if (msg_id.isEmpty()) return; warning_widget->hide(); + QStringList warnings; + clearLayout(signals_container->layout()); QString msg_name = tr("untitled"); if (auto msg = dbc()->msg(msg_id)) { for (int i = 0; i < msg->sigs.size(); ++i) { - auto form = new SignalEdit(i, msg_id, msg->sigs[i]); + auto form = new SignalEdit(i, msg_id, &(msg->sigs[i])); + form->setChartOpened(charts->isChartOpened(msg_id, &(msg->sigs[i]))); signals_container->layout()->addWidget(form); - QObject::connect(form, &SignalEdit::showChart, [this, sig = &msg->sigs[i]]() { emit showChart(msg_id, sig); }); QObject::connect(form, &SignalEdit::showFormClicked, this, &DetailWidget::showForm); QObject::connect(form, &SignalEdit::remove, this, &DetailWidget::removeSignal); QObject::connect(form, &SignalEdit::save, this, &DetailWidget::saveSignal); QObject::connect(form, &SignalEdit::highlight, binary_view, &BinaryView::highlight); QObject::connect(binary_view, &BinaryView::signalHovered, form, &SignalEdit::signalHovered); + QObject::connect(form, &SignalEdit::showChart, [this, sig = &msg->sigs[i]](bool show) { charts->showChart(msg_id, sig, show); }); + if (i == show_form_idx) { + QTimer::singleShot(0, [=]() { emit form->showFormClicked(); }); + } } msg_name = msg->name.c_str(); - if (msg->size != can->lastMessage(msg_id).dat.size()) { - warning_label->setText(tr("Message size (%1) is incorrect!").arg(msg->size)); - warning_widget->show(); - } + if (msg->size != can->lastMessage(msg_id).dat.size()) + warnings.push_back(tr("Message size (%1) is incorrect.").arg(msg->size)); } edit_btn->setVisible(true); name_label->setText(msg_name); binary_view->setMessage(msg_id); history_log->setMessage(msg_id); + + // Check overlapping bits + if (auto overlapping = binary_view->getOverlappingSignals(); !overlapping.isEmpty()) { + for (auto s : overlapping) + warnings.push_back(tr("%1 has overlapping bits.").arg(s->name.c_str())); + } + + if (!warnings.isEmpty()) { + warning_label->setText(warnings.join('\n')); + warning_widget->show(); + } } void DetailWidget::updateState() { @@ -141,6 +201,20 @@ void DetailWidget::updateState() { history_log->updateState(); } +void DetailWidget::moveBinaryView() { + if (binview_in_left_col) { + right_column->insertWidget(0, binary_view_container); + emit binaryViewMoved(true); + } else { + main_layout->insertWidget(0, binary_view_container); + emit binaryViewMoved(false); + } + split_btn->setText(binview_in_left_col ? "⬅" : "➡"); + split_btn->setToolTip(binview_in_left_col ? tr("Split to two columns") : tr("Move back")); + binary_view->updateGeometry(); + binview_in_left_col = !binview_in_left_col; +} + void DetailWidget::showForm() { SignalEdit *sender = qobject_cast(QObject::sender()); for (auto f : signals_container->findChildren()) { @@ -151,6 +225,13 @@ void DetailWidget::showForm() { } } +void DetailWidget::updateChartState(const QString &id, const Signal *sig, bool opened) { + if (id == msg_id) { + for (auto f : signals_container->findChildren()) + if (f->sig == sig) f->setChartOpened(opened); + } +} + void DetailWidget::editMsg() { auto msg = dbc()->msg(msg_id); QString name = msg ? msg->name.c_str() : "untitled"; @@ -162,46 +243,54 @@ void DetailWidget::editMsg() { } } -void DetailWidget::addSignal(int start_bit, int to) { - if (dbc()->msg(msg_id)) { - AddSignalDialog dlg(msg_id, start_bit, to - start_bit + 1, this); - if (dlg.exec()) { - dbc()->addSignal(msg_id, dlg.form->getSignal()); - dbcMsgChanged(); +void DetailWidget::addSignal(int from, int to) { + if (auto msg = dbc()->msg(msg_id)) { + Signal sig = {}; + for (int i = 1; /**/; ++i) { + sig.name = "NEW_SIGNAL_" + std::to_string(i); + auto it = std::find_if(msg->sigs.begin(), msg->sigs.end(), [&](auto &s) { return sig.name == s.name; }); + if (it == msg->sigs.end()) break; } + sig.is_little_endian = false, + updateSigSizeParamsFromRange(sig, from, to); + dbc()->addSignal(msg_id, sig); + dbcMsgChanged(msg->sigs.size() - 1); } } void DetailWidget::resizeSignal(const Signal *sig, int from, int to) { - assert(sig != nullptr); Signal s = *sig; - s.start_bit = s.is_little_endian ? from : bigEndianBitIndex(from);; - s.size = to - from + 1; - if (s.is_little_endian) { - s.lsb = s.start_bit; - s.msb = s.start_bit + s.size - 1; - } else { - s.lsb = bigEndianStartBitsIndex(bigEndianBitIndex(s.start_bit) + s.size - 1); - s.msb = s.start_bit; - } - dbc()->updateSignal(msg_id, s.name.c_str(), s); - dbcMsgChanged(); + updateSigSizeParamsFromRange(s, from, to); + saveSignal(sig, s); } -void DetailWidget::saveSignal() { - SignalEdit *sig_form = qobject_cast(QObject::sender()); - auto s = sig_form->form->getSignal(); - dbc()->updateSignal(msg_id, sig_form->sig_name, s); +void DetailWidget::saveSignal(const Signal *sig, const Signal &new_sig) { + auto msg = dbc()->msg(msg_id); + if (new_sig.name != sig->name) { + auto it = std::find_if(msg->sigs.begin(), msg->sigs.end(), [&](auto &s) { return s.name == new_sig.name; }); + if (it != msg->sigs.end()) { + QString warning_str = tr("There is already a signal with the same name '%1'").arg(new_sig.name.c_str()); + QMessageBox::warning(this, tr("Failed to save signal"), warning_str); + return; + } + } + + auto [start, end] = getSignalRange(&new_sig); + if (start < 0 || end >= msg->size * 8) { + QString warning_str = tr("Signal size [%1] exceed limit").arg(new_sig.size); + QMessageBox::warning(this, tr("Failed to save signal"), warning_str); + return; + } + + dbc()->updateSignal(msg_id, sig->name.c_str(), new_sig); // update binary view and history log - binary_view->setMessage(msg_id); - history_log->setMessage(msg_id); + dbcMsgChanged(); } -void DetailWidget::removeSignal() { - SignalEdit *sig_form = qobject_cast(QObject::sender()); - QString text = tr("Are you sure you want to remove signal '%1'").arg(sig_form->sig_name); +void DetailWidget::removeSignal(const Signal *sig) { + QString text = tr("Are you sure you want to remove signal '%1'").arg(sig->name.c_str()); if (QMessageBox::Yes == QMessageBox::question(this, tr("Remove signal"), text)) { - dbc()->removeSignal(msg_id, sig_form->sig_name); + dbc()->removeSignal(msg_id, sig->name.c_str()); dbcMsgChanged(); } } diff --git a/tools/cabana/detailwidget.h b/tools/cabana/detailwidget.h index 02bbb2a9e..656aacb10 100644 --- a/tools/cabana/detailwidget.h +++ b/tools/cabana/detailwidget.h @@ -2,11 +2,22 @@ #include #include +#include #include "tools/cabana/binaryview.h" +#include "tools/cabana/chartswidget.h" #include "tools/cabana/historylog.h" #include "tools/cabana/signaledit.h" +class TitleFrame : public QFrame { + Q_OBJECT +public: + TitleFrame(QWidget *parent) : QFrame(parent) {} + void mouseDoubleClickEvent(QMouseEvent *e) { emit doubleClicked(); } +signals: + void doubleClicked(); +}; + class EditMessageDialog : public QDialog { Q_OBJECT @@ -30,22 +41,24 @@ class DetailWidget : public QWidget { Q_OBJECT public: - DetailWidget(QWidget *parent); + DetailWidget(ChartsWidget *charts, QWidget *parent); void setMessage(const QString &message_id); - void dbcMsgChanged(); + void dbcMsgChanged(int show_form_idx = -1); signals: - void showChart(const QString &msg_id, const Signal *sig); - void removeChart(const Signal *sig); + void binaryViewMoved(bool in); private: + void updateChartState(const QString &id, const Signal *sig, bool opened); + void showTabBarContextMenu(const QPoint &pt); void addSignal(int start_bit, int to); void resizeSignal(const Signal *sig, int from, int to); - void saveSignal(); - void removeSignal(); + void saveSignal(const Signal *sig, const Signal &new_sig); + void removeSignal(const Signal *sig); void editMsg(); void showForm(); void updateState(); + void moveBinaryView(); QString msg_id; QLabel *name_label, *time_label, *warning_label; @@ -53,8 +66,13 @@ private: QPushButton *edit_btn; QWidget *signals_container; QTabBar *tabbar; - QStringList messages; + QHBoxLayout *main_layout; + QVBoxLayout *right_column; + bool binview_in_left_col = false; + QWidget *binary_view_container; + QPushButton *split_btn; HistoryLog *history_log; BinaryView *binary_view; ScrollArea *scroll; + ChartsWidget *charts; }; diff --git a/tools/cabana/historylog.cc b/tools/cabana/historylog.cc index a20845f15..8136d0577 100644 --- a/tools/cabana/historylog.cc +++ b/tools/cabana/historylog.cc @@ -7,7 +7,7 @@ QVariant HistoryLogModel::data(const QModelIndex &index, int role) const { bool has_signal = dbc_msg && !dbc_msg->sigs.empty(); if (role == Qt::DisplayRole) { - const auto &m = can->messages(msg_id)[index.row()]; + const auto &m = messages[index.row()]; if (index.column() == 0) { return QString::number(m.ts, 'f', 2); } @@ -49,7 +49,8 @@ void HistoryLogModel::updateState() { if (msg_id.isEmpty()) return; int prev_row_count = row_count; - row_count = can->messages(msg_id).size(); + messages = can->messages(msg_id); + row_count = messages.size(); int delta = row_count - prev_row_count; if (delta > 0) { beginInsertRows({}, prev_row_count, row_count - 1); diff --git a/tools/cabana/historylog.h b/tools/cabana/historylog.h index bc6d1f937..d39bcf9f1 100644 --- a/tools/cabana/historylog.h +++ b/tools/cabana/historylog.h @@ -22,6 +22,7 @@ private: int row_count = 0; int column_count = 2; const Msg *dbc_msg = nullptr; + std::deque messages; }; class HistoryLog : public QWidget { diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc index d0e171c86..c2baca4d2 100644 --- a/tools/cabana/mainwin.cc +++ b/tools/cabana/mainwin.cc @@ -3,20 +3,16 @@ #include #include #include -#include #include #include "tools/replay/util.h" static MainWindow *main_win = nullptr; void qLogMessageHandler(QtMsgType type, const QMessageLogContext &context, const QString &msg) { - if (main_win) main_win->showStatusMessage(msg); + if (main_win) emit main_win->showMessage(msg, 0); } MainWindow::MainWindow() : QWidget() { - main_win = this; - qInstallMessageHandler(qLogMessageHandler); - QVBoxLayout *main_layout = new QVBoxLayout(this); main_layout->setContentsMargins(11, 11, 11, 5); main_layout->setSpacing(0); @@ -25,14 +21,15 @@ MainWindow::MainWindow() : QWidget() { h_layout->setContentsMargins(0, 0, 0, 0); main_layout->addLayout(h_layout); - QSplitter *splitter = new QSplitter(Qt::Horizontal, this); + splitter = new QSplitter(Qt::Horizontal, this); + splitter->setHandleWidth(11); messages_widget = new MessagesWidget(this); splitter->addWidget(messages_widget); - detail_widget = new DetailWidget(this); + charts_widget = new ChartsWidget(this); + detail_widget = new DetailWidget(charts_widget, this); splitter->addWidget(detail_widget); - splitter->setSizes({100, 500}); h_layout->addWidget(splitter); // right widgets @@ -54,13 +51,13 @@ MainWindow::MainWindow() : QWidget() { video_widget = new VideoWidget(this); r_layout->addWidget(video_widget, 0, Qt::AlignTop); - charts_widget = new ChartsWidget(this); r_layout->addWidget(charts_widget); h_layout->addWidget(right_container); // status bar status_bar = new QStatusBar(this); + status_bar->setFixedHeight(20); status_bar->setContentsMargins(0, 0, 0, 0); status_bar->setSizeGripEnabled(true); progress_bar = new QProgressBar(); @@ -75,19 +72,23 @@ MainWindow::MainWindow() : QWidget() { qRegisterMetaType("ReplyMsgType"); installMessageHandler([this](ReplyMsgType type, const std::string msg) { // use queued connection to recv the log messages from replay. - emit logMessageFromReplay(QString::fromStdString(msg), 3000); + emit showMessage(QString::fromStdString(msg), 3000); }); installDownloadProgressHandler([this](uint64_t cur, uint64_t total, bool success) { emit updateProgressBar(cur, total, success); }); - QObject::connect(this, &MainWindow::logMessageFromReplay, status_bar, &QStatusBar::showMessage); + QObject::connect(this, &MainWindow::showMessage, status_bar, &QStatusBar::showMessage); QObject::connect(this, &MainWindow::updateProgressBar, this, &MainWindow::updateDownloadProgress); QObject::connect(messages_widget, &MessagesWidget::msgSelectionChanged, detail_widget, &DetailWidget::setMessage); - QObject::connect(detail_widget, &DetailWidget::showChart, charts_widget, &ChartsWidget::addChart); + QObject::connect(detail_widget, &DetailWidget::binaryViewMoved, [this](bool in) { splitter->setSizes({in ? 100 : 0, 500}); }); QObject::connect(charts_widget, &ChartsWidget::dock, this, &MainWindow::dockCharts); + QObject::connect(charts_widget, &ChartsWidget::rangeChanged, video_widget, &VideoWidget::rangeChanged); QObject::connect(settings_btn, &QPushButton::clicked, this, &MainWindow::setOption); QObject::connect(can, &CANMessages::eventsMerged, [=]() { fingerprint_label->setText(can->carFingerprint() ); }); + + main_win = this; + qInstallMessageHandler(qLogMessageHandler); } void MainWindow::updateDownloadProgress(uint64_t cur, uint64_t total, bool success) { @@ -100,7 +101,6 @@ void MainWindow::updateDownloadProgress(uint64_t cur, uint64_t total, bool succe } } - void MainWindow::dockCharts(bool dock) { if (dock && floating_window) { floating_window->removeEventFilter(charts_widget); diff --git a/tools/cabana/mainwin.h b/tools/cabana/mainwin.h index 63f704dcc..b77744ba9 100644 --- a/tools/cabana/mainwin.h +++ b/tools/cabana/mainwin.h @@ -1,6 +1,7 @@ #pragma once #include +#include #include #include "tools/cabana/chartswidget.h" @@ -17,7 +18,7 @@ public: void showStatusMessage(const QString &msg, int timeout = 0) { status_bar->showMessage(msg, timeout); } signals: - void logMessageFromReplay(const QString &msg, int timeout); + void showMessage(const QString &msg, int timeout); void updateProgressBar(uint64_t cur, uint64_t total, bool success); protected: @@ -29,6 +30,7 @@ protected: MessagesWidget *messages_widget; DetailWidget *detail_widget; ChartsWidget *charts_widget; + QSplitter *splitter; QWidget *floating_window = nullptr; QVBoxLayout *r_layout; QProgressBar *progress_bar; diff --git a/tools/cabana/messageswidget.cc b/tools/cabana/messageswidget.cc index c289f54fc..4d97bba58 100644 --- a/tools/cabana/messageswidget.cc +++ b/tools/cabana/messageswidget.cc @@ -2,6 +2,9 @@ #include #include +#include +#include +#include #include #include #include @@ -68,9 +71,7 @@ MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) { QObject::connect(can, &CANMessages::updated, [this]() { model->updateState(); }); QObject::connect(dbc_combo, SIGNAL(activated(const QString &)), SLOT(loadDBCFromName(const QString &))); QObject::connect(load_from_paste, &QPushButton::clicked, this, &MessagesWidget::loadDBCFromPaste); - QObject::connect(save_btn, &QPushButton::clicked, [=]() { - // TODO: save DBC to file - }); + QObject::connect(save_btn, &QPushButton::clicked, this, &MessagesWidget::saveDBC); QObject::connect(table_widget->selectionModel(), &QItemSelectionModel::currentChanged, [=](const QModelIndex ¤t, const QModelIndex &previous) { if (current.isValid()) { emit msgSelectionChanged(current.data(Qt::UserRole).toString()); @@ -78,16 +79,18 @@ MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) { }); QFile json_file("./car_fingerprint_to_dbc.json"); - if(json_file.open(QIODevice::ReadOnly)) { + if (json_file.open(QIODevice::ReadOnly)) { fingerprint_to_dbc = QJsonDocument::fromJson(json_file.readAll()); } } void MessagesWidget::loadDBCFromName(const QString &name) { - dbc()->open(name); - dbc_combo->setCurrentText(name); - // refresh model - model->updateState(); + if (name != dbc()->name()) { + dbc()->open(name); + dbc_combo->setCurrentText(name); + // re-sort model to refresh column 'Name' + model->updateState(true); + } } void MessagesWidget::loadDBCFromPaste() { @@ -100,14 +103,20 @@ void MessagesWidget::loadDBCFromPaste() { void MessagesWidget::loadDBCFromFingerprint() { auto fingerprint = can->carFingerprint(); - if (!fingerprint.isEmpty() && dbc()->name().isEmpty()) { + if (!fingerprint.isEmpty() && dbc()->name().isEmpty()) { auto dbc_name = fingerprint_to_dbc[fingerprint]; - if (dbc_name != QJsonValue::Undefined) { + if (dbc_name != QJsonValue::Undefined) { loadDBCFromName(dbc_name.toString()); } } } +void MessagesWidget::saveDBC() { + SaveDBCDialog dlg(this); + dlg.dbc_edit->setText(dbc()->generateDBC()); + dlg.exec(); +} + // MessageListModel QVariant MessageListModel::headerData(int section, Qt::Orientation orientation, int role) const { @@ -221,6 +230,8 @@ void MessageListModel::sort(int column, Qt::SortOrder order) { } } +// LoadDBCDialog + LoadDBCDialog::LoadDBCDialog(QWidget *parent) : QDialog(parent) { QVBoxLayout *main_layout = new QVBoxLayout(this); dbc_edit = new QTextEdit(this); @@ -230,7 +241,48 @@ LoadDBCDialog::LoadDBCDialog(QWidget *parent) : QDialog(parent) { auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); main_layout->addWidget(buttonBox); - setFixedWidth(640); - connect(buttonBox, &QDialogButtonBox::accepted, this, &QDialog::accept); - connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); + setMinimumSize({640, 480}); + QObject::connect(buttonBox, &QDialogButtonBox::accepted, this, &QDialog::accept); + QObject::connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); +} + +// SaveDBCDialog + +SaveDBCDialog::SaveDBCDialog(QWidget *parent) : QDialog(parent) { + setWindowTitle(tr("Save DBC")); + QVBoxLayout *main_layout = new QVBoxLayout(this); + dbc_edit = new QTextEdit(this); + dbc_edit->setAcceptRichText(false); + main_layout->addWidget(dbc_edit); + + QPushButton *copy_to_clipboard = new QPushButton(tr("Copy To Clipboard"), this); + QPushButton *save_as = new QPushButton(tr("Save As"), this); + + QHBoxLayout *btn_layout = new QHBoxLayout(); + btn_layout->addStretch(); + btn_layout->addWidget(copy_to_clipboard); + btn_layout->addWidget(save_as); + main_layout->addLayout(btn_layout); + setMinimumSize({640, 480}); + + QObject::connect(copy_to_clipboard, &QPushButton::clicked, this, &SaveDBCDialog::copytoClipboard); + QObject::connect(save_as, &QPushButton::clicked, this, &SaveDBCDialog::saveAs); +} + +void SaveDBCDialog::copytoClipboard() { + dbc_edit->selectAll(); + dbc_edit->copy(); + QDialog::accept(); +} + +void SaveDBCDialog::saveAs() { + QString file_name = QFileDialog::getSaveFileName(this, tr("Save File"), + QDir::homePath() + "/untitled.dbc", tr("DBC (*.dbc)")); + if (!file_name.isEmpty()) { + QFile file(file_name); + if (file.open(QIODevice::WriteOnly)) { + file.write(dbc_edit->toPlainText().toUtf8()); + } + QDialog::accept(); + } } diff --git a/tools/cabana/messageswidget.h b/tools/cabana/messageswidget.h index fcd4939da..a3d4d860b 100644 --- a/tools/cabana/messageswidget.h +++ b/tools/cabana/messageswidget.h @@ -17,6 +17,16 @@ public: QTextEdit *dbc_edit; }; +class SaveDBCDialog : public QDialog { + Q_OBJECT + +public: + SaveDBCDialog(QWidget *parent); + void copytoClipboard(); + void saveAs(); + QTextEdit *dbc_edit; +}; + class MessageListModel : public QAbstractTableModel { Q_OBJECT @@ -52,6 +62,7 @@ public slots: void loadDBCFromName(const QString &name); void loadDBCFromFingerprint(); void loadDBCFromPaste(); + void saveDBC(); signals: void msgSelectionChanged(const QString &message_id); diff --git a/tools/cabana/settings.cc b/tools/cabana/settings.cc index 0b36f25fb..17299ebca 100644 --- a/tools/cabana/settings.cc +++ b/tools/cabana/settings.cc @@ -17,6 +17,8 @@ void Settings::save() { s.setValue("log_size", can_msg_log_size); s.setValue("cached_segment", cached_segment_limit); s.setValue("chart_height", chart_height); + s.setValue("chart_theme", chart_theme); + s.setValue("max_chart_x_range", max_chart_x_range); emit changed(); } @@ -26,6 +28,8 @@ void Settings::load() { can_msg_log_size = s.value("log_size", 100).toInt(); cached_segment_limit = s.value("cached_segment", 3).toInt(); chart_height = s.value("chart_height", 200).toInt(); + chart_theme = s.value("chart_theme", 0).toInt(); + max_chart_x_range = s.value("max_chart_x_range", 3 * 60).toInt(); } // SettingsDlg @@ -45,7 +49,7 @@ SettingsDlg::SettingsDlg(QWidget *parent) : QDialog(parent) { log_size->setRange(50, 500); log_size->setSingleStep(10); log_size->setValue(settings.can_msg_log_size); - form_layout->addRow(tr("Log size"), log_size); + form_layout->addRow(tr("Signal history log size"), log_size); cached_segment = new QSpinBox(this); cached_segment->setRange(3, 60); @@ -53,12 +57,23 @@ SettingsDlg::SettingsDlg(QWidget *parent) : QDialog(parent) { cached_segment->setValue(settings.cached_segment_limit); form_layout->addRow(tr("Cached segments limit"), cached_segment); + max_chart_x_range = new QSpinBox(this); + max_chart_x_range->setRange(1, 60); + max_chart_x_range->setSingleStep(1); + max_chart_x_range->setValue(settings.max_chart_x_range / 60); + form_layout->addRow(tr("Chart range (minutes)"), max_chart_x_range); + chart_height = new QSpinBox(this); chart_height->setRange(100, 500); chart_height->setSingleStep(10); chart_height->setValue(settings.chart_height); form_layout->addRow(tr("Chart height"), chart_height); + chart_theme = new QComboBox(); + chart_theme->addItems({"Light", "Dark"}); + chart_theme->setCurrentIndex(settings.chart_theme == 1 ? 1 : 0); + form_layout->addRow(tr("Chart theme"), chart_theme); + main_layout->addLayout(form_layout); auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); @@ -74,6 +89,8 @@ void SettingsDlg::save() { settings.can_msg_log_size = log_size->value(); settings.cached_segment_limit = cached_segment->value(); settings.chart_height = chart_height->value(); + settings.chart_theme = chart_theme->currentIndex(); + settings.max_chart_x_range = max_chart_x_range->value() * 60; settings.save(); accept(); } diff --git a/tools/cabana/settings.h b/tools/cabana/settings.h index 22542fc04..88eeebc72 100644 --- a/tools/cabana/settings.h +++ b/tools/cabana/settings.h @@ -1,5 +1,6 @@ #pragma once +#include #include #include @@ -15,6 +16,8 @@ public: int can_msg_log_size = 100; int cached_segment_limit = 3; int chart_height = 200; + int chart_theme = 0; + int max_chart_x_range = 3 * 60; // 3 minutes signals: void changed(); @@ -30,6 +33,8 @@ public: QSpinBox *log_size ; QSpinBox *cached_segment; QSpinBox *chart_height; + QComboBox *chart_theme; + QSpinBox *max_chart_x_range; }; extern Settings settings; diff --git a/tools/cabana/signaledit.cc b/tools/cabana/signaledit.cc index d5dccf0e6..ef0a85eba 100644 --- a/tools/cabana/signaledit.cc +++ b/tools/cabana/signaledit.cc @@ -1,8 +1,10 @@ #include "tools/cabana/signaledit.h" #include +#include #include #include +#include #include #include #include @@ -11,7 +13,7 @@ // SignalForm -SignalForm::SignalForm(const Signal &sig, QWidget *parent) : start_bit(sig.start_bit), QWidget(parent) { +SignalForm::SignalForm(const Signal &sig, QWidget *parent) : QWidget(parent) { QFormLayout *form_layout = new QFormLayout(this); name = new QLineEdit(sig.name.c_str()); @@ -35,13 +37,16 @@ SignalForm::SignalForm(const Signal &sig, QWidget *parent) : start_bit(sig.start sign->setCurrentIndex(sig.is_signed ? 0 : 1); form_layout->addRow(tr("sign"), sign); - factor = new QDoubleSpinBox(); - factor->setDecimals(3); - factor->setValue(sig.factor); + auto double_validator = new QDoubleValidator(this); + + factor = new QLineEdit(); + factor->setValidator(double_validator); + factor->setText(QString::number(sig.factor)); form_layout->addRow(tr("Factor"), factor); - offset = new QSpinBox(); - offset->setValue(sig.offset); + offset = new QLineEdit(); + offset->setValidator(double_validator); + offset->setText(QString::number(sig.offset)); form_layout->addRow(tr("Offset"), offset); // TODO: parse the following parameters in opendbc @@ -49,40 +54,19 @@ SignalForm::SignalForm(const Signal &sig, QWidget *parent) : start_bit(sig.start form_layout->addRow(tr("Unit"), unit); comment = new QLineEdit(); form_layout->addRow(tr("Comment"), comment); - min_val = new QDoubleSpinBox(); - factor->setDecimals(3); + min_val = new QLineEdit(); + min_val->setValidator(double_validator); form_layout->addRow(tr("Minimum value"), min_val); - max_val = new QDoubleSpinBox(); - factor->setDecimals(3); + max_val = new QLineEdit(); + max_val->setValidator(double_validator); form_layout->addRow(tr("Maximum value"), max_val); val_desc = new QLineEdit(); form_layout->addRow(tr("Value descriptions"), val_desc); } -Signal SignalForm::getSignal() { - // TODO: Check if the size is valid, and no duplicate name - Signal sig = {}; - sig.start_bit = start_bit; - sig.name = name->text().toStdString(); - sig.size = size->text().toInt(); - sig.offset = offset->text().toDouble(); - sig.factor = factor->text().toDouble(); - sig.is_signed = sign->currentIndex() == 0; - sig.is_little_endian = endianness->currentIndex() == 0; - if (sig.is_little_endian) { - sig.lsb = sig.start_bit; - sig.msb = sig.start_bit + sig.size - 1; - } else { - sig.lsb = bigEndianStartBitsIndex(bigEndianBitIndex(sig.start_bit) + sig.size - 1); - sig.msb = sig.start_bit; - } - return sig; -} - // SignalEdit -SignalEdit::SignalEdit(int index, const QString &msg_id, const Signal &sig, QWidget *parent) - : sig(&sig), form_idx(index), sig_name(sig.name.c_str()), QWidget(parent) { +SignalEdit::SignalEdit(int index, const QString &msg_id, const Signal *sig, QWidget *parent) : msg_id(msg_id), sig(sig), form_idx(index), QWidget(parent) { QVBoxLayout *main_layout = new QVBoxLayout(this); main_layout->setContentsMargins(0, 0, 0, 0); @@ -93,27 +77,26 @@ SignalEdit::SignalEdit(int index, const QString &msg_id, const Signal &sig, QWid title_layout->addWidget(icon); title = new ElidedLabel(this); title->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::MinimumExpanding); - title->setText(QString("%1. %2").arg(index + 1).arg(sig_name)); + title->setText(QString("%1. %2").arg(index + 1).arg(sig->name.c_str())); title->setStyleSheet(QString("font-weight:bold; color:%1").arg(getColor(index))); title_layout->addWidget(title, 1); QPushButton *seek_btn = new QPushButton("⌕"); - seek_btn->setStyleSheet("font-weight:bold;font-size:20px"); + seek_btn->setStyleSheet("QPushButton{font-weight:bold;font-size:18px}"); seek_btn->setToolTip(tr("Find signal values")); - seek_btn->setFixedSize(20, 20); + seek_btn->setFixedSize(25, 25); title_layout->addWidget(seek_btn); - QPushButton *plot_btn = new QPushButton("📈"); - plot_btn->setToolTip(tr("Show Plot")); - plot_btn->setFixedSize(20, 20); - QObject::connect(plot_btn, &QPushButton::clicked, this, &SignalEdit::showChart); + plot_btn = new QPushButton(this); + plot_btn->setStyleSheet("QPushButton {font-size:18px}"); + plot_btn->setFixedSize(25, 25); title_layout->addWidget(plot_btn); main_layout->addLayout(title_layout); // signal form form_container = new QWidget(this); QVBoxLayout *v_layout = new QVBoxLayout(form_container); - form = new SignalForm(sig, this); + form = new SignalForm(*sig, this); v_layout->addWidget(form); QHBoxLayout *h = new QHBoxLayout(); @@ -133,20 +116,41 @@ SignalEdit::SignalEdit(int index, const QString &msg_id, const Signal &sig, QWid hline->setFrameShadow(QFrame::Sunken); main_layout->addWidget(hline); - QObject::connect(remove_btn, &QPushButton::clicked, this, &SignalEdit::remove); + QObject::connect(remove_btn, &QPushButton::clicked, [this]() { emit remove(this->sig); }); QObject::connect(title, &ElidedLabel::clicked, this, &SignalEdit::showFormClicked); - QObject::connect(save_btn, &QPushButton::clicked, [=]() { - QString new_name = form->getSignal().name.c_str(); - title->setText(QString("%1. %2").arg(index + 1).arg(new_name)); - emit save(); - sig_name = new_name; - }); - QObject::connect(seek_btn, &QPushButton::clicked, [this, msg_id, s = &sig]() { - SignalFindDlg dlg(msg_id, s, this); + QObject::connect(save_btn, &QPushButton::clicked, this, &SignalEdit::saveSignal); + QObject::connect(plot_btn, &QPushButton::clicked, [this]() { emit showChart(!chart_opened); }); + QObject::connect(seek_btn, &QPushButton::clicked, [this, msg_id]() { + SignalFindDlg dlg(msg_id, this->sig, this); dlg.exec(); }); } +void SignalEdit::saveSignal() { + Signal s = *sig; + s.name = form->name->text().toStdString(); + s.size = form->size->text().toInt(); + s.offset = form->offset->text().toDouble(); + s.factor = form->factor->text().toDouble(); + s.is_signed = form->sign->currentIndex() == 0; + s.is_little_endian = form->endianness->currentIndex() == 0; + if (s.is_little_endian) { + s.lsb = s.start_bit; + s.msb = s.start_bit + s.size - 1; + } else { + s.lsb = bigEndianStartBitsIndex(bigEndianBitIndex(s.start_bit) + s.size - 1); + s.msb = s.start_bit; + } + title->setText(QString("%1. %2").arg(form_idx + 1).arg(form->name->text())); + emit save(this->sig, s); +} + +void SignalEdit::setChartOpened(bool opened) { + plot_btn->setText(opened ? "☒" : "📈"); + plot_btn->setToolTip(opened ? tr("Close Plot") :tr("Show Plot")); + chart_opened = opened; +} + void SignalEdit::setFormVisible(bool visible) { form_container->setVisible(visible); icon->setText(visible ? "▼" : ">"); @@ -167,27 +171,7 @@ void SignalEdit::leaveEvent(QEvent *event) { QWidget::leaveEvent(event); } -// AddSignalDialog - -AddSignalDialog::AddSignalDialog(const QString &id, int start_bit, int size, QWidget *parent) : QDialog(parent) { - setWindowTitle(tr("Add signal to %1").arg(dbc()->msg(id)->name.c_str())); - QVBoxLayout *main_layout = new QVBoxLayout(this); - - Signal sig = { - .name = "untitled", - .start_bit = bigEndianBitIndex(start_bit), - .is_little_endian = false, - .size = size, - }; - form = new SignalForm(sig, this); - main_layout->addWidget(form); - auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); - main_layout->addWidget(buttonBox); - setFixedWidth(parent->width() * 0.9); - - connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); - connect(buttonBox, &QDialogButtonBox::accepted, this, &QDialog::accept); -} +// SignalFindDlg SignalFindDlg::SignalFindDlg(const QString &id, const Signal *signal, QWidget *parent) : QDialog(parent) { setWindowTitle(tr("Find signal values")); diff --git a/tools/cabana/signaledit.h b/tools/cabana/signaledit.h index 1213b3ec5..e3d38d5b2 100644 --- a/tools/cabana/signaledit.h +++ b/tools/cabana/signaledit.h @@ -15,48 +15,43 @@ class SignalForm : public QWidget { public: SignalForm(const Signal &sig, QWidget *parent); - Signal getSignal(); - QLineEdit *name, *unit, *comment, *val_desc; - QSpinBox *size, *offset; - QDoubleSpinBox *factor, *min_val, *max_val; + QLineEdit *name, *unit, *comment, *val_desc, *offset, *factor, *min_val, *max_val; + QSpinBox *size; QComboBox *sign, *endianness; - int start_bit = 0; }; class SignalEdit : public QWidget { Q_OBJECT public: - SignalEdit(int index, const QString &msg_id, const Signal &sig, QWidget *parent = nullptr); + SignalEdit(int index, const QString &msg_id, const Signal *sig, QWidget *parent = nullptr); + void setChartOpened(bool opened); void setFormVisible(bool show); void signalHovered(const Signal *sig); inline bool isFormVisible() const { return form_container->isVisible(); } - QString sig_name; - SignalForm *form; - int form_idx = 0; const Signal *sig = nullptr; signals: void highlight(const Signal *sig); - void showChart(); + void showChart(bool show); void showFormClicked(); - void remove(); - void save(); + void remove(const Signal *sig); + void save(const Signal *sig, const Signal &new_sig); protected: void enterEvent(QEvent *event) override; void leaveEvent(QEvent *event) override; + void saveSignal(); + SignalForm *form; ElidedLabel *title; QWidget *form_container; QLabel *icon; -}; - -class AddSignalDialog : public QDialog { -public: - AddSignalDialog(const QString &id, int start_bit, int size, QWidget *parent); - SignalForm *form; + int form_idx = 0; + QString msg_id; + bool chart_opened = false; + QPushButton *plot_btn; }; class SignalFindDlg : public QDialog { diff --git a/tools/cabana/tests/test_cabana b/tools/cabana/tests/test_cabana new file mode 100755 index 000000000..bac242fbd --- /dev/null +++ b/tools/cabana/tests/test_cabana @@ -0,0 +1,4 @@ +#!/bin/sh +cd "$(dirname "$0")" +export LD_LIBRARY_PATH="../../../opendbc/can:$LD_LIBRARY_PATH" +exec ./_test_cabana "$1" diff --git a/tools/cabana/tests/test_cabana.cc b/tools/cabana/tests/test_cabana.cc new file mode 100644 index 000000000..d0aa2cbb4 --- /dev/null +++ b/tools/cabana/tests/test_cabana.cc @@ -0,0 +1,35 @@ + +#include "catch2/catch.hpp" +#include "tools/cabana/dbcmanager.h" + +TEST_CASE("DBCManager::generateDBC") { + DBCManager dbc_origin(nullptr); + dbc_origin.open("toyota_new_mc_pt_generated"); + QString dbc_string = dbc_origin.generateDBC(); + + DBCManager dbc_from_generated(nullptr); + dbc_from_generated.open("", dbc_string); + + auto dbc = dbc_origin.getDBC(); + auto new_dbc = dbc_from_generated.getDBC(); + REQUIRE(dbc->msgs.size() == new_dbc->msgs.size()); + for (int i = 0; i < dbc->msgs.size(); ++i) { + REQUIRE(dbc->msgs[i].name == new_dbc->msgs[i].name); + REQUIRE(dbc->msgs[i].address == new_dbc->msgs[i].address); + REQUIRE(dbc->msgs[i].size == new_dbc->msgs[i].size); + REQUIRE(dbc->msgs[i].sigs.size() == new_dbc->msgs[i].sigs.size()); + auto &sig = dbc->msgs[i].sigs; + auto &new_sig = new_dbc->msgs[i].sigs; + for (int j = 0; j < sig.size(); ++j) { + REQUIRE(sig[j].name == new_sig[j].name); + REQUIRE(sig[j].start_bit == new_sig[j].start_bit); + REQUIRE(sig[j].msb == new_sig[j].msb); + REQUIRE(sig[j].lsb == new_sig[j].lsb); + REQUIRE(sig[j].size == new_sig[j].size); + REQUIRE(sig[j].is_signed == new_sig[j].is_signed); + REQUIRE(sig[j].factor == new_sig[j].factor); + REQUIRE(sig[j].offset == new_sig[j].offset); + REQUIRE(sig[j].is_little_endian == new_sig[j].is_little_endian); + } + } +} diff --git a/tools/cabana/tests/test_runner.cc b/tools/cabana/tests/test_runner.cc new file mode 100644 index 000000000..b20ac86c6 --- /dev/null +++ b/tools/cabana/tests/test_runner.cc @@ -0,0 +1,10 @@ +#define CATCH_CONFIG_RUNNER +#include "catch2/catch.hpp" +#include + +int main(int argc, char **argv) { + // unit tests for Qt + QCoreApplication app(argc, argv); + const int res = Catch::Session().run(argc, argv); + return (res < 0xff ? res : 0xff); +} diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc index 78965e3e8..9a28f71bb 100644 --- a/tools/cabana/videowidget.cc +++ b/tools/cabana/videowidget.cc @@ -17,7 +17,6 @@ VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) { QVBoxLayout *main_layout = new QVBoxLayout(this); main_layout->setContentsMargins(0, 0, 0, 0); - // TODO: figure out why the CameraWidget crashed occasionally. cam_widget = new CameraWidget("camerad", VISION_STREAM_ROAD, false, this); cam_widget->setFixedSize(parent->width(), parent->width() / 1.596); main_layout->addWidget(cam_widget); @@ -57,7 +56,6 @@ VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) { setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); - QObject::connect(can, &CANMessages::rangeChanged, this, &VideoWidget::rangeChanged); QObject::connect(can, &CANMessages::updated, this, &VideoWidget::updateState); QObject::connect(slider, &QSlider::sliderReleased, [this]() { can->seekTo(slider->value() / 1000.0); }); QObject::connect(slider, &QSlider::valueChanged, [=](int value) { time_label->setText(formatTime(value / 1000)); }); @@ -70,8 +68,8 @@ void VideoWidget::pause(bool pause) { can->pause(pause); } -void VideoWidget::rangeChanged(double min, double max) { - if (!can->isZoomed()) { +void VideoWidget::rangeChanged(double min, double max, bool is_zoomed) { + if (!is_zoomed) { min = 0; max = can->totalSeconds(); } diff --git a/tools/cabana/videowidget.h b/tools/cabana/videowidget.h index d6d036c46..51dae4c76 100644 --- a/tools/cabana/videowidget.h +++ b/tools/cabana/videowidget.h @@ -26,9 +26,9 @@ class VideoWidget : public QWidget { public: VideoWidget(QWidget *parnet = nullptr); + void rangeChanged(double min, double max, bool is_zommed); protected: - void rangeChanged(double min, double max); void updateState(); void pause(bool pause); diff --git a/tools/gpstest/fuzzy_testing.py b/tools/gpstest/fuzzy_testing.py index 216e7d0dd..df6691c55 100755 --- a/tools/gpstest/fuzzy_testing.py +++ b/tools/gpstest/fuzzy_testing.py @@ -66,7 +66,7 @@ def get_continuous_coords(lat, lon) -> Tuple[int, int]: return round(lat, 5), round(lon, 5) rc_p: Any = None -def exec_remote_checker(lat, lon, duration): +def exec_remote_checker(lat, lon, duration, ip_addr): global rc_p # TODO: good enough for testing remote_cmd = "export PYTHONPATH=/data/pythonpath:/data/pythonpath/pyextra && " @@ -74,8 +74,8 @@ def exec_remote_checker(lat, lon, duration): remote_cmd += f"timeout {duration} /usr/local/pyenv/shims/python tools/gpstest/remote_checker.py " remote_cmd += f"{lat} {lon}" - ssh_cmd = ['ssh', '-i', '/home/batman/openpilot/xx/phone/key/id_rsa', - 'comma@192.168.60.130'] + ssh_cmd = ["ssh", "-i", "/home/batman/openpilot/xx/phone/key/id_rsa", + f"comma@{ip_addr}"] ssh_cmd += [remote_cmd] rc_p = sp.Popen(ssh_cmd, stdout=sp.PIPE) @@ -84,8 +84,9 @@ def exec_remote_checker(lat, lon, duration): print(f"Checker Result: {rc_output.strip().decode('utf-8')}") -def run_remote_checker(spoof_proc, lat, lon, duration) -> bool: - checker_thread = threading.Thread(target=exec_remote_checker, args=(lat, lon, duration)) +def run_remote_checker(spoof_proc, lat, lon, duration, ip_addr) -> bool: + checker_thread = threading.Thread(target=exec_remote_checker, + args=(lat, lon, duration, ip_addr)) checker_thread.start() tcnt = 0 @@ -107,8 +108,12 @@ def run_remote_checker(spoof_proc, lat, lon, duration) -> bool: def main(): + if len(sys.argv) < 2: + print(f"usage: {sys.argv[0]} [-c]") + ip_addr = sys.argv[1] + continuous_mode = False - if len(sys.argv) == 2 and sys.argv[1] == '-c': + if len(sys.argv) == 3 and sys.argv[2] == '-c': print("Continuous Mode!") continuous_mode = True @@ -123,7 +128,7 @@ def main(): start_time = time.monotonic() # remote checker runs blocking - if not run_remote_checker(spoof_proc, lat, lon, duration): + if not run_remote_checker(spoof_proc, lat, lon, duration, ip_addr): # location could not be matched by ublox module pass diff --git a/tools/gpstest/remote_checker.py b/tools/gpstest/remote_checker.py index 84f6c0c3d..a649a105c 100644 --- a/tools/gpstest/remote_checker.py +++ b/tools/gpstest/remote_checker.py @@ -3,6 +3,7 @@ import sys import time from typing import List +from common.params import Params import cereal.messaging as messaging from selfdrive.manager.process_config import managed_processes @@ -12,30 +13,35 @@ procs: List[str] = []#"ubloxd", "pigeond"] def main(): - if len(sys.argv) < 3: + if len(sys.argv) != 4: print("args: ") return - sol_lat = float(sys.argv[1]) - sol_lon = float(sys.argv[2]) + quectel_mod = Params().get_bool("UbloxAvailable") + sol_lat = float(sys.argv[2]) + sol_lon = float(sys.argv[3]) for p in procs: managed_processes[p].start() time.sleep(0.5) # give time to startup - gps_sock = messaging.sub_sock('gpsLocationExternal', timeout=0.1) + socket = 'gpsLocation' if quectel_mod else 'gpsLocationExternal' + gps_sock = messaging.sub_sock(socket, timeout=0.1) # analyze until the location changed while True: events = messaging.drain_sock(gps_sock) for e in events: - lat = e.gpsLocationExternal.latitude - lon = e.gpsLocationExternal.longitude + loc = e.gpsLocation if quectel_mod else e.gpsLocationExternal + lat = loc.latitude + lon = loc.longitude if abs(lat - sol_lat) < DELTA and abs(lon - sol_lon) < DELTA: print("MATCH") return + time.sleep(0.1) + for p in procs: if not managed_processes[p].proc.is_alive(): print(f"ERROR: '{p}' died") diff --git a/tools/gpstest/run_static_gps_signal.py b/tools/gpstest/run_static_gps_signal.py deleted file mode 100755 index 3787038f1..000000000 --- a/tools/gpstest/run_static_gps_signal.py +++ /dev/null @@ -1,83 +0,0 @@ -#!/usr/bin/env python3 -import os -import sys -import random -import datetime as dt -import subprocess as sp -from typing import Tuple - -from laika.downloader import download_nav -from laika.gps_time import GPSTime -from laika.helpers import ConstellationId - -cache_dir = '/tmp/gpstest/' - - -def download_rinex(): - # TODO: check if there is a better way to get the full brdc file for LimeGPS - gps_time = GPSTime.from_datetime(dt.datetime.utcnow()) - utc_time = dt.datetime.utcnow() - dt.timedelta(1) - gps_time = GPSTime.from_datetime(dt.datetime(utc_time.year, utc_time.month, utc_time.day)) - return download_nav(gps_time, cache_dir, ConstellationId.GPS) - - -def get_random_coords(lat, lon) -> Tuple[int, int]: - # jump around the world - # max values, lat: -90 to 90, lon: -180 to 180 - - lat_add = random.random()*20 + 10 - lon_add = random.random()*20 + 20 - - lat = ((lat + lat_add + 90) % 180) - 90 - lon = ((lon + lon_add + 180) % 360) - 180 - return round(lat, 5), round(lon, 5) - - -def check_availability() -> bool: - cmd = ["LimeSuite/builddir/LimeUtil/LimeUtil", "--find"] - output = sp.check_output(cmd) - - if output.strip() == b"": - return False - - print(f"Device: {output.strip().decode('utf-8')}") - return True - - -def main(): - if not os.path.exists('LimeGPS'): - print("LimeGPS not found run 'setup.sh' first") - return - - if not os.path.exists('LimeSuite'): - print("LimeSuite not found run 'setup.sh' first") - return - - if not check_availability(): - print("No limeSDR device found!") - return - - rinex_file = download_rinex() - lat, lon = get_random_coords(47.2020, 15.7403) - - if len(sys.argv) == 3: - lat = float(sys.argv[1]) - lon = float(sys.argv[2]) - - try: - print(f"starting LimeGPS, Location: {lat},{lon}") - cmd = ["LimeGPS/LimeGPS", "-e", rinex_file, "-l", f"{lat},{lon},100"] - sp.check_output(cmd, stderr=sp.PIPE) - except KeyboardInterrupt: - print("stopping LimeGPS") - except Exception as e: - out_stderr = e.stderr.decode('utf-8')# pylint:disable=no-member - if "Device is busy." in out_stderr: - print("GPS simulation is already running, Device is busy!") - return - - print(f"LimeGPS crashed: {str(e)}") - print(f"stderr:\n{e.stderr.decode('utf-8')}")# pylint:disable=no-member - -if __name__ == "__main__": - main() diff --git a/tools/gpstest/run_unittest.sh b/tools/gpstest/run_unittest.sh new file mode 100755 index 000000000..9f93fdfc9 --- /dev/null +++ b/tools/gpstest/run_unittest.sh @@ -0,0 +1,16 @@ +#!/bin/bash + +# NOTE: can only run inside limeGPS test box! + +# run limeGPS with random static location +timeout 300 ./simulate_gps_signal.py 32.7518 -117.1962 & +gps_PID=$(ps -aux | grep -m 1 "timeout 300" | cut -d ' ' -f 7) + +echo "starting limeGPS..." +sleep 10 + +# run unit tests (skipped when module not present) +python -m unittest test_gps.py +python -m unittest test_gps_qcom.py + +kill $gps_PID diff --git a/tools/gpstest/simulate_gps_signal.py b/tools/gpstest/simulate_gps_signal.py new file mode 100755 index 000000000..f1e5ad202 --- /dev/null +++ b/tools/gpstest/simulate_gps_signal.py @@ -0,0 +1,102 @@ +#!/usr/bin/env python3 +import os +import random +import argparse +import datetime as dt +import subprocess as sp +from typing import Tuple + +from laika.downloader import download_nav +from laika.gps_time import GPSTime +from laika.helpers import ConstellationId + +cache_dir = '/tmp/gpstest/' + + +def download_rinex(): + # TODO: check if there is a better way to get the full brdc file for LimeGPS + gps_time = GPSTime.from_datetime(dt.datetime.utcnow()) + utc_time = dt.datetime.utcnow() - dt.timedelta(1) + gps_time = GPSTime.from_datetime(dt.datetime(utc_time.year, utc_time.month, utc_time.day)) + return download_nav(gps_time, cache_dir, ConstellationId.GPS) + +def get_coords(lat, lon, s1, s2, o1=0, o2=0) -> Tuple[int, int]: + lat_add = random.random()*s1 + o1 + lon_add = random.random()*s2 + o2 + + lat = ((lat + lat_add + 90) % 180) - 90 + lon = ((lon + lon_add + 180) % 360) - 180 + return round(lat, 5), round(lon, 5) + +def get_continuous_coords(lat, lon) -> Tuple[int, int]: + # continuously move around the world + return get_coords(lat, lon, 0.01, 0.01) + +def get_random_coords(lat, lon) -> Tuple[int, int]: + # jump around the world + return get_coords(lat, lon, 20, 20, 10, 20) + +def check_availability() -> bool: + cmd = ["LimeSuite/builddir/LimeUtil/LimeUtil", "--find"] + output = sp.check_output(cmd) + + if output.strip() == b"": + return False + + print(f"Device: {output.strip().decode('utf-8')}") + return True + +def main(lat, lon, jump_sim, contin_sim): + if not os.path.exists('LimeGPS'): + print("LimeGPS not found run 'setup.sh' first") + return + + if not os.path.exists('LimeSuite'): + print("LimeSuite not found run 'setup.sh' first") + return + + if not check_availability(): + print("No limeSDR device found!") + return + + rinex_file = download_rinex() + + if lat == 0 and lon == 0: + lat, lon = get_random_coords(47.2020, 15.7403) + + timeout = None + if jump_sim: + timeout = 30 + + while True: + try: + print(f"starting LimeGPS, Location: {lat},{lon}") + cmd = ["LimeGPS/LimeGPS", "-e", rinex_file, "-l", f"{lat},{lon},100"] + sp.check_output(cmd, stderr=sp.PIPE, timeout=timeout) + except KeyboardInterrupt: + print("stopping LimeGPS") + return + except sp.TimeoutExpired: + print("LimeGPS timeout reached!") + except Exception as e: + out_stderr = e.stderr.decode('utf-8')# pylint:disable=no-member + if "Device is busy." in out_stderr: + print("GPS simulation is already running, Device is busy!") + return + + print(f"LimeGPS crashed: {str(e)}") + print(f"stderr:\n{e.stderr.decode('utf-8')}")# pylint:disable=no-member + + if contin_sim: + lat, lon = get_continuous_coords(lat, lon) + else: + lat, lon = get_random_coords(lat, lon) + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description="Simulate static [or random jumping] GPS signal.") + parser.add_argument("lat", type=float, nargs='?', default=0) + parser.add_argument("lon", type=float, nargs='?', default=0) + parser.add_argument("--jump", action="store_true", help="signal that jumps around the world") + parser.add_argument("--contin", action="store_true", help="continuously/slowly moving around the world") + args = parser.parse_args() + main(args.lat, args.lon, args.jump, args.contin) diff --git a/tools/gpstest/test_gps.py b/tools/gpstest/test_gps.py index f5e19372f..8bc5dc89a 100644 --- a/tools/gpstest/test_gps.py +++ b/tools/gpstest/test_gps.py @@ -2,8 +2,8 @@ import time import unittest import struct -import numpy as np +from common.params import Params import cereal.messaging as messaging import selfdrive.sensord.pigeond as pd from system.hardware import TICI @@ -22,7 +22,20 @@ def read_events(service, duration_sec): return events -def verify_ubloxgnss_data(socket: messaging.SubSocket): +def create_backup(pigeon): + # 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 not pigeon.wait_for_ack(ack=pd.UBLOX_SOS_ACK, nack=pd.UBLOX_SOS_NACK): + assert False, "Could not store almanac" + except TimeoutError: + pass + + +def verify_ubloxgnss_data(socket: messaging.SubSocket, max_time: int): start_time = 0 end_time = 0 events = messaging.drain_sock(socket) @@ -42,7 +55,7 @@ def verify_ubloxgnss_data(socket: messaging.SubSocket): assert end_time != 0, "no ublox measurements received!" ttfm = (end_time - start_time)/1e9 - assert ttfm < 35, f"Time to first measurement > 35s, {ttfm}" + assert ttfm < max_time, f"Time to first measurement > {max_time}s, {ttfm}" # check for satellite count in measurements sat_count = [] @@ -52,42 +65,31 @@ def verify_ubloxgnss_data(socket: messaging.SubSocket): sat_count.append(event.ubloxGnss.measurementReport.numMeas) num_sat = int(sum(sat_count)/len(sat_count)) - assert num_sat > 8, f"Not enough satellites {num_sat} (TestBox setup!)" + assert num_sat >= 5, f"Not enough satellites {num_sat} (TestBox setup!)" -def verify_gps_location(socket: messaging.SubSocket): - buf_lon = [0]*10 - buf_lat = [0]*10 - buf_i = 0 +def verify_gps_location(socket: messaging.SubSocket, max_time: int): events = messaging.drain_sock(socket) assert len(events) != 0, "no gpsLocationExternal measurements" start_time = events[0].logMonoTime end_time = 0 for event in events: - buf_lon[buf_i % 10] = event.gpsLocationExternal.longitude - buf_lat[buf_i % 10] = event.gpsLocationExternal.latitude - buf_i += 1 - - if buf_i < 9: - continue + gps_valid = event.gpsLocationExternal.flags % 2 - if any([lat == 0 or lon == 0 for lat,lon in zip(buf_lat, buf_lon)]): - continue - - if np.std(buf_lon) < 1e-5 and np.std(buf_lat) < 1e-5: + if gps_valid: end_time = event.logMonoTime break assert end_time != 0, "GPS location never converged!" ttfl = (end_time - start_time)/1e9 - assert ttfl < 40, f"Time to first location > 40s, {ttfl}" + assert ttfl < max_time, f"Time to first location > {max_time}s, {ttfl}" hacc = events[-1].gpsLocationExternal.accuracy vacc = events[-1].gpsLocationExternal.verticalAccuracy - assert hacc < 15, f"Horizontal accuracy too high, {hacc}" - assert vacc < 43, f"Vertical accuracy too high, {vacc}" + assert hacc < 20, f"Horizontal accuracy too high, {hacc}" + assert vacc < 45, f"Vertical accuracy too high, {vacc}" def verify_time_to_first_fix(pigeon): @@ -111,11 +113,16 @@ class TestGPS(unittest.TestCase): if not TICI: raise unittest.SkipTest + ublox_available = Params().get_bool("UbloxAvailable") + if not ublox_available: + raise unittest.SkipTest + + def tearDown(self): pd.set_power(False) @with_processes(['ubloxd']) - def test_ublox_reset(self): + def test_a_ublox_reset(self): pigeon, pm = pd.create_pigeon() pd.init_baudrate(pigeon) @@ -127,14 +134,58 @@ class TestGPS(unittest.TestCase): gle = messaging.sub_sock("gpsLocationExternal", timeout=0.1) # receive some messages (restart after cold start takes up to 30seconds) - pd.run_receiving(pigeon, pm, 40) + pd.run_receiving(pigeon, pm, 60) + + # store almanac for next test + create_backup(pigeon) - verify_ubloxgnss_data(ugs) - verify_gps_location(gle) + verify_ubloxgnss_data(ugs, 60) + verify_gps_location(gle, 60) # skip for now, this might hang for a while #verify_time_to_first_fix(pigeon) + @with_processes(['ubloxd']) + def test_b_ublox_almanac(self): + pigeon, pm = pd.create_pigeon() + pd.init_baudrate(pigeon) + + # device cold start + pigeon.send(b"\xb5\x62\x06\x04\x04\x00\xff\xff\x00\x00\x0c\x5d") + time.sleep(1) # wait for cold start + pd.init_baudrate(pigeon) + + # clear configuration + pigeon.send_with_ack(b"\xb5\x62\x06\x09\x0d\x00\x00\x00\x1f\x1f\x00\x00\x00\x00\x00\x00\x00\x00\x17\x71\x5b") + + # restoring almanac backup + pigeon.send(b"\xB5\x62\x09\x14\x00\x00\x1D\x60") + status = pigeon.wait_for_backup_restore_status() + assert status == 2, "Could not restore almanac backup" + + pd.initialize_pigeon(pigeon) + + ugs = messaging.sub_sock("ubloxGnss", timeout=0.1) + gle = messaging.sub_sock("gpsLocationExternal", timeout=0.1) + + pd.run_receiving(pigeon, pm, 15) + verify_ubloxgnss_data(ugs, 15) + verify_gps_location(gle, 20) + + + @with_processes(['ubloxd']) + def test_c_ublox_startup(self): + pigeon, pm = pd.create_pigeon() + pd.init_baudrate(pigeon) + pd.initialize_pigeon(pigeon) + + ugs = messaging.sub_sock("ubloxGnss", timeout=0.1) + gle = messaging.sub_sock("gpsLocationExternal", timeout=0.1) + pd.run_receiving(pigeon, pm, 10) + verify_ubloxgnss_data(ugs, 10) + verify_gps_location(gle, 10) + + if __name__ == "__main__": - unittest.main() \ No newline at end of file + unittest.main() diff --git a/tools/gpstest/test_gps_qcom.py b/tools/gpstest/test_gps_qcom.py new file mode 100644 index 000000000..0909316c5 --- /dev/null +++ b/tools/gpstest/test_gps_qcom.py @@ -0,0 +1,109 @@ +#!/usr/bin/env python3 +import time +import unittest +import subprocess as sp + +from common.params import Params +from system.hardware import TICI +import cereal.messaging as messaging +from selfdrive.manager.process_config import managed_processes + + +def exec_mmcli(cmd): + cmd = "mmcli -m 0 " + cmd + p = sp.Popen(cmd, shell=True, stdout=sp.PIPE, stderr=sp.PIPE) + return p.communicate() + + +def wait_for_location(socket, timeout): + while True: + events = messaging.drain_sock(socket) + for event in events: + if event.gpsLocation.flags % 2: + return False + + timeout -= 1 + if timeout <= 0: + return True + + time.sleep(0.1) + continue + + +class TestGPS(unittest.TestCase): + @classmethod + def setUpClass(cls): + if not TICI: + raise unittest.SkipTest + + ublox_available = Params().get_bool("UbloxAvailable") + if ublox_available: + raise unittest.SkipTest + + @unittest.skip("Skip cold start test due to time") + def test_quectel_cold_start(self): + # delete assistance data to enforce cold start for GNSS + # testing shows that this takes up to 20min + + # invalidate supl setting, cannot be reset + _, err = exec_mmcli("--location-set-supl-server=unittest:1") + + _, err = exec_mmcli("--command='AT+QGPSDEL=0'") + assert len(err) == 0, f"GPSDEL failed: {err}" + + managed_processes['rawgpsd'].start() + start_time = time.monotonic() + glo = messaging.sub_sock("gpsLocation", timeout=0.1) + + timeout = 10*60*25 # 25 minute + timedout = wait_for_location(glo, timeout) + managed_processes['rawgpsd'].stop() + + assert timedout is False, "Waiting for location timed out (25min)!" + + duration = time.monotonic() - start_time + assert duration < 50, f"Received GPS location {duration}!" + + + def test_a_quectel_cold_start_AGPS(self): + _, err = exec_mmcli("--command='AT+QGPSDEL=0'") + assert len(err) == 0, f"GPSDEL failed: {err}" + + # setup AGPS + exec_mmcli("--location-set-supl-server=supl.google.com:7276") + + managed_processes['rawgpsd'].start() + start_time = time.monotonic() + glo = messaging.sub_sock("gpsLocation", timeout=0.1) + + timeout = 10*60*3 # 3 minute + timedout = wait_for_location(glo, timeout) + managed_processes['rawgpsd'].stop() + + assert timedout is False, "Waiting for location timed out (3min)!" + + duration = time.monotonic() - start_time + assert duration < 60, f"Received GPS location {duration}!" + + + def test_b_quectel_startup(self): + + # setup AGPS + exec_mmcli("--location-set-supl-server=supl.google.com:7276") + + managed_processes['rawgpsd'].start() + start_time = time.monotonic() + glo = messaging.sub_sock("gpsLocation", timeout=0.1) + + timeout = 10*60*3 # 3 minute + timedout = wait_for_location(glo, timeout) + managed_processes['rawgpsd'].stop() + + assert timedout is False, "Waiting for location timed out (3min)!" + + duration = time.monotonic() - start_time + assert duration < 60, f"Received GPS location {duration}!" + + +if __name__ == "__main__": + unittest.main() diff --git a/tools/plotjuggler/layouts/thermal_debug.xml b/tools/plotjuggler/layouts/thermal_debug.xml index cebda8175..c10b78f1c 100644 --- a/tools/plotjuggler/layouts/thermal_debug.xml +++ b/tools/plotjuggler/layouts/thermal_debug.xml @@ -1,82 +1,83 @@ - + - + - - + + - - - - - - - - + + + + + + + + - - + + - - - - + + + + - - + + - + - + - - + + - + - - + + - + + - - + + - + - + - - + + - - - - + + + + - - + + - - - - + + + + @@ -92,8 +93,8 @@ - - + + diff --git a/tools/plotjuggler/test_plotjuggler.py b/tools/plotjuggler/test_plotjuggler.py index edaec9c80..8fc032042 100755 --- a/tools/plotjuggler/test_plotjuggler.py +++ b/tools/plotjuggler/test_plotjuggler.py @@ -1,5 +1,6 @@ #!/usr/bin/env python3 import os +import glob import signal import subprocess import time @@ -9,12 +10,14 @@ from common.basedir import BASEDIR from common.timeout import Timeout from tools.plotjuggler.juggle import install +PJ_DIR = os.path.join(BASEDIR, "tools/plotjuggler") + class TestPlotJuggler(unittest.TestCase): def test_demo(self): install() - pj = os.path.join(BASEDIR, "tools/plotjuggler/juggle.py") + pj = os.path.join(PJ_DIR, "juggle.py") p = subprocess.Popen(f'QT_QPA_PLATFORM=offscreen {pj} --demo None 1 --qlog', stderr=subprocess.PIPE, shell=True, start_new_session=True) @@ -29,5 +32,22 @@ class TestPlotJuggler(unittest.TestCase): self.assertEqual(p.poll(), None) os.killpg(os.getpgid(p.pid), signal.SIGTERM) + # TODO: also test that layouts successfully load + def test_layouts(self): + bad_strings = ( + # if a previously loaded file is defined, + # PJ will throw a warning when loading the layout + "fileInfo", + "previouslyLoaded_Datafiles", + ) + for fn in glob.glob(os.path.join(PJ_DIR, "layouts/*")): + name = os.path.basename(fn) + with self.subTest(layout=name): + with open(fn) as f: + layout = f.read() + violations = [s for s in bad_strings if s in layout] + assert len(violations) == 0, f"These should be stripped out of the layout: {str(violations)}" + + if __name__ == "__main__": unittest.main() diff --git a/tools/replay/tests/test_replay.cc b/tools/replay/tests/test_replay.cc index 5b61b6b6f..30e3c811e 100644 --- a/tools/replay/tests/test_replay.cc +++ b/tools/replay/tests/test_replay.cc @@ -197,8 +197,8 @@ void TestReplay::test_seek() { stream_thread_ = new QThread(this); QEventLoop loop; std::thread thread = std::thread([&]() { - for (int i = 0; i < 50; ++i) { - testSeekTo(random_int(0, 3 * 60)); + for (int i = 0; i < 10; ++i) { + testSeekTo(random_int(0, 1 * 60)); } loop.quit(); }); @@ -207,8 +207,7 @@ void TestReplay::test_seek() { } TEST_CASE("Replay") { - auto flag = GENERATE(REPLAY_FLAG_NO_FILE_CACHE, REPLAY_FLAG_NONE); - TestReplay replay(DEMO_ROUTE, flag); + TestReplay replay(DEMO_ROUTE); REQUIRE(replay.load()); replay.test_seek(); } diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index a105ed751..f72927ba9 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -82,11 +82,10 @@ class Camerad: self.queue = cl.CommandQueue(self.ctx) cl_arg = f" -DHEIGHT={H} -DWIDTH={W} -DRGB_STRIDE={W * 3} -DUV_WIDTH={W // 2} -DUV_HEIGHT={H // 2} -DRGB_SIZE={W * H} -DCL_DEBUG " - # TODO: move rgb_to_yuv.cl to local dir once the frame stream camera is removed - kernel_fn = os.path.join(BASEDIR, "system", "camerad", "transforms", "rgb_to_yuv.cl") + kernel_fn = os.path.join(BASEDIR, "tools/sim/rgb_to_nv12.cl") with open(kernel_fn) as f: prg = cl.Program(self.ctx, f.read()).build(cl_arg) - self.krnl = prg.rgb_to_yuv + self.krnl = prg.rgb_to_nv12 self.Wdiv4 = W // 4 if (W % 4 == 0) else (W + (4 - W % 4)) // 4 self.Hdiv4 = H // 4 if (H % 4 == 0) else (H + (4 - H % 4)) // 4 diff --git a/system/camerad/transforms/rgb_to_yuv.cl b/tools/sim/rgb_to_nv12.cl similarity index 75% rename from system/camerad/transforms/rgb_to_yuv.cl rename to tools/sim/rgb_to_nv12.cl index 60dbdb4d5..54816d5d7 100644 --- a/system/camerad/transforms/rgb_to_yuv.cl +++ b/tools/sim/rgb_to_nv12.cl @@ -29,23 +29,21 @@ inline void convert_4_ys(__global uchar * out_yuv, int yi, const uchar8 rgbs1, c vstore4(yy, 0, out_yuv + yi); } -inline void convert_uv(__global uchar * out_yuv, int ui, int vi, +inline void convert_uv(__global uchar * out_yuv, int uvi, const uchar8 rgbs1, const uchar8 rgbs2) { // U & V: average of 2x2 pixels square const short ab = AVERAGE(rgbs1.s0, rgbs1.s3, rgbs2.s0, rgbs2.s3); const short ag = AVERAGE(rgbs1.s1, rgbs1.s4, rgbs2.s1, rgbs2.s4); const short ar = AVERAGE(rgbs1.s2, rgbs1.s5, rgbs2.s2, rgbs2.s5); #ifdef CL_DEBUG - if(ui >= RGB_SIZE + RGB_SIZE / 4) - printf("U overflow, %d >= %d\n", ui, RGB_SIZE + RGB_SIZE / 4); - if(vi >= RGB_SIZE + RGB_SIZE / 2) - printf("V overflow, %d >= %d\n", vi, RGB_SIZE + RGB_SIZE / 2); + if(uvi >= RGB_SIZE + RGB_SIZE / 2) + printf("UV overflow, %d >= %d\n", uvi, RGB_SIZE + RGB_SIZE / 2); #endif - out_yuv[ui] = RGB_TO_U(ar, ag, ab); - out_yuv[vi] = RGB_TO_V(ar, ag, ab); + out_yuv[uvi] = RGB_TO_U(ar, ag, ab); + out_yuv[uvi+1] = RGB_TO_V(ar, ag, ab); } -inline void convert_2_uvs(__global uchar * out_yuv, int ui, int vi, +inline void convert_2_uvs(__global uchar * out_yuv, int uvi, const uchar8 rgbs1, const uchar8 rgbs2, const uchar8 rgbs3, const uchar8 rgbs4) { // U & V: average of 2x2 pixels square const short ab1 = AVERAGE(rgbs1.s0, rgbs1.s3, rgbs2.s0, rgbs2.s3); @@ -54,25 +52,20 @@ inline void convert_2_uvs(__global uchar * out_yuv, int ui, int vi, const short ab2 = AVERAGE(rgbs1.s6, rgbs3.s1, rgbs2.s6, rgbs4.s1); const short ag2 = AVERAGE(rgbs1.s7, rgbs3.s2, rgbs2.s7, rgbs4.s2); const short ar2 = AVERAGE(rgbs3.s0, rgbs3.s3, rgbs4.s0, rgbs4.s3); - uchar2 u2 = (uchar2)( + uchar4 uv = (uchar4)( RGB_TO_U(ar1, ag1, ab1), - RGB_TO_U(ar2, ag2, ab2) - ); - uchar2 v2 = (uchar2)( RGB_TO_V(ar1, ag1, ab1), + RGB_TO_U(ar2, ag2, ab2), RGB_TO_V(ar2, ag2, ab2) ); #ifdef CL_DEBUG1 - if(ui > RGB_SIZE + RGB_SIZE / 4 - 2) - printf("U 2 overflow, %d >= %d\n", ui, RGB_SIZE + RGB_SIZE / 4 - 2); - if(vi > RGB_SIZE + RGB_SIZE / 2 - 2) - printf("V 2 overflow, %d >= %d\n", vi, RGB_SIZE + RGB_SIZE / 2 - 2); + if(uvi > RGB_SIZE + RGB_SIZE / 2 - 4) + printf("UV2 overflow, %d >= %d\n", uvi, RGB_SIZE + RGB_SIZE / 2 - 2); #endif - vstore2(u2, 0, out_yuv + ui); - vstore2(v2, 0, out_yuv + vi); + vstore4(uv, 0, out_yuv + uvi); } -__kernel void rgb_to_yuv(__global uchar const * const rgb, +__kernel void rgb_to_nv12(__global uchar const * const rgb, __global uchar * out_yuv) { const int dx = get_global_id(0); @@ -81,8 +74,7 @@ __kernel void rgb_to_yuv(__global uchar const * const rgb, const int row = mul24(dy, 4); // Current row in rgb image const int bgri_start = mad24(row, RGB_STRIDE, mul24(col, 3)); // Start offset of rgb data being converted const int yi_start = mad24(row, WIDTH, col); // Start offset in the target yuv buffer - int ui = mad24(row / 2, UV_WIDTH, RGB_SIZE + col / 2); - int vi = mad24(row / 2 , UV_WIDTH, RGB_SIZE + UV_WIDTH * UV_HEIGHT + col / 2); + int uvi = mad24(row / 2, WIDTH, RGB_SIZE + col); int num_col = min(WIDTH - col, 4); int num_row = min(HEIGHT - row, 4); if(num_row == 4) { @@ -99,15 +91,15 @@ __kernel void rgb_to_yuv(__global uchar const * const rgb, convert_4_ys(out_yuv, yi_start + WIDTH, rgbs1_0, rgbs1_1); convert_4_ys(out_yuv, yi_start + WIDTH * 2, rgbs2_0, rgbs2_1); convert_4_ys(out_yuv, yi_start + WIDTH * 3, rgbs3_0, rgbs3_1); - convert_2_uvs(out_yuv, ui, vi, rgbs0_0, rgbs1_0, rgbs0_1, rgbs1_1); - convert_2_uvs(out_yuv, ui + UV_WIDTH, vi + UV_WIDTH, rgbs2_0, rgbs3_0, rgbs2_1, rgbs3_1); + convert_2_uvs(out_yuv, uvi, rgbs0_0, rgbs1_0, rgbs0_1, rgbs1_1); + convert_2_uvs(out_yuv, uvi + WIDTH, rgbs2_0, rgbs3_0, rgbs2_1, rgbs3_1); } else if(num_col == 2) { convert_2_ys(out_yuv, yi_start, rgbs0_0); convert_2_ys(out_yuv, yi_start + WIDTH, rgbs1_0); convert_2_ys(out_yuv, yi_start + WIDTH * 2, rgbs2_0); convert_2_ys(out_yuv, yi_start + WIDTH * 3, rgbs3_0); - convert_uv(out_yuv, ui, vi, rgbs0_0, rgbs1_0); - convert_uv(out_yuv, ui + UV_WIDTH, vi + UV_WIDTH, rgbs2_0, rgbs3_0); + convert_uv(out_yuv, uvi, rgbs0_0, rgbs1_0); + convert_uv(out_yuv, uvi + WIDTH, rgbs2_0, rgbs3_0); } } else { const uchar8 rgbs0_0 = vload8(0, rgb + bgri_start); @@ -117,11 +109,11 @@ __kernel void rgb_to_yuv(__global uchar const * const rgb, if(num_col == 4) { convert_4_ys(out_yuv, yi_start, rgbs0_0, rgbs0_1); convert_4_ys(out_yuv, yi_start + WIDTH, rgbs1_0, rgbs1_1); - convert_2_uvs(out_yuv, ui, vi, rgbs0_0, rgbs1_0, rgbs0_1, rgbs1_1); + convert_2_uvs(out_yuv, uvi, rgbs0_0, rgbs1_0, rgbs0_1, rgbs1_1); } else if(num_col == 2) { convert_2_ys(out_yuv, yi_start, rgbs0_0); convert_2_ys(out_yuv, yi_start + WIDTH, rgbs1_0); - convert_uv(out_yuv, ui, vi, rgbs0_0, rgbs1_0); + convert_uv(out_yuv, uvi, rgbs0_0, rgbs1_0); } } } diff --git a/update_requirements.sh b/update_requirements.sh index 0967e2dc6..8511a0a4d 100755 --- a/update_requirements.sh +++ b/update_requirements.sh @@ -60,6 +60,7 @@ if [ -d "./xx" ] || [ -n "$POETRY_VIRTUALENVS_CREATE" ]; then RUN="" else echo "PYTHONPATH=${PWD}" > .env + poetry self add poetry-dotenv-plugin@^0.1.0 RUN="poetry run" fi