Merge remote-tracking branch 'upstream/master' into ui_accel_gradient

pull/27391/head
Shane Smiskol 2 years ago
commit 2e30dfc183
  1. 2
      RELEASES.md
  2. 2
      common/params.cc
  3. 2
      panda
  4. 2
      release/check-submodules.sh
  5. BIN
      selfdrive/assets/img_driver_face.png
  6. BIN
      selfdrive/assets/img_driver_face_static.png
  7. 40
      selfdrive/car/__init__.py
  8. 4
      selfdrive/car/chrysler/carcontroller.py
  9. 5
      selfdrive/car/ford/values.py
  10. 4
      selfdrive/car/gm/carcontroller.py
  11. 43
      selfdrive/car/gm/interface.py
  12. 4
      selfdrive/car/gm/values.py
  13. 4
      selfdrive/car/hyundai/carcontroller.py
  14. 4
      selfdrive/car/interfaces.py
  15. 6
      selfdrive/car/mazda/carcontroller.py
  16. 4
      selfdrive/car/subaru/carcontroller.py
  17. 4
      selfdrive/car/toyota/carcontroller.py
  18. 4
      selfdrive/car/volkswagen/carcontroller.py
  19. 5
      selfdrive/car/volkswagen/values.py
  20. 5
      selfdrive/controls/controlsd.py
  21. 4
      selfdrive/controls/lib/events.py
  22. 4
      selfdrive/controls/lib/latcontrol_torque.py
  23. 2
      selfdrive/locationd/laikad.py
  24. 8
      selfdrive/loggerd/tests/test_loggerd.py
  25. 2
      selfdrive/test/process_replay/ref_commit
  26. 2
      selfdrive/ui/qt/offroad/driverview.cc
  27. 49
      selfdrive/ui/qt/setup/reset.cc
  28. 11
      selfdrive/ui/qt/setup/reset.h
  29. 47
      selfdrive/ui/qt/setup/setup.cc
  30. 5
      selfdrive/ui/qt/setup/setup.h
  31. 29
      selfdrive/ui/translations/main_de.ts
  32. 29
      selfdrive/ui/translations/main_ja.ts
  33. 32
      selfdrive/ui/translations/main_ko.ts
  34. 29
      selfdrive/ui/translations/main_pt-BR.ts
  35. 29
      selfdrive/ui/translations/main_zh-CHS.ts
  36. 29
      selfdrive/ui/translations/main_zh-CHT.ts
  37. 7
      tools/cabana/binaryview.cc
  38. 188
      tools/cabana/chartswidget.cc
  39. 19
      tools/cabana/chartswidget.h
  40. 14
      tools/cabana/historylog.cc
  41. 37
      tools/cabana/mainwin.cc
  42. 3
      tools/cabana/mainwin.h
  43. 35
      tools/cabana/messageswidget.cc
  44. 2
      tools/cabana/messageswidget.h
  45. 2
      tools/cabana/settings.cc
  46. 64
      tools/cabana/signaledit.cc
  47. 2
      tools/cabana/signaledit.h
  48. 36
      tools/cabana/util.cc
  49. 9
      tools/cabana/util.h
  50. 2
      tools/gpstest/rpc_server.py
  51. 2
      tools/gpstest/test_laikad.py

@ -2,7 +2,7 @@ Version 0.9.2 (2023-03-XX)
========================
* Draw MPC path instead of model predicted path, this is a more accurate representation of what the car will do.
Version 0.9.1 (2023-02-23)
Version 0.9.1 (2023-02-28)
========================
* New driving model
* 30% improved height estimation resulting in better driving performance for tall cars

@ -138,7 +138,7 @@ std::unordered_map<std::string, uint32_t> keys = {
{"IsReleaseBranch", CLEAR_ON_MANAGER_START},
{"IsUpdateAvailable", CLEAR_ON_MANAGER_START},
{"JoystickDebugMode", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF},
{"LaikadEphemeris", PERSISTENT | DONT_LOG},
{"LaikadEphemerisV2", PERSISTENT | DONT_LOG},
{"LanguageSetting", PERSISTENT},
{"LastAthenaPingTime", CLEAR_ON_MANAGER_START},
{"LastGPSPosition", PERSISTENT},

@ -1 +1 @@
Subproject commit d2c2d5f926537a132a253277998ef350fe866d27
Subproject commit 1923b1418933e464ff7460a3e0a05d63aad0d53b

@ -1,7 +1,7 @@
#!/bin/bash
while read hash submodule ref; do
git -C $submodule fetch --depth 300 origin master
git -C $submodule fetch --depth 1000 origin master
git -C $submodule branch -r --contains $hash | grep "origin/master"
if [ "$?" -eq 0 ]; then
echo "$submodule ok"

Binary file not shown.

Before

Width:  |  Height:  |  Size: 19 KiB

After

Width:  |  Height:  |  Size: 3.7 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.8 KiB

@ -73,7 +73,7 @@ def dbc_dict(pt_dbc, radar_dbc, chassis_dbc=None, body_dbc=None) -> Dict[str, st
return {'pt': pt_dbc, 'radar': radar_dbc, 'chassis': chassis_dbc, 'body': body_dbc}
def apply_std_steer_torque_limits(apply_torque, apply_torque_last, driver_torque, LIMITS):
def apply_driver_steer_torque_limits(apply_torque, apply_torque_last, driver_torque, LIMITS):
# limits due to driver torque
driver_max_torque = LIMITS.STEER_MAX + (LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER
@ -93,29 +93,37 @@ def apply_std_steer_torque_limits(apply_torque, apply_torque_last, driver_torque
return int(round(float(apply_torque)))
def apply_toyota_steer_torque_limits(apply_torque, apply_torque_last, motor_torque, LIMITS):
# limits due to comparison of commanded torque VS motor reported torque
max_lim = min(max(motor_torque + LIMITS.STEER_ERROR_MAX, LIMITS.STEER_ERROR_MAX), LIMITS.STEER_MAX)
min_lim = max(min(motor_torque - LIMITS.STEER_ERROR_MAX, -LIMITS.STEER_ERROR_MAX), -LIMITS.STEER_MAX)
def apply_dist_to_meas_limits(val, val_last, val_meas,
STEER_DELTA_UP, STEER_DELTA_DOWN,
STEER_ERROR_MAX, STEER_MAX):
# limits due to comparison of commanded val VS measured val (torque/angle/curvature)
max_lim = min(max(val_meas + STEER_ERROR_MAX, STEER_ERROR_MAX), STEER_MAX)
min_lim = max(min(val_meas - STEER_ERROR_MAX, -STEER_ERROR_MAX), -STEER_MAX)
apply_torque = clip(apply_torque, min_lim, max_lim)
val = clip(val, min_lim, max_lim)
# slow rate if steer torque increases in magnitude
if apply_torque_last > 0:
apply_torque = clip(apply_torque,
max(apply_torque_last - LIMITS.STEER_DELTA_DOWN, -LIMITS.STEER_DELTA_UP),
apply_torque_last + LIMITS.STEER_DELTA_UP)
# slow rate if val increases in magnitude
if val_last > 0:
val = clip(val,
max(val_last - STEER_DELTA_DOWN, -STEER_DELTA_UP),
val_last + STEER_DELTA_UP)
else:
apply_torque = clip(apply_torque,
apply_torque_last - LIMITS.STEER_DELTA_UP,
min(apply_torque_last + LIMITS.STEER_DELTA_DOWN, LIMITS.STEER_DELTA_UP))
val = clip(val,
val_last - STEER_DELTA_UP,
min(val_last + STEER_DELTA_DOWN, STEER_DELTA_UP))
return int(round(float(apply_torque)))
return float(val)
def apply_meas_steer_torque_limits(apply_torque, apply_torque_last, motor_torque, LIMITS):
return int(round(apply_dist_to_meas_limits(apply_torque, apply_torque_last, motor_torque,
LIMITS.STEER_DELTA_UP, LIMITS.STEER_DELTA_DOWN,
LIMITS.STEER_ERROR_MAX, LIMITS.STEER_MAX)))
def apply_std_steer_angle_limits(apply_angle, apply_angle_last, v_ego, LIMITS):
# pick angle rate limits based on wind up/down
steer_up = apply_angle_last * apply_angle > 0. and abs(apply_angle) > abs(apply_angle_last)
steer_up = apply_angle_last * apply_angle >= 0. and abs(apply_angle) > abs(apply_angle_last)
rate_limits = LIMITS.ANGLE_RATE_LIMIT_UP if steer_up else LIMITS.ANGLE_RATE_LIMIT_DOWN
angle_rate_lim = interp(v_ego, rate_limits.speed_bp, rate_limits.angle_v)

@ -1,6 +1,6 @@
from opendbc.can.packer import CANPacker
from common.realtime import DT_CTRL
from selfdrive.car import apply_toyota_steer_torque_limits
from selfdrive.car import apply_meas_steer_torque_limits
from selfdrive.car.chrysler.chryslercan import create_lkas_hud, create_lkas_command, create_cruise_buttons
from selfdrive.car.chrysler.values import RAM_CARS, CarControllerParams, ChryslerFlags
@ -67,7 +67,7 @@ class CarController:
# steer torque
new_steer = int(round(CC.actuators.steer * self.params.STEER_MAX))
apply_steer = apply_toyota_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, self.params)
apply_steer = apply_meas_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, self.params)
if not lkas_active or not lkas_control_bit:
apply_steer = 0
self.apply_steer_last = apply_steer

@ -28,8 +28,9 @@ class CarControllerParams:
# Curvature rate limits
# TODO: unify field names used by curvature and angle control cars
ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[5, 15, 25], angle_v=[0.005, 0.00056, 0.0002])
ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[5, 15, 25], angle_v=[0.008, 0.00089, 0.00032])
# ~2 m/s^3 up, ~-3 m/s^3 down
ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[5, 15, 25], angle_v=[0.004, 0.00044, 0.00016])
ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[5, 15, 25], angle_v=[0.006, 0.00066, 0.00024])
ACCEL_MAX = 2.0 # m/s^s max acceleration
ACCEL_MIN = -3.5 # m/s^s max deceleration

@ -3,7 +3,7 @@ from common.conversions import Conversions as CV
from common.numpy_fast import interp
from common.realtime import DT_CTRL
from opendbc.can.packer import CANPacker
from selfdrive.car import apply_std_steer_torque_limits
from selfdrive.car import apply_driver_steer_torque_limits
from selfdrive.car.gm import gmcan
from selfdrive.car.gm.values import DBC, CanBus, CarControllerParams, CruiseButtons
@ -73,7 +73,7 @@ class CarController:
if CC.latActive:
new_steer = int(round(actuators.steer * self.params.STEER_MAX))
apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params)
apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params)
else:
apply_steer = 0

@ -3,13 +3,11 @@ from cereal import car
from math import fabs
from panda import Panda
from common.numpy_fast import interp
from common.conversions import Conversions as CV
from selfdrive.car import STD_CARGO_KG, create_button_event, scale_tire_stiffness, get_safety_config
from selfdrive.car.gm.radar_interface import RADAR_HEADER_MSG
from selfdrive.car.gm.values import CAR, CruiseButtons, CarControllerParams, EV_CAR, CAMERA_ACC_CAR, CanBus
from selfdrive.car.interfaces import CarInterfaceBase, TorqueFromLateralAccelCallbackType, FRICTION_THRESHOLD
from selfdrive.controls.lib.drive_helpers import apply_center_deadzone
from selfdrive.car.interfaces import CarInterfaceBase
ButtonType = car.CarState.ButtonEvent.Type
EventName = car.CarEvent.EventName
@ -46,43 +44,6 @@ class CarInterface(CarInterfaceBase):
else:
return CarInterfaceBase.get_steer_feedforward_default
@staticmethod
def torque_from_lateral_accel_bolt(lateral_accel_value, torque_params, lateral_accel_error, lateral_accel_deadzone, vego, friction_compensation):
friction_interp = interp(
apply_center_deadzone(lateral_accel_error, lateral_accel_deadzone),
[-FRICTION_THRESHOLD, FRICTION_THRESHOLD],
[-torque_params.friction, torque_params.friction]
)
friction = friction_interp if friction_compensation else 0.0
steer_torque = lateral_accel_value / torque_params.latAccelFactor
# TODO:
# 1. Learn the correction factors from data
# 2. Generalize the logic to other GM torque control platforms
steer_break_pts = [-1.0, -0.9, -0.75, -0.5, 0.0, 0.5, 0.75, 0.9, 1.0]
steer_lataccel_factors = [1.5, 1.15, 1.02, 1.0, 1.0, 1.0, 1.02, 1.15, 1.5]
steer_correction_factor = interp(
steer_torque,
steer_break_pts,
steer_lataccel_factors
)
vego_break_pts = [0.0, 10.0, 15.0, 20.0, 100.0]
vego_lataccel_factors = [1.5, 1.5, 1.25, 1.0, 1.0]
vego_correction_factor = interp(
vego,
vego_break_pts,
vego_lataccel_factors,
)
return (steer_torque + friction) / (steer_correction_factor * vego_correction_factor)
def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType:
if self.CP.carFingerprint == CAR.BOLT_EUV:
return self.torque_from_lateral_accel_bolt
else:
return self.torque_from_lateral_accel_linear
@staticmethod
def _get_params(ret, candidate, fingerprint, car_fw, experimental_long):
ret.carName = "gm"
@ -227,7 +188,7 @@ class CarInterface(CarInterfaceBase):
ret.steerRatio = 16.8
ret.centerToFront = ret.wheelbase * 0.4
tire_stiffness_factor = 1.0
ret.steerActuatorDelay = 0.12
ret.steerActuatorDelay = 0.2
CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning)
elif candidate == CAR.SILVERADO:

@ -14,8 +14,8 @@ class CarControllerParams:
STEER_STEP = 3 # Active control frames per command (~33hz)
INACTIVE_STEER_STEP = 10 # Inactive control frames per command (10hz)
STEER_DELTA_UP = 10 # Delta rates require review due to observed EPS weakness
STEER_DELTA_DOWN = 15
STEER_DRIVER_ALLOWANCE = 65
STEER_DELTA_DOWN = 25
STEER_DRIVER_ALLOWANCE = 50
STEER_DRIVER_MULTIPLIER = 4
STEER_DRIVER_FACTOR = 100
NEAR_STOP_BRAKE_PHASE = 0.5 # m/s

@ -3,7 +3,7 @@ from common.conversions import Conversions as CV
from common.numpy_fast import clip
from common.realtime import DT_CTRL
from opendbc.can.packer import CANPacker
from selfdrive.car import apply_std_steer_torque_limits
from selfdrive.car import apply_driver_steer_torque_limits
from selfdrive.car.hyundai import hyundaicanfd, hyundaican
from selfdrive.car.hyundai.values import HyundaiFlags, Buttons, CarControllerParams, CANFD_CAR, CAR
@ -60,7 +60,7 @@ class CarController:
# steering torque
new_steer = int(round(actuators.steer * self.params.STEER_MAX))
apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params)
apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params)
if not CC.latActive:
apply_steer = 0

@ -18,7 +18,7 @@ from selfdrive.controls.lib.vehicle_model import VehicleModel
ButtonType = car.CarState.ButtonEvent.Type
GearShifter = car.CarState.GearShifter
EventName = car.CarEvent.EventName
TorqueFromLateralAccelCallbackType = Callable[[float, car.CarParams.LateralTorqueTuning, float, float, float, bool], float]
TorqueFromLateralAccelCallbackType = Callable[[float, car.CarParams.LateralTorqueTuning, float, float, bool], float]
MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS
ACCEL_MAX = 2.0
@ -131,7 +131,7 @@ class CarInterfaceBase(ABC):
return self.get_steer_feedforward_default
@staticmethod
def torque_from_lateral_accel_linear(lateral_accel_value, torque_params, lateral_accel_error, lateral_accel_deadzone, vego, friction_compensation):
def torque_from_lateral_accel_linear(lateral_accel_value, torque_params, lateral_accel_error, lateral_accel_deadzone, friction_compensation):
# The default is a linear relationship between torque and lateral acceleration (accounting for road roll and steering friction)
friction_interp = interp(
apply_center_deadzone(lateral_accel_error, lateral_accel_deadzone),

@ -1,6 +1,6 @@
from cereal import car
from opendbc.can.packer import CANPacker
from selfdrive.car import apply_std_steer_torque_limits
from selfdrive.car import apply_driver_steer_torque_limits
from selfdrive.car.mazda import mazdacan
from selfdrive.car.mazda.values import CarControllerParams, Buttons
@ -23,8 +23,8 @@ class CarController:
if CC.latActive:
# calculate steer and also set limits due to driver torque
new_steer = int(round(CC.actuators.steer * CarControllerParams.STEER_MAX))
apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last,
CS.out.steeringTorque, CarControllerParams)
apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last,
CS.out.steeringTorque, CarControllerParams)
if CC.cruiseControl.cancel:
# If brake is pressed, let us wait >70ms before trying to disable crz to avoid

@ -1,5 +1,5 @@
from opendbc.can.packer import CANPacker
from selfdrive.car import apply_std_steer_torque_limits
from selfdrive.car import apply_driver_steer_torque_limits
from selfdrive.car.subaru import subarucan
from selfdrive.car.subaru.values import DBC, GLOBAL_GEN2, PREGLOBAL_CARS, CarControllerParams
@ -34,7 +34,7 @@ class CarController:
# limits due to driver torque
new_steer = int(round(apply_steer))
apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.p)
apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.p)
if not CC.latActive:
apply_steer = 0

@ -1,6 +1,6 @@
from cereal import car
from common.numpy_fast import clip, interp
from selfdrive.car import apply_toyota_steer_torque_limits, create_gas_interceptor_command, make_can_msg
from selfdrive.car import apply_meas_steer_torque_limits, create_gas_interceptor_command, make_can_msg
from selfdrive.car.toyota.toyotacan import create_steer_command, create_ui_command, \
create_accel_command, create_acc_cancel_command, \
create_fcw_command, create_lta_steer_command
@ -60,7 +60,7 @@ class CarController:
# steer torque
new_steer = int(round(actuators.steer * CarControllerParams.STEER_MAX))
apply_steer = apply_toyota_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.torque_rate_limits)
apply_steer = apply_meas_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.torque_rate_limits)
# Count up to MAX_STEER_RATE_FRAMES, at which point we need to cut torque to avoid a steering fault
if lat_active and abs(CS.out.steeringRateDeg) >= MAX_STEER_RATE:

@ -3,7 +3,7 @@ from opendbc.can.packer import CANPacker
from common.numpy_fast import clip
from common.conversions import Conversions as CV
from common.realtime import DT_CTRL
from selfdrive.car import apply_std_steer_torque_limits
from selfdrive.car import apply_driver_steer_torque_limits
from selfdrive.car.volkswagen import mqbcan, pqcan
from selfdrive.car.volkswagen.values import CANBUS, PQ_CARS, CarControllerParams
@ -44,7 +44,7 @@ class CarController:
if CC.latActive:
new_steer = int(round(actuators.steer * self.CCP.STEER_MAX))
apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.CCP)
apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.CCP)
if apply_steer == 0:
hcaEnabled = False
self.hcaEnabledFrameCount = 0

@ -1050,6 +1050,7 @@ FW_VERSIONS = {
b'\xf1\x8704E906027DD\xf1\x893123',
b'\xf1\x8704L906026DE\xf1\x895418',
b'\xf1\x875NA907115E \xf1\x890003',
b'\xf1\x875NA907115E \xf1\x890005',
],
(Ecu.transmission, 0x7e1, None): [
b'\xf1\x870D9300043 \xf1\x895202',
@ -1058,8 +1059,8 @@ FW_VERSIONS = {
b'\xf1\x870DL300013G \xf1\x892119',
],
(Ecu.srs, 0x715, None): [
b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\0161213001211001205212111052100',
b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\0161213001211001205212112052100',
b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e1213001211001205212111052100',
b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e1213001211001205212112052100',
b'\xf1\x873Q0959655CQ\xf1\x890720\xf1\x82\x0e1213111211001205212112052111',
],
(Ecu.eps, 0x712, None): [

@ -280,8 +280,9 @@ class Controls:
# Alert if fan isn't spinning for 5 seconds
if self.sm['peripheralState'].pandaType != log.PandaState.PandaType.unknown:
if self.sm['peripheralState'].fanSpeedRpm == 0 and self.sm['deviceState'].fanSpeedPercentDesired > 50:
if (self.sm.frame - self.last_functional_fan_frame) * DT_CTRL > 5.0:
if self.sm['peripheralState'].fanSpeedRpm < 500 and self.sm['deviceState'].fanSpeedPercentDesired > 50:
# allow enough time for the fan controller in the panda to recover from stalls
if (self.sm.frame - self.last_functional_fan_frame) * DT_CTRL > 15.0:
self.events.add(EventName.fanMalfunction)
else:
self.last_functional_fan_frame = self.sm.frame

@ -317,9 +317,9 @@ def modeld_lagging_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubM
def wrong_car_mode_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert:
text = "Cruise Mode Disabled"
text = "Enable Adaptive Cruise to Engage"
if CP.carName == "honda":
text = "Main Switch Off"
text = "Enable Main Switch to Engage"
return NoEntryAlert(text)

@ -64,10 +64,10 @@ class LatControlTorque(LatControl):
error = setpoint - measurement
gravity_adjusted_lateral_accel = desired_lateral_accel - params.roll * ACCELERATION_DUE_TO_GRAVITY
pid_log.error = self.torque_from_lateral_accel(error, self.torque_params, error,
lateral_accel_deadzone, CS.vEgo, friction_compensation=False)
lateral_accel_deadzone, friction_compensation=False)
ff = self.torque_from_lateral_accel(gravity_adjusted_lateral_accel, self.torque_params,
desired_lateral_accel - actual_lateral_accel,
lateral_accel_deadzone, CS.vEgo, friction_compensation=True)
lateral_accel_deadzone, friction_compensation=True)
freeze_integrator = steer_limited or CS.steeringPressed or CS.vEgo < 5
output_torque = self.pid.update(pid_log.error,

@ -28,7 +28,7 @@ from selfdrive.locationd.models.gnss_kf import States as GStates
from system.swaglog import cloudlog
MAX_TIME_GAP = 10
EPHEMERIS_CACHE = 'LaikadEphemeris'
EPHEMERIS_CACHE = 'LaikadEphemerisV2'
DOWNLOADS_CACHE_FOLDER = "/tmp/comma_download_cache/"
CACHE_VERSION = 0.2
POS_FIX_RESIDUAL_THRESHOLD = 100.0

@ -86,7 +86,7 @@ class TestLoggerd(unittest.TestCase):
params.clear_all()
for k, _, v in fake_params:
params.put(k, v)
params.put("LaikadEphemeris", "abc")
params.put("LaikadEphemerisV2", "abc")
lr = list(LogReader(str(self._gen_bootlog())))
initData = lr[0].initData
@ -103,14 +103,14 @@ class TestLoggerd(unittest.TestCase):
# check params
logged_params = {entry.key: entry.value for entry in initData.params.entries}
expected_params = set(k for k, _, __ in fake_params) | {'LaikadEphemeris'}
expected_params = set(k for k, _, __ in fake_params) | {'LaikadEphemerisV2'}
assert set(logged_params.keys()) == expected_params, set(logged_params.keys()) ^ expected_params
assert logged_params['LaikadEphemeris'] == b'', f"DONT_LOG param value was logged: {repr(logged_params['LaikadEphemeris'])}"
assert logged_params['LaikadEphemerisV2'] == b'', f"DONT_LOG param value was logged: {repr(logged_params['LaikadEphemerisV2'])}"
for param_key, initData_key, v in fake_params:
self.assertEqual(getattr(initData, initData_key), v)
self.assertEqual(logged_params[param_key].decode(), v)
params.put("LaikadEphemeris", "")
params.put("LaikadEphemerisV2", "")
def test_rotation(self):
os.environ["LOGGERD_TEST"] = "1"

@ -1 +1 @@
f7ff7e7d37c276c31d8d44c73a0091b5996650b1
772f30de36fc7f8421dabb779cc02f45eb83d7bb

@ -27,7 +27,7 @@ void DriverViewWindow::mouseReleaseEvent(QMouseEvent* e) {
}
DriverViewScene::DriverViewScene(QWidget* parent) : sm({"driverStateV2"}), QWidget(parent) {
face_img = loadPixmap("../assets/img_driver_face.png", {FACE_IMG_SIZE, FACE_IMG_SIZE});
face_img = loadPixmap("../assets/img_driver_face_static.png", {FACE_IMG_SIZE, FACE_IMG_SIZE});
}
void DriverViewScene::showEvent(QShowEvent* event) {

@ -11,14 +11,11 @@
#define NVME "/dev/nvme0n1"
#define USERDATA "/dev/disk/by-partlabel/userdata"
void Reset::doReset() {
// best effort to wipe nvme and sd card
void Reset::doErase() {
// best effort to wipe nvme
std::system("sudo umount " NVME);
std::system("yes | sudo mkfs.ext4 " NVME);
// we handle two cases here
// * user-prompted factory reset
// * recovering from a corrupt userdata by formatting
int rm = std::system("sudo rm -rf /data/*");
std::system("sudo umount " USERDATA);
int fmt = std::system("yes | sudo mkfs.ext4 " USERDATA);
@ -30,22 +27,26 @@ void Reset::doReset() {
rebootBtn->show();
}
void Reset::startReset() {
body->setText(tr("Resetting device...\nThis may take up to a minute."));
rejectBtn->hide();
rebootBtn->hide();
confirmBtn->hide();
#ifdef __aarch64__
QTimer::singleShot(100, this, &Reset::doErase);
#endif
}
void Reset::confirm() {
const QString confirm_txt = tr("Are you sure you want to reset your device?");
if (body->text() != confirm_txt) {
body->setText(confirm_txt);
} else {
body->setText(tr("Resetting device..."));
rejectBtn->hide();
rebootBtn->hide();
confirmBtn->hide();
#ifdef __aarch64__
QTimer::singleShot(100, this, &Reset::doReset);
#endif
startReset();
}
}
Reset::Reset(bool recover, QWidget *parent) : QWidget(parent) {
Reset::Reset(ResetMode mode, QWidget *parent) : QWidget(parent) {
QVBoxLayout *main_layout = new QVBoxLayout(this);
main_layout->setContentsMargins(45, 220, 45, 45);
main_layout->setSpacing(0);
@ -56,7 +57,7 @@ Reset::Reset(bool recover, QWidget *parent) : QWidget(parent) {
main_layout->addSpacing(60);
body = new QLabel(tr("System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot."));
body = new QLabel(tr("Press confirm to erase all content and settings. Press cancel to resume boot."));
body->setWordWrap(true);
body->setStyleSheet("font-size: 80px; font-weight: light;");
main_layout->addWidget(body, 1, Qt::AlignTop | Qt::AlignLeft);
@ -82,10 +83,16 @@ Reset::Reset(bool recover, QWidget *parent) : QWidget(parent) {
blayout->addWidget(confirmBtn);
QObject::connect(confirmBtn, &QPushButton::clicked, this, &Reset::confirm);
bool recover = mode == ResetMode::RECOVER;
rejectBtn->setVisible(!recover);
rebootBtn->setVisible(recover);
if (recover) {
body->setText(tr("Unable to mount data partition. Press confirm to reset your device."));
body->setText(tr("Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device."));
}
// automatically start if we're just finishing up an ABL reset
if (mode == ResetMode::FORMAT) {
startReset();
}
setStyleSheet(R"(
@ -108,9 +115,17 @@ Reset::Reset(bool recover, QWidget *parent) : QWidget(parent) {
}
int main(int argc, char *argv[]) {
bool recover = argc > 1 && strcmp(argv[1], "--recover") == 0;
ResetMode mode = ResetMode::USER_RESET;
if (argc > 1) {
if (strcmp(argv[1], "--recover") == 0) {
mode = ResetMode::RECOVER;
} else if (strcmp(argv[1], "--format") == 0) {
mode = ResetMode::FORMAT;
}
}
QApplication a(argc, argv);
Reset reset(recover);
Reset reset(mode);
setMainWindow(&reset);
return a.exec();
}

@ -2,18 +2,25 @@
#include <QPushButton>
#include <QWidget>
enum ResetMode {
USER_RESET, // user initiated a factory reset from openpilot
RECOVER, // userdata is corrupt for some reason, give a chance to recover
FORMAT, // finish up an ABL factory reset
};
class Reset : public QWidget {
Q_OBJECT
public:
explicit Reset(bool recover = false, QWidget *parent = 0);
explicit Reset(ResetMode mode, QWidget *parent = 0);
private:
QLabel *body;
QPushButton *rejectBtn;
QPushButton *rebootBtn;
QPushButton *confirmBtn;
void doReset();
void doErase();
void startReset();
private slots:
void confirm();

@ -34,7 +34,7 @@ bool is_elf(char *fname) {
void Setup::download(QString url) {
CURL *curl = curl_easy_init();
if (!curl) {
emit finished(false);
emit finished(url, tr("Something went wrong. Reboot the device."));
return;
}
@ -53,15 +53,24 @@ void Setup::download(QString url) {
curl_easy_setopt(curl, CURLOPT_FOLLOWLOCATION, 1L);
curl_easy_setopt(curl, CURLOPT_USERAGENT, (USER_AGENT + version).c_str());
curl_easy_setopt(curl, CURLOPT_HTTPHEADER, list);
curl_easy_setopt(curl, CURLOPT_TIMEOUT, 30L);
int ret = curl_easy_perform(curl);
long res_status = 0;
curl_easy_getinfo(curl, CURLINFO_RESPONSE_CODE, &res_status);
if (ret == CURLE_OK && res_status == 200 && is_elf(tmpfile)) {
rename(tmpfile, "/tmp/installer");
emit finished(true);
if (ret != CURLE_OK || res_status != 200) {
emit finished(url, tr("Ensure the entered URL is valid, and the device’s internet connection is good."));
} else if (!is_elf(tmpfile)) {
emit finished(url, tr("No custom software found at this URL."));
} else {
emit finished(false);
rename(tmpfile, "/tmp/installer");
FILE *fp_url = fopen("/tmp/installer_url", "w");
fprintf(fp_url, "%s", url.toStdString().c_str());
fclose(fp_url);
emit finished(url);
}
curl_slist_free_all(list);
@ -234,10 +243,10 @@ QWidget * Setup::downloading() {
return widget;
}
QWidget * Setup::download_failed() {
QWidget * Setup::download_failed(QLabel *url, QLabel *body) {
QWidget *widget = new QWidget();
QVBoxLayout *main_layout = new QVBoxLayout(widget);
main_layout->setContentsMargins(55, 225, 55, 55);
main_layout->setContentsMargins(55, 185, 55, 55);
main_layout->setSpacing(0);
QLabel *title = new QLabel(tr("Download Failed"));
@ -246,7 +255,13 @@ QWidget * Setup::download_failed() {
main_layout->addSpacing(67);
QLabel *body = new QLabel(tr("Ensure the entered URL is valid, and the device’s internet connection is good."));
url->setWordWrap(true);
url->setAlignment(Qt::AlignTop | Qt::AlignLeft);
url->setStyleSheet("font-family: \"JetBrains Mono\"; font-size: 64px; font-weight: 400; margin-right: 100px;");
main_layout->addWidget(url);
main_layout->addSpacing(48);
body->setWordWrap(true);
body->setAlignment(Qt::AlignTop | Qt::AlignLeft);
body->setStyleSheet("font-size: 80px; font-weight: 300; margin-right: 100px;");
@ -271,7 +286,7 @@ QWidget * Setup::download_failed() {
restart->setProperty("primary", true);
blayout->addWidget(restart);
QObject::connect(restart, &QPushButton::clicked, this, [=]() {
setCurrentIndex(2);
setCurrentIndex(1);
});
widget->setStyleSheet(R"(
@ -304,15 +319,19 @@ Setup::Setup(QWidget *parent) : QStackedWidget(parent) {
downloading_widget = downloading();
addWidget(downloading_widget);
failed_widget = download_failed();
QLabel *url_label = new QLabel();
QLabel *body_label = new QLabel();
failed_widget = download_failed(url_label, body_label);
addWidget(failed_widget);
QObject::connect(this, &Setup::finished, [=](bool success) {
// hide setup on success
qDebug() << "finished" << success;
if (success) {
QObject::connect(this, &Setup::finished, [=](const QString &url, const QString &error) {
qDebug() << "finished" << url << error;
if (error.isEmpty()) {
// hide setup on success
QTimer::singleShot(3000, this, &QWidget::hide);
} else {
url_label->setText(url);
body_label->setText(error);
setCurrentWidget(failed_widget);
}
});

@ -1,5 +1,6 @@
#pragma once
#include <QLabel>
#include <QStackedWidget>
#include <QString>
#include <QWidget>
@ -15,13 +16,13 @@ private:
QWidget *getting_started();
QWidget *network_setup();
QWidget *downloading();
QWidget *download_failed();
QWidget *download_failed(QLabel *url, QLabel *body);
QWidget *failed_widget;
QWidget *downloading_widget;
signals:
void finished(bool success);
void finished(const QString &url, const QString &error = "");
public slots:
void nextPage();

@ -576,18 +576,10 @@ location set</source>
<source>Are you sure you want to reset your device?</source>
<translation>Bist du sicher, dass du das Gerät auf Werkseinstellungen zurücksetzen möchtest?</translation>
</message>
<message>
<source>Resetting device...</source>
<translation>Gerät wird zurückgesetzt...</translation>
</message>
<message>
<source>System Reset</source>
<translation>System auf Werkseinstellungen zurücksetzen</translation>
</message>
<message>
<source>System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.</source>
<translation>Zurücksetzen auf Werkseinstellungen wurde ausgewählt. Drücke Annehmen, um alle Inhalte und Einstellungen zu löschen. Drücke Abbrechen, um mit dem Starten des Gerätes fortzufahren.</translation>
</message>
<message>
<source>Cancel</source>
<translation>Abbrechen</translation>
@ -601,8 +593,17 @@ location set</source>
<translation>Bestätigen</translation>
</message>
<message>
<source>Unable to mount data partition. Press confirm to reset your device.</source>
<translation>Datenpartition kann nicht geöffnet werden. Drücke Annehmen, um dein Gerät auf Werkseinstellungen zurückzusetzen.</translation>
<source>Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Press confirm to erase all content and settings. Press cancel to resume boot.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Resetting device...
This may take up to a minute.</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>
@ -702,6 +703,14 @@ location set</source>
<source>Start over</source>
<translation>Von neuem beginnen</translation>
</message>
<message>
<source>No custom software found at this URL.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Something went wrong. Reboot the device.</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>
<name>SetupWidget</name>

@ -574,18 +574,10 @@ location set</source>
<source>Are you sure you want to reset your device?</source>
<translation></translation>
</message>
<message>
<source>Resetting device...</source>
<translation>...</translation>
</message>
<message>
<source>System Reset</source>
<translation></translation>
</message>
<message>
<source>System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.</source>
<translation></translation>
</message>
<message>
<source>Cancel</source>
<translation></translation>
@ -599,8 +591,17 @@ location set</source>
<translation></translation>
</message>
<message>
<source>Unable to mount data partition. Press confirm to reset your device.</source>
<translation>data</translation>
<source>Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Press confirm to erase all content and settings. Press cancel to resume boot.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Resetting device...
This may take up to a minute.</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>
@ -700,6 +701,14 @@ location set</source>
<source>Start over</source>
<translation></translation>
</message>
<message>
<source>No custom software found at this URL.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Something went wrong. Reboot the device.</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>
<name>SetupWidget</name>

@ -403,7 +403,7 @@ location set</source>
</message>
<message>
<source>Waiting for GPS</source>
<translation>GPS </translation>
<translation>GPS </translation>
</message>
</context>
<context>
@ -574,18 +574,10 @@ location set</source>
<source>Are you sure you want to reset your device?</source>
<translation> ?</translation>
</message>
<message>
<source>Resetting device...</source>
<translation> ...</translation>
</message>
<message>
<source>System Reset</source>
<translation> </translation>
</message>
<message>
<source>System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.</source>
<translation> . . .</translation>
</message>
<message>
<source>Cancel</source>
<translation></translation>
@ -599,8 +591,18 @@ location set</source>
<translation></translation>
</message>
<message>
<source>Unable to mount data partition. Press confirm to reset your device.</source>
<translation> . .</translation>
<source>Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.</source>
<translation> . . .</translation>
</message>
<message>
<source>Press confirm to erase all content and settings. Press cancel to resume boot.</source>
<translation> . .</translation>
</message>
<message>
<source>Resetting device...
This may take up to a minute.</source>
<translation> ...
1 .</translation>
</message>
</context>
<context>
@ -700,6 +702,14 @@ location set</source>
<source>Start over</source>
<translation> </translation>
</message>
<message>
<source>Something went wrong. Reboot the device.</source>
<translation> . .</translation>
</message>
<message>
<source>No custom software found at this URL.</source>
<translation> URL에서 .</translation>
</message>
</context>
<context>
<name>SetupWidget</name>

@ -578,18 +578,10 @@ trabalho definido</translation>
<source>Are you sure you want to reset your device?</source>
<translation>Tem certeza que quer resetar seu dispositivo?</translation>
</message>
<message>
<source>Resetting device...</source>
<translation>Resetando dispositivo...</translation>
</message>
<message>
<source>System Reset</source>
<translation>Resetar Sistema</translation>
</message>
<message>
<source>System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.</source>
<translation>Solicitado reset do sistema. Confirme para apagar todo conteúdo e configurações. Aperte cancelar para continuar boot.</translation>
</message>
<message>
<source>Cancel</source>
<translation>Cancelar</translation>
@ -603,8 +595,17 @@ trabalho definido</translation>
<translation>Confirmar</translation>
</message>
<message>
<source>Unable to mount data partition. Press confirm to reset your device.</source>
<translation>Não foi possível montar a partição de dados. Pressione confirmar para resetar seu dispositivo.</translation>
<source>Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Press confirm to erase all content and settings. Press cancel to resume boot.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Resetting device...
This may take up to a minute.</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>
@ -704,6 +705,14 @@ trabalho definido</translation>
<source>Start over</source>
<translation>Inicializar</translation>
</message>
<message>
<source>No custom software found at this URL.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Something went wrong. Reboot the device.</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>
<name>SetupWidget</name>

@ -572,18 +572,10 @@ location set</source>
<source>Are you sure you want to reset your device?</source>
<translation></translation>
</message>
<message>
<source>Resetting device...</source>
<translation></translation>
</message>
<message>
<source>System Reset</source>
<translation></translation>
</message>
<message>
<source>System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.</source>
<translation></translation>
</message>
<message>
<source>Cancel</source>
<translation></translation>
@ -597,8 +589,17 @@ location set</source>
<translation></translation>
</message>
<message>
<source>Unable to mount data partition. Press confirm to reset your device.</source>
<translation> </translation>
<source>Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Press confirm to erase all content and settings. Press cancel to resume boot.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Resetting device...
This may take up to a minute.</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>
@ -698,6 +699,14 @@ location set</source>
<source>Start over</source>
<translation></translation>
</message>
<message>
<source>No custom software found at this URL.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Something went wrong. Reboot the device.</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>
<name>SetupWidget</name>

@ -574,18 +574,10 @@ location set</source>
<source>Are you sure you want to reset your device?</source>
<translation></translation>
</message>
<message>
<source>Resetting device...</source>
<translation></translation>
</message>
<message>
<source>System Reset</source>
<translation></translation>
</message>
<message>
<source>System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.</source>
<translation></translation>
</message>
<message>
<source>Cancel</source>
<translation></translation>
@ -599,8 +591,17 @@ location set</source>
<translation></translation>
</message>
<message>
<source>Unable to mount data partition. Press confirm to reset your device.</source>
<translation></translation>
<source>Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Press confirm to erase all content and settings. Press cancel to resume boot.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Resetting device...
This may take up to a minute.</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>
@ -700,6 +701,14 @@ location set</source>
<source>Start over</source>
<translation></translation>
</message>
<message>
<source>No custom software found at this URL.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Something went wrong. Reboot the device.</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>
<name>SetupWidget</name>

@ -293,7 +293,6 @@ void BinaryViewModel::updateState() {
double max_f = 255.0;
double factor = 0.25;
double scaler = max_f / log2(1.0 + factor);
char hex[3] = {'\0'};
for (int i = 0; i < binary.size(); ++i) {
for (int j = 0; j < 8; ++j) {
auto &item = items[i * column_count + j];
@ -305,9 +304,7 @@ void BinaryViewModel::updateState() {
double alpha = std::clamp(offset + log2(1.0 + factor * (double)n / (double)last_msg.count) * scaler, min_f, max_f);
item.bg_color.setAlpha(alpha);
}
hex[0] = toHex(binary[i] >> 4);
hex[1] = toHex(binary[i] & 0xf);
items[i * column_count + 8].val = hex;
items[i * column_count + 8].val = toHex(binary[i]);
items[i * column_count + 8].bg_color = last_msg.colors[i];
}
for (int i = binary.size() * column_count; i < items.size(); ++i) {
@ -375,7 +372,7 @@ void BinaryItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &op
bg.setAlpha(std::max(50, bg.alpha()));
}
painter->fillRect(option.rect, bg);
painter->setPen(Qt::black);
painter->setPen(option.palette.color(QPalette::Text));
}
}

@ -1,5 +1,6 @@
#include "tools/cabana/chartswidget.h"
#include <QActionGroup>
#include <QApplication>
#include <QCompleter>
#include <QDialogButtonBox>
@ -24,11 +25,12 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QFrame(parent) {
// toolbar
QToolBar *toolbar = new QToolBar(tr("Charts"), this);
toolbar->setIconSize({16, 16});
int icon_size = style()->pixelMetric(QStyle::PM_SmallIconSize);
toolbar->setIconSize({icon_size, icon_size});
QAction *new_plot_btn = toolbar->addAction(utils::icon("file-plus"), tr("New Plot"));
toolbar->addWidget(title_label = new QLabel());
title_label->setContentsMargins(0, 0, 12, 0);
title_label->setContentsMargins(0, 0, style()->pixelMetric(QStyle::PM_LayoutHorizontalSpacing), 0);
QMenu *menu = new QMenu(this);
for (int i = 0; i < MAX_COLUMN_COUNT; ++i) {
@ -76,8 +78,8 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QFrame(parent) {
main_layout->addWidget(charts_scroll);
// init settings
use_dark_theme = QApplication::style()->standardPalette().color(QPalette::WindowText).value() >
QApplication::style()->standardPalette().color(QPalette::Background).value();
use_dark_theme = QApplication::palette().color(QPalette::WindowText).value() >
QApplication::palette().color(QPalette::Background).value();
column_count = std::clamp(settings.chart_column_count, 1, MAX_COLUMN_COUNT);
max_chart_range = std::clamp(settings.chart_range, 1, settings.max_cached_minutes * 60);
display_range = {0, max_chart_range};
@ -154,12 +156,10 @@ void ChartsWidget::updateState() {
can->seekTo(zoomed_range.first);
}
charts_layout->parentWidget()->setUpdatesEnabled(false);
const auto &range = is_zoomed ? zoomed_range : display_range;
for (auto c : charts) {
c->updatePlot(cur_sec, range.first, range.second);
}
charts_layout->parentWidget()->setUpdatesEnabled(true);
}
void ChartsWidget::setMaxChartRange(int value) {
@ -185,7 +185,7 @@ void ChartsWidget::settingChanged() {
range_slider->setRange(1, settings.max_cached_minutes * 60);
for (auto c : charts) {
c->setFixedHeight(settings.chart_height);
c->setSeriesType(settings.chart_series_type == 0 ? QAbstractSeries::SeriesTypeLine : QAbstractSeries::SeriesTypeScatter);
c->setSeriesType((SeriesType)settings.chart_series_type);
}
}
@ -213,7 +213,6 @@ ChartView *ChartsWidget::createChart() {
}
void ChartsWidget::showChart(const MessageId &id, const Signal *sig, bool show, bool merge) {
setUpdatesEnabled(false);
ChartView *chart = findChart(id, sig);
if (show && !chart) {
chart = merge && charts.size() > 0 ? charts.back() : createChart();
@ -223,7 +222,6 @@ void ChartsWidget::showChart(const MessageId &id, const Signal *sig, bool show,
chart->removeIf([&](auto &s) { return s.msg_id == id && s.sig == sig; });
}
updateToolBar();
setUpdatesEnabled(true);
}
void ChartsWidget::setColumnCount(int n) {
@ -313,7 +311,7 @@ bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) {
// ChartView
ChartView::ChartView(QWidget *parent) : QChartView(nullptr, parent) {
series_type = settings.chart_series_type == 0 ? QAbstractSeries::SeriesTypeLine : QAbstractSeries::SeriesTypeScatter;
series_type = (SeriesType)settings.chart_series_type;
QChart *chart = new QChart();
chart->setBackgroundVisible(false);
axis_x = new QValueAxis(this);
@ -325,44 +323,58 @@ ChartView::ChartView(QWidget *parent) : QChartView(nullptr, parent) {
chart->setMargins({0, 0, 0, 0});
background = new QGraphicsRectItem(chart);
background->setBrush(Qt::white);
background->setBrush(QApplication::palette().color(QPalette::Base));
background->setPen(Qt::NoPen);
background->setZValue(chart->zValue() - 1);
move_icon = new QGraphicsPixmapItem(utils::icon("grip-horizontal"), chart);
setChart(chart);
createToolButtons();
setRenderHint(QPainter::Antialiasing);
// TODO: enable zoomIn/seekTo in live streaming mode.
setRubberBand(can->liveStreaming() ? QChartView::NoRubberBand : QChartView::HorizontalRubberBand);
QObject::connect(dbc(), &DBCManager::signalRemoved, this, &ChartView::signalRemoved);
QObject::connect(dbc(), &DBCManager::signalUpdated, this, &ChartView::signalUpdated);
QObject::connect(dbc(), &DBCManager::msgRemoved, this, &ChartView::msgRemoved);
QObject::connect(dbc(), &DBCManager::msgUpdated, this, &ChartView::msgUpdated);
}
void ChartView::createToolButtons() {
move_icon = new QGraphicsPixmapItem(utils::icon("grip-horizontal"), chart());
move_icon->setToolTip(tr("Drag and drop to combine charts"));
QToolButton *remove_btn = toolButton("x", tr("Remove Chart"));
close_btn_proxy = new QGraphicsProxyWidget(chart);
close_btn_proxy = new QGraphicsProxyWidget(chart());
close_btn_proxy->setWidget(remove_btn);
close_btn_proxy->setZValue(chart->zValue() + 11);
close_btn_proxy->setZValue(chart()->zValue() + 11);
QToolButton *manage_btn = toolButton("list", "");
// series types
QMenu *menu = new QMenu(this);
line_series_action = menu->addAction(tr("Line"), [this]() { setSeriesType(QAbstractSeries::SeriesTypeLine); });
line_series_action->setCheckable(true);
line_series_action->setChecked(series_type == QAbstractSeries::SeriesTypeLine);
scatter_series_action = menu->addAction(tr("Scatter"), [this]() { setSeriesType(QAbstractSeries::SeriesTypeScatter); });
scatter_series_action->setCheckable(true);
scatter_series_action->setChecked(series_type == QAbstractSeries::SeriesTypeScatter);
auto change_series_group = new QActionGroup(menu);
change_series_group->setExclusive(true);
QStringList types{tr("line"), tr("Step Line"), tr("Scatter")};
for (int i = 0; i < types.size(); ++i) {
QAction *act = new QAction(types[i], change_series_group);
act->setData(i);
act->setCheckable(true);
act->setChecked(i == (int)series_type);
menu->addAction(act);
}
menu->addSeparator();
menu->addAction(tr("Manage series"), this, &ChartView::manageSeries);
QToolButton *manage_btn = toolButton("list", "");
manage_btn->setMenu(menu);
manage_btn->setPopupMode(QToolButton::InstantPopup);
manage_btn_proxy = new QGraphicsProxyWidget(chart);
manage_btn_proxy = new QGraphicsProxyWidget(chart());
manage_btn_proxy->setWidget(manage_btn);
manage_btn_proxy->setZValue(chart->zValue() + 11);
manage_btn_proxy->setZValue(chart()->zValue() + 11);
setChart(chart);
setRenderHint(QPainter::Antialiasing);
// TODO: enable zoomIn/seekTo in live streaming mode.
setRubberBand(can->liveStreaming() ? QChartView::NoRubberBand : QChartView::HorizontalRubberBand);
QObject::connect(dbc(), &DBCManager::signalRemoved, this, &ChartView::signalRemoved);
QObject::connect(dbc(), &DBCManager::signalUpdated, this, &ChartView::signalUpdated);
QObject::connect(dbc(), &DBCManager::msgRemoved, this, &ChartView::msgRemoved);
QObject::connect(dbc(), &DBCManager::msgUpdated, this, &ChartView::msgUpdated);
QObject::connect(remove_btn, &QToolButton::clicked, this, &ChartView::remove);
QObject::connect(change_series_group, &QActionGroup::triggered, [this](QAction *action) {
setSeriesType((SeriesType)action->data().toInt());
});
}
void ChartView::addSeries(const MessageId &msg_id, const Signal *sig) {
@ -432,10 +444,12 @@ void ChartView::manageSeries() {
void ChartView::resizeEvent(QResizeEvent *event) {
updatePlotArea(align_to);
int x = event->size().width() - close_btn_proxy->size().width() - 11;
close_btn_proxy->setPos(x, 8);
manage_btn_proxy->setPos(x - manage_btn_proxy->size().width() - 5, 8);
move_icon->setPos(11, 8);
int top_margin = style()->pixelMetric(QStyle::PM_LayoutTopMargin);
int spacing = style()->pixelMetric(QStyle::PM_LayoutHorizontalSpacing);
int x = event->size().width() - close_btn_proxy->size().width() - style()->pixelMetric(QStyle::PM_LayoutRightMargin);
close_btn_proxy->setPos(x, top_margin);
manage_btn_proxy->setPos(x - manage_btn_proxy->size().width() - spacing, top_margin);
move_icon->setPos(style()->pixelMetric(QStyle::PM_LayoutLeftMargin), top_margin);
QChartView::resizeEvent(event);
}
@ -480,7 +494,7 @@ void ChartView::updateSeriesPoints() {
int num_points = std::max<int>(end - begin, 1);
int pixels_per_point = width() / num_points;
if (series_type == QAbstractSeries::SeriesTypeScatter) {
if (series_type == SeriesType::Scatter) {
((QScatterSeries *)s.series)->setMarkerSize(std::clamp(pixels_per_point / 3, 2, 8));
} else {
s.series->setPointsVisible(pixels_per_point > 20);
@ -494,7 +508,9 @@ void ChartView::updateSeries(const Signal *sig, const std::vector<Event *> *even
if (!sig || s.sig == sig) {
if (clear) {
s.vals.clear();
s.step_vals.clear();
s.vals.reserve(settings.max_cached_minutes * 60 * 100); // [n]seconds * 100hz
s.step_vals.reserve(settings.max_cached_minutes * 60 * 100 * 2);
s.last_value_mono_time = 0;
}
s.series->setColor(getColor(s.sig));
@ -502,6 +518,7 @@ void ChartView::updateSeries(const Signal *sig, const std::vector<Event *> *even
struct Chunk {
std::vector<Event *>::const_iterator first, second;
QVector<QPointF> vals;
QVector<QPointF> step_vals;
};
// split into one minitue chunks
QVector<Chunk> chunks;
@ -514,6 +531,7 @@ void ChartView::updateSeries(const Signal *sig, const std::vector<Event *> *even
QtConcurrent::blockingMap(chunks, [&](Chunk &chunk) {
chunk.vals.reserve(60 * 100); // 100 hz
chunk.step_vals.reserve(60 * 100 * 2); // 100 hz
double route_start_time = can->routeStartTime();
for (auto it = chunk.first; it != chunk.second; ++it) {
if ((*it)->which == cereal::Event::Which::CAN) {
@ -523,6 +541,10 @@ void ChartView::updateSeries(const Signal *sig, const std::vector<Event *> *even
double value = get_raw_value((uint8_t *)dat.begin(), dat.size(), *s.sig);
double ts = ((*it)->mono_time / (double)1e9) - route_start_time; // seconds
chunk.vals.push_back({ts, value});
if (!chunk.step_vals.empty()) {
chunk.step_vals.push_back({ts, chunk.step_vals.back().y()});
}
chunk.step_vals.push_back({ts,value});
}
}
}
@ -530,11 +552,17 @@ void ChartView::updateSeries(const Signal *sig, const std::vector<Event *> *even
});
for (auto &c : chunks) {
s.vals.append(c.vals);
if (!c.step_vals.empty()) {
if (!s.step_vals.empty()) {
s.step_vals.append({c.step_vals.first().x(), s.step_vals.back().y()});
}
s.step_vals.append(c.step_vals);
}
}
if (events->size()) {
s.last_value_mono_time = events->back()->mono_time;
}
s.series->replace(s.vals);
s.series->replace(series_type == SeriesType::StepLine ? s.step_vals : s.vals);
}
}
updateAxisY();
@ -546,9 +574,16 @@ void ChartView::updateAxisY() {
double min = std::numeric_limits<double>::max();
double max = std::numeric_limits<double>::lowest();
QString unit = sigs[0].sig->unit;
for (auto &s : sigs) {
if (!s.series->isVisible()) continue;
// Only show unit when all signals have the same unit
if (unit != s.sig->unit) {
unit.clear();
}
auto first = std::lower_bound(s.vals.begin(), s.vals.end(), axis_x->min(), [](auto &p, double x) { return p.x() < x; });
auto last = std::lower_bound(first, s.vals.end(), axis_x->max(), [](auto &p, double x) { return p.x() < x; });
for (auto it = first; it != last; ++it) {
@ -556,6 +591,8 @@ void ChartView::updateAxisY() {
if (it->y() > max) max = it->y();
}
}
axis_y->setTitleText(unit);
if (min == std::numeric_limits<double>::max()) min = 0;
if (max == std::numeric_limits<double>::lowest()) max = 0;
@ -567,7 +604,9 @@ void ChartView::updateAxisY() {
QFontMetrics fm(axis_y->labelsFont());
int n = qMax(int(-qFloor(std::log10((max_y - min_y) / (tick_count - 1)))), 0) + 1;
y_label_width = qMax(fm.width(QString::number(min_y, 'f', n)), fm.width(QString::number(max_y, 'f', n))) + 15; // left margin 15
int title_spacing = axis_y->titleText().isEmpty() ? 0 : 20;
y_label_width = title_spacing + qMax(fm.width(QString::number(min_y, 'f', n)), fm.width(QString::number(max_y, 'f', n))) + 15; // left margin 15
axis_y->setLabelFormat(QString("%.%1f").arg(n));
emit axisYLabelWidthChanged(y_label_width);
}
}
@ -600,7 +639,7 @@ qreal ChartView::niceNumber(qreal x, bool ceiling) {
}
void ChartView::leaveEvent(QEvent *event) {
track_pts.clear();
clearTrackPoints();
scene()->update();
QChartView::leaveEvent(event);
}
@ -656,26 +695,31 @@ void ChartView::mouseMoveEvent(QMouseEvent *ev) {
auto rubber = findChild<QRubberBand *>();
bool is_zooming = rubber && rubber->isVisible();
const auto plot_area = chart()->plotArea();
track_pts.clear();
clearTrackPoints();
if (!is_zooming && plot_area.contains(ev->pos())) {
track_pts.resize(sigs.size());
QStringList text_list;
const double sec = chart()->mapToValue(ev->pos()).x();
for (int i = 0; i < sigs.size(); ++i) {
QString value = "--";
qreal x = -1;
for (auto &s : sigs) {
if (!s.series->isVisible()) continue;
// use reverse iterator to find last item <= sec.
auto it = std::lower_bound(sigs[i].vals.rbegin(), sigs[i].vals.rend(), sec, [](auto &p, double x) { return p.x() > x; });
if (it != sigs[i].vals.rend() && it->x() >= axis_x->min()) {
value = QString::number(it->y());
track_pts[i] = chart()->mapToPosition(*it);
auto it = std::lower_bound(s.vals.rbegin(), s.vals.rend(), sec, [](auto &p, double x) { return p.x() > x; });
if (it != s.vals.rend() && it->x() >= axis_x->min()) {
s.track_pt = chart()->mapToPosition(*it);
x = std::max(x, s.track_pt.x());
}
text_list.push_back(QString("<span style=\"color:%1;\">■ </span>%2: <b>%3</b>").arg(sigs[i].series->color().name(), sigs[i].sig->name, value));
text_list.push_back(QString("<span style=\"color:%1;\">■ </span>%2: <b>%3</b>")
.arg(s.series->color().name(), s.sig->name,
s.track_pt.isNull() ? "--" : QString::number(s.track_pt.y())));
}
if (x < 0) {
x = ev->pos().x();
}
auto max = std::max_element(track_pts.begin(), track_pts.end(), [](auto &a, auto &b) { return a.x() < b.x(); });
auto pt = (max == track_pts.end()) ? ev->pos() : *max;
text_list.push_front(QString::number(chart()->mapToValue(pt).x(), 'f', 3));
QPointF tooltip_pt(pt.x() + 12, plot_area.top() - 20);
QToolTip::showText(mapToGlobal(tooltip_pt.toPoint()), pt.isNull() ? "" : text_list.join("<br />"), this, plot_area.toRect());
text_list.push_front(QString::number(chart()->mapToValue({x, 0}).x(), 'f', 3));
QPointF tooltip_pt(x + 12, plot_area.top() - 20);
QToolTip::showText(mapToGlobal(tooltip_pt.toPoint()), text_list.join("<br />"), this, plot_area.toRect());
scene()->invalidate({}, QGraphicsScene::ForegroundLayer);
} else {
QToolTip::hideText();
@ -720,6 +764,7 @@ void ChartView::dropEvent(QDropEvent *event) {
}
void ChartView::drawForeground(QPainter *painter, const QRectF &rect) {
// draw time line
qreal x = chart()->mapToPosition(QPointF{cur_sec, 0}).x();
x = std::clamp(x, chart()->plotArea().left(), chart()->plotArea().right());
qreal y1 = chart()->plotArea().top() - 2;
@ -727,18 +772,20 @@ void ChartView::drawForeground(QPainter *painter, const QRectF &rect) {
painter->setPen(QPen(chart()->titleBrush().color(), 2));
painter->drawLine(QPointF{x, y1}, QPointF{x, y2});
auto max = std::max_element(track_pts.begin(), track_pts.end(), [](auto &a, auto &b) { return a.x() < b.x(); });
if (max != track_pts.end() && !max->isNull()) {
painter->setPen(QPen(Qt::darkGray, 1, Qt::DashLine));
painter->drawLine(QPointF{max->x(), y1}, QPointF{max->x(), y2});
painter->setPen(Qt::NoPen);
for (int i = 0; i < track_pts.size(); ++i) {
if (!track_pts[i].isNull() && i < sigs.size()) {
painter->setBrush(sigs[i].series->color().darker(125));
painter->drawEllipse(track_pts[i], 5.5, 5.5);
}
// draw track points
painter->setPen(Qt::NoPen);
qreal track_line_x = -1;
for (auto &s : sigs) {
if (!s.track_pt.isNull() && s.series->isVisible()) {
painter->setBrush(s.series->color().darker(125));
painter->drawEllipse(s.track_pt, 5.5, 5.5);
track_line_x = std::max(track_line_x, s.track_pt.x());
}
}
if (track_line_x > 0) {
painter->setPen(QPen(Qt::darkGray, 1, Qt::DashLine));
painter->drawLine(QPointF{track_line_x, y1}, QPointF{track_line_x, y2});
}
// paint points. OpenGL mode lacks certain features (such as showing points)
painter->setPen(Qt::NoPen);
@ -754,11 +801,14 @@ void ChartView::drawForeground(QPainter *painter, const QRectF &rect) {
}
}
QXYSeries *ChartView::createSeries(QAbstractSeries::SeriesType type, QColor color) {
QXYSeries *ChartView::createSeries(SeriesType type, QColor color) {
QXYSeries *series = nullptr;
if (type == QAbstractSeries::SeriesTypeLine) {
if (type == SeriesType::Line) {
series = new QLineSeries(this);
chart()->legend()->setMarkerShape(QLegend::MarkerShapeRectangle);
} else if (type == SeriesType::StepLine) {
series = new QLineSeries(this);
chart()->legend()->setMarkerShape(QLegend::MarkerShapeFromSeries);
} else {
series = new QScatterSeries(this);
chart()->legend()->setMarkerShape(QLegend::MarkerShapeCircle);
@ -779,9 +829,7 @@ QXYSeries *ChartView::createSeries(QAbstractSeries::SeriesType type, QColor colo
return series;
}
void ChartView::setSeriesType(QAbstractSeries::SeriesType type) {
line_series_action->setChecked(type == QAbstractSeries::SeriesTypeLine);
scatter_series_action->setChecked(type == QAbstractSeries::SeriesTypeScatter);
void ChartView::setSeriesType(SeriesType type) {
if (type != series_type) {
series_type = type;
for (auto &s : sigs) {
@ -790,7 +838,7 @@ void ChartView::setSeriesType(QAbstractSeries::SeriesType type) {
}
for (auto &s : sigs) {
auto series = createSeries(series_type, getColor(s.sig));
series->replace(s.vals);
series->replace(series_type == SeriesType::StepLine ? s.step_vals : s.vals);
s.series = series;
}
updateSeriesPoints();

@ -20,6 +20,12 @@ using namespace QtCharts;
const int CHART_MIN_WIDTH = 300;
enum class SeriesType {
Line = 0,
StepLine,
Scatter
};
class ChartView : public QChartView {
Q_OBJECT
@ -29,7 +35,7 @@ public:
bool hasSeries(const MessageId &msg_id, const Signal *sig) const;
void updateSeries(const Signal *sig = nullptr, const std::vector<Event*> *events = nullptr, bool clear = true);
void updatePlot(double cur, double min, double max);
void setSeriesType(QAbstractSeries::SeriesType type);
void setSeriesType(SeriesType type);
void updatePlotArea(int left);
struct SigItem {
@ -37,7 +43,9 @@ public:
const Signal *sig = nullptr;
QXYSeries *series = nullptr;
QVector<QPointF> vals;
QVector<QPointF> step_vals;
uint64_t last_value_mono_time = 0;
QPointF track_pt{};
};
signals:
@ -57,6 +65,7 @@ private slots:
void signalRemoved(const Signal *sig) { removeIf([=](auto &s) { return s.sig == sig; }); }
private:
void createToolButtons();
void mousePressEvent(QMouseEvent *event) override;
void mouseReleaseEvent(QMouseEvent *event) override;
void mouseMoveEvent(QMouseEvent *ev) override;
@ -70,15 +79,15 @@ private:
void drawForeground(QPainter *painter, const QRectF &rect) override;
std::tuple<double, double, int> getNiceAxisNumbers(qreal min, qreal max, int tick_count);
qreal niceNumber(qreal x, bool ceiling);
QXYSeries *createSeries(QAbstractSeries::SeriesType type, QColor color);
QXYSeries *createSeries(SeriesType type, QColor color);
void updateSeriesPoints();
void removeIf(std::function<bool(const SigItem &)> predicate);
inline void clearTrackPoints() { for (auto &s : sigs) s.track_pt = {}; }
int y_label_width = 0;
int align_to = 0;
QValueAxis *axis_x;
QValueAxis *axis_y;
QVector<QPointF> track_pts;
QGraphicsPixmapItem *move_icon;
QGraphicsProxyWidget *close_btn_proxy;
QGraphicsProxyWidget *manage_btn_proxy;
@ -86,9 +95,7 @@ private:
QList<SigItem> sigs;
double cur_sec = 0;
const QString mime_type = "application/x-cabanachartview";
QAbstractSeries::SeriesType series_type = QAbstractSeries::SeriesTypeLine;
QAction *line_series_action;
QAction *scatter_series_action;
SeriesType series_type = SeriesType::Line;
friend class ChartsWidget;
};

@ -15,8 +15,10 @@ QVariant HistoryLogModel::data(const QModelIndex &index, int role) const {
return QString::number((m.mono_time / (double)1e9) - can->routeStartTime(), 'f', 2);
}
return show_signals ? QString::number(m.sig_values[index.column() - 1]) : toHex(m.data);
} else if (role == Qt::UserRole && index.column() == 1 && !show_signals) {
} else if (role == ColorsRole) {
return QVariant::fromValue(m.colors);
} else if (role == BytesRole) {
return m.data;
}
return {};
}
@ -48,7 +50,15 @@ QVariant HistoryLogModel::headerData(int section, Qt::Orientation orientation, i
if (section == 0) {
return "Time";
}
return show_signals ? sigs[section - 1]->name : "Data";
if (show_signals) {
QString name = sigs[section - 1]->name;
if (!sigs[section - 1]->unit.isEmpty()) {
name += QString(" (%1)").arg(sigs[section - 1]->unit);
}
return name;
} else {
return "Data";
}
} else if (role == Qt::BackgroundRole && section > 0 && show_signals) {
return QBrush(getColor(sigs[section - 1]));
}

@ -58,14 +58,21 @@ MainWindow::MainWindow() : QMainWindow() {
fingerprint_to_dbc = QJsonDocument::fromJson(json_file.readAll());
}
setStyleSheet(QString(R"(QMainWindow::separator {
width: %1px; /* when vertical */
height: %1px; /* when horizontal */
})").arg(style()->pixelMetric(QStyle::PM_SplitterWidth)));
QObject::connect(this, &MainWindow::showMessage, statusBar(), &QStatusBar::showMessage);
QObject::connect(this, &MainWindow::updateProgressBar, this, &MainWindow::updateDownloadProgress);
QObject::connect(messages_widget, &MessagesWidget::msgSelectionChanged, center_widget, &CenterWidget::setMessage);
QObject::connect(charts_widget, &ChartsWidget::dock, this, &MainWindow::dockCharts);
QObject::connect(can, &AbstractStream::streamStarted, this, &MainWindow::loadDBCFromFingerprint);
QObject::connect(can, &AbstractStream::eventsMerged, this, &MainWindow::updateStatus);
QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &MainWindow::DBCFileChanged);
QObject::connect(UndoStack::instance(), &QUndoStack::cleanChanged, this, &MainWindow::undoStackCleanChanged);
QObject::connect(UndoStack::instance(), &QUndoStack::indexChanged, this, &MainWindow::undoStackIndexChanged);
QObject::connect(&settings, &Settings::changed, this, &MainWindow::updateStatus);
}
void MainWindow::createActions() {
@ -179,11 +186,16 @@ void MainWindow::createStatusBar() {
progress_bar->setVisible(false);
statusBar()->addWidget(new QLabel(tr("For Help, Press F1")));
statusBar()->addPermanentWidget(progress_bar);
statusBar()->addPermanentWidget(status_label = new QLabel(this));
updateStatus();
}
void MainWindow::createShortcuts() {
auto shortcut = new QShortcut(QKeySequence(Qt::Key_Space), this, nullptr, nullptr, Qt::ApplicationShortcut);
QObject::connect(shortcut, &QShortcut::activated, []() { can->pause(!can->isPaused()); });
shortcut = new QShortcut(QKeySequence(QKeySequence::FullScreen), this, nullptr, nullptr, Qt::ApplicationShortcut);
QObject::connect(shortcut, &QShortcut::activated, this, &MainWindow::toggleFullScreen);
// TODO: add more shortcuts here.
}
@ -403,6 +415,18 @@ void MainWindow::updateDownloadProgress(uint64_t cur, uint64_t total, bool succe
}
}
void MainWindow::updateStatus() {
float cached_minutes = 0;
if (!can->liveStreaming()) {
if (auto events = can->events(); !events->empty()) {
cached_minutes = (events->back()->mono_time - events->front()->mono_time) / (1e9 * 60);
}
} else {
settings.max_cached_minutes = settings.max_cached_minutes;
}
status_label->setText(tr("Cached Minutes:%1 FPS:%2").arg(cached_minutes, 0, 'f', 1).arg(settings.fps));
}
void MainWindow::dockCharts(bool dock) {
if (dock && floating_window) {
floating_window->removeEventFilter(charts_widget);
@ -460,6 +484,19 @@ void MainWindow::onlineHelp() {
}
}
void MainWindow::toggleFullScreen() {
if (isFullScreen()) {
menuBar()->show();
statusBar()->show();
showNormal();
showMaximized();
} else {
menuBar()->hide();
statusBar()->hide();
showFullScreen();
}
}
// HelpOverlay
HelpOverlay::HelpOverlay(MainWindow *parent) : QWidget(parent) {
setAttribute(Qt::WA_NoSystemBackground, true);

@ -56,6 +56,8 @@ protected:
void undoStackCleanChanged(bool clean);
void undoStackIndexChanged(int index);
void onlineHelp();
void toggleFullScreen();
void updateStatus();
VideoWidget *video_widget = nullptr;
QDockWidget *video_dock;
@ -65,6 +67,7 @@ protected:
QWidget *floating_window = nullptr;
QVBoxLayout *charts_layout;
QProgressBar *progress_bar;
QLabel *status_label;
QJsonDocument fingerprint_to_dbc;
QSplitter *video_splitter;;
QString current_file = "";

@ -20,11 +20,15 @@ MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) {
table_widget = new QTableView(this);
model = new MessageListModel(this);
table_widget->setModel(model);
table_widget->setItemDelegateForColumn(4, new MessageBytesDelegate(table_widget));
table_widget->setItemDelegateForColumn(5, new MessageBytesDelegate(table_widget));
table_widget->setSelectionBehavior(QAbstractItemView::SelectRows);
table_widget->setSelectionMode(QAbstractItemView::SingleSelection);
table_widget->setSortingEnabled(true);
table_widget->sortByColumn(0, Qt::AscendingOrder);
table_widget->setColumnWidth(0, 150);
table_widget->setColumnWidth(1, 50);
table_widget->setColumnWidth(2, 50);
table_widget->setColumnWidth(3, 50);
table_widget->horizontalHeader()->setStretchLastSection(true);
table_widget->verticalHeader()->hide();
main_layout->addWidget(table_widget);
@ -108,7 +112,7 @@ void MessagesWidget::reset() {
QVariant MessageListModel::headerData(int section, Qt::Orientation orientation, int role) const {
if (orientation == Qt::Horizontal && role == Qt::DisplayRole)
return (QString[]){"Name", "ID", "Freq", "Count", "Bytes"}[section];
return (QString[]){"Name", "Bus", "ID", "Freq", "Count", "Bytes"}[section];
return {};
}
@ -119,12 +123,13 @@ QVariant MessageListModel::data(const QModelIndex &index, int role) const {
if (role == Qt::DisplayRole) {
switch (index.column()) {
case 0: return msgName(id);
case 1: return id.toString(); // TODO: put source and address in separate columns
case 2: return can_data.freq;
case 3: return can_data.count;
case 4: return toHex(can_data.dat);
case 1: return id.source;
case 2: return QString::number(id.address, 16);;
case 3: return can_data.freq;
case 4: return can_data.count;
case 5: return toHex(can_data.dat);
}
} else if (role == Qt::UserRole && index.column() == 4) {
} else if (role == ColorsRole) {
QVector<QColor> colors = can_data.colors;
if (!suppressed_bytes.empty()) {
for (int i = 0; i < colors.size(); i++) {
@ -134,6 +139,8 @@ QVariant MessageListModel::data(const QModelIndex &index, int role) const {
}
}
return QVariant::fromValue(colors);
} else if (role == BytesRole) {
return can_data.dat;
}
return {};
}
@ -171,15 +178,23 @@ void MessageListModel::sortMessages() {
});
} else if (sort_column == 1) {
std::sort(msgs.begin(), msgs.end(), [this](auto &l, auto &r) {
return sort_order == Qt::AscendingOrder ? l < r : l > r;
auto ll = std::pair{l.source, l};
auto rr = std::pair{r.source, r};
return sort_order == Qt::AscendingOrder ? ll < rr : ll > rr;
});
} else if (sort_column == 2) {
std::sort(msgs.begin(), msgs.end(), [this](auto &l, auto &r) {
auto ll = std::pair{l.address, l};
auto rr = std::pair{r.address, r};
return sort_order == Qt::AscendingOrder ? ll < rr : ll > rr;
});
} else if (sort_column == 3) {
std::sort(msgs.begin(), msgs.end(), [this](auto &l, auto &r) {
auto ll = std::pair{can->lastMessage(l).freq, l};
auto rr = std::pair{can->lastMessage(r).freq, r};
return sort_order == Qt::AscendingOrder ? ll < rr : ll > rr;
});
} else if (sort_column == 3) {
} else if (sort_column == 4) {
std::sort(msgs.begin(), msgs.end(), [this](auto &l, auto &r) {
auto ll = std::pair{can->lastMessage(l).count, l};
auto rr = std::pair{can->lastMessage(r).count, r};
@ -200,7 +215,7 @@ void MessageListModel::msgsReceived(const QHash<MessageId, CanData> *new_msgs) {
}
for (int i = 0; i < msgs.size(); ++i) {
if (new_msgs->contains(msgs[i])) {
for (int col = 2; col < columnCount(); ++col)
for (int col = 3; col < columnCount(); ++col)
emit dataChanged(index(i, col), index(i, col), {Qt::DisplayRole});
}
}

@ -16,7 +16,7 @@ Q_OBJECT
public:
MessageListModel(QObject *parent) : QAbstractTableModel(parent) {}
QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const override;
int columnCount(const QModelIndex &parent = QModelIndex()) const override { return 5; }
int columnCount(const QModelIndex &parent = QModelIndex()) const override { return 6; }
QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const;
int rowCount(const QModelIndex &parent = QModelIndex()) const override { return msgs.size(); }
void sort(int column, Qt::SortOrder order = Qt::AscendingOrder) override;

@ -65,7 +65,7 @@ SettingsDlg::SettingsDlg(QWidget *parent) : QDialog(parent) {
form_layout->addRow(tr("Max Cached Minutes"), cached_minutes);
chart_series_type = new QComboBox(this);
chart_series_type->addItems({tr("Line"), tr("Scatter")});
chart_series_type->addItems({tr("Line"), tr("Step Line"), tr("Scatter")});
chart_series_type->setCurrentIndex(settings.chart_series_type);
form_layout->addRow(tr("Chart Default Series Type"), chart_series_type);

@ -61,16 +61,29 @@ void SignalModel::updateState(const QHash<MessageId, CanData> *msgs) {
auto &dat = can->lastMessage(msg_id).dat;
int row = 0;
for (auto item : root->children) {
double value = get_raw_value((uint8_t *)dat.begin(), dat.size(), *item->sig);
item->sig_val = QString::number(value);
emit dataChanged(index(row, 1), index(row, 1), {Qt::DisplayRole});
QString value = QString::number(get_raw_value((uint8_t *)dat.begin(), dat.size(), *item->sig));
if (!item->sig->unit.isEmpty()){
value += " " + item->sig->unit;
}
if (value != item->sig_val) {
item->sig_val = value;
emit dataChanged(index(row, 1), index(row, 1), {Qt::DisplayRole});
}
++row;
}
}
}
SignalModel::Item *SignalModel::getItem(const QModelIndex &index) const {
SignalModel::Item *item = nullptr;
if (index.isValid()) {
item = (SignalModel::Item *)index.internalPointer();
}
return item ? item : root.get();
}
int SignalModel::rowCount(const QModelIndex &parent) const {
if (parent.column() > 0) return 0;
if (parent.isValid() && parent.column() > 0) return 0;
auto parent_item = getItem(parent);
int row_count = parent_item->children.size();
@ -99,14 +112,19 @@ int SignalModel::signalRow(const Signal *sig) const {
}
QModelIndex SignalModel::index(int row, int column, const QModelIndex &parent) const {
if (!hasIndex(row, column, parent)) return {};
return createIndex(row, column, getItem(parent)->children[row]);
if (parent.isValid() && parent.column() != 0) return {};
auto parent_item = getItem(parent);
if (parent_item && row < parent_item->children.size()) {
return createIndex(row, column, parent_item->children[row]);
}
return {};
}
QModelIndex SignalModel::parent(const QModelIndex &index) const {
if (!index.isValid()) return {};
Item *parent_item = getItem(index)->parent;
return parent_item == root.get() ? QModelIndex() : createIndex(parent_item->row(), 0, parent_item);
return !parent_item || parent_item == root.get() ? QModelIndex() : createIndex(parent_item->row(), 0, parent_item);
}
QVariant SignalModel::data(const QModelIndex &index, int role) const {
@ -287,8 +305,8 @@ SignalItemDelegate::SignalItemDelegate(QObject *parent) : QStyledItemDelegate(pa
QSize SignalItemDelegate::sizeHint(const QStyleOptionViewItem &option, const QModelIndex &index) const {
QSize size = QStyledItemDelegate::sizeHint(option, index);
if (!index.parent().isValid() && index.column() == 0) {
size.rwidth() = std::min(((QWidget*)parent())->size().width() / 2, size.width() + color_label_width + 8);
if (index.column() == 0 && !index.parent().isValid()) {
size.rwidth() = std::min(option.widget->size().width() / 2, size.width() + color_label_width + 8);
}
return size;
}
@ -304,22 +322,34 @@ void SignalItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &op
// color label
auto bg_color = getColor(item->sig);
QRect rc{option.rect.left(), option.rect.top(), color_label_width, option.rect.height()};
int h_margin = option.widget->style()->pixelMetric(QStyle::PM_FocusFrameHMargin) + 1;
int v_margin = option.widget->style()->pixelMetric(QStyle::PM_FocusFrameVMargin);
QRect rc{option.rect.left() + h_margin, option.rect.top(), color_label_width, option.rect.height()};
painter->setPen(Qt::NoPen);
painter->setBrush(item->highlight ? bg_color.darker(125) : bg_color);
painter->drawRoundedRect(rc.adjusted(0, 2, 0, -2), 3, 3);
painter->drawRoundedRect(rc.adjusted(0, v_margin, 0, -v_margin), 3, 3);
painter->setPen(item->highlight ? Qt::white : Qt::black);
painter->setFont(small_font);
painter->drawText(rc, Qt::AlignCenter, QString::number(item->row() + 1));
// signal name
painter->setFont(option.font);
painter->setPen((option.state & QStyle::State_Selected ? option.palette.highlightedText() : option.palette.text()).color());
painter->setPen(option.palette.color(option.state & QStyle::State_Selected ? QPalette::HighlightedText : QPalette::Text));
QString text = index.data(Qt::DisplayRole).toString();
QRect text_rect = option.rect.adjusted(rc.width() + 6, 0, 0, 0);
QRect text_rect = option.rect;
text_rect.setLeft(rc.right() + h_margin * 2);
text = painter->fontMetrics().elidedText(text, Qt::ElideRight, text_rect.width());
painter->drawText(text_rect, option.displayAlignment, text);
painter->restore();
} else if (index.column() == 1 && item && item->type == SignalModel::Item::Sig) {
// draw signal value
if (option.state & QStyle::State_Selected) {
painter->fillRect(option.rect, option.palette.highlight());
}
painter->setPen(option.palette.color(option.state & QStyle::State_Selected ? QPalette::HighlightedText : QPalette::Text));
QRect rc = option.rect.adjusted(0, 0, -70, 0);
auto text = painter->fontMetrics().elidedText(index.data(Qt::DisplayRole).toString(), Qt::ElideRight, rc.width());
painter->drawText(rc, Qt::AlignRight | Qt::AlignVCenter, text);
} else {
QStyledItemDelegate::paint(painter, option, index);
}
@ -355,7 +385,6 @@ SignalView::SignalView(ChartsWidget *charts, QWidget *parent) : charts(charts),
setFrameStyle(QFrame::StyledPanel | QFrame::Plain);
// title bar
QWidget *title_bar = new QWidget(this);
title_bar->setAutoFillBackground(true);
QHBoxLayout *hl = new QHBoxLayout(title_bar);
hl->addWidget(signal_count_lb = new QLabel());
filter_edit = new QLineEdit(this);
@ -416,8 +445,11 @@ void SignalView::rowsChanged() {
if (!tree->indexWidget(index)) {
QWidget *w = new QWidget(this);
QHBoxLayout *h = new QHBoxLayout(w);
h->setContentsMargins(0, 2, 0, 2);
h->addStretch(1);
int v_margin = style()->pixelMetric(QStyle::PM_FocusFrameVMargin);
int h_margin = style()->pixelMetric(QStyle::PM_FocusFrameHMargin);
h->setContentsMargins(0, v_margin, -h_margin, v_margin);
h->setSpacing(style()->pixelMetric(QStyle::PM_ToolBarItemSpacing));
h->addStretch(0);
auto remove_btn = toolButton("x", tr("Remove signal"));
auto plot_btn = toolButton("graph-up", "");

@ -42,7 +42,7 @@ public:
bool saveSignal(const Signal *origin_s, Signal &s);
void resizeSignal(const Signal *sig, int start_bit, int size);
void removeSignal(const Signal *sig);
inline Item *getItem(const QModelIndex &index) const { return index.isValid() ? (Item *)index.internalPointer() : root.get(); }
Item *getItem(const QModelIndex &index) const;
int signalRow(const Signal *sig) const;
void showExtraInfo(const QModelIndex &index);

@ -71,26 +71,26 @@ void ChangeTracker::clear() {
MessageBytesDelegate::MessageBytesDelegate(QObject *parent) : QStyledItemDelegate(parent) {
fixed_font = QFontDatabase::systemFont(QFontDatabase::FixedFont);
byte_width = QFontMetrics(fixed_font).width("00 ");
}
void MessageBytesDelegate::paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const {
auto colors = index.data(ColorsRole).value<QVector<QColor>>();
auto byte_list = index.data(BytesRole).toByteArray();
int v_margin = option.widget->style()->pixelMetric(QStyle::PM_FocusFrameVMargin);
int h_margin = option.widget->style()->pixelMetric(QStyle::PM_FocusFrameHMargin);
QRect rc{option.rect.left() + h_margin, option.rect.top() + v_margin, byte_width, option.rect.height() - 2 * v_margin};
auto color_role = option.state & QStyle::State_Selected ? QPalette::HighlightedText: QPalette::Text;
painter->setPen(option.palette.color(color_role));
painter->setFont(fixed_font);
int space = painter->boundingRect(option.rect, option.displayAlignment, " ").width();
QRect pos = painter->boundingRect(option.rect, option.displayAlignment, "00").adjusted(0, 0, 2, 0);
pos.moveLeft(pos.x() + space);
int m = space / 2;
const QMargins margins(m, m, m, m);
auto colors = index.data(Qt::UserRole).value<QVector<QColor>>();
auto byte_list = index.data(Qt::DisplayRole).toString().split(" ");
for (int i = 0; i < byte_list.size(); ++i) {
if (i < colors.size() && colors[i].alpha() > 0) {
painter->fillRect(pos.marginsAdded(margins), colors[i]);
painter->fillRect(rc, colors[i]);
}
painter->drawText(pos, Qt::AlignCenter, byte_list[i]);
pos.moveLeft(pos.right() + space);
painter->drawText(rc, Qt::AlignCenter, toHex(byte_list[i]));
rc.moveLeft(rc.right() + 1);
}
}
@ -114,8 +114,8 @@ QValidator::State NameValidator::validate(QString &input, int &pos) const {
namespace utils {
QPixmap icon(const QString &id) {
static bool dark_theme = QApplication::style()->standardPalette().color(QPalette::WindowText).value() >
QApplication::style()->standardPalette().color(QPalette::Background).value();
static bool dark_theme = QApplication::palette().color(QPalette::WindowText).value() >
QApplication::palette().color(QPalette::Background).value();
QPixmap pm;
QString key = "bootstrap_" % id % (dark_theme ? "1" : "0");
if (!QPixmapCache::find(key, &pm)) {
@ -138,3 +138,13 @@ QToolButton *toolButton(const QString &icon, const QString &tooltip) {
btn->setAutoRaise(true);
return btn;
};
QString toHex(uint8_t byte) {
static std::array<QString, 256> hex = []() {
std::array<QString, 256> ret;
for (int i = 0; i < 256; ++i) ret[i] = QStringLiteral("%1").arg(i, 2, 16, QLatin1Char('0')).toUpper();
return ret;
}();
return hex[byte];
}

@ -14,7 +14,6 @@
#include "tools/cabana/dbcmanager.h"
using namespace dbcmanager;
class ChangeTracker {
public:
void compute(const QByteArray &dat, double ts, uint32_t freq);
@ -31,16 +30,22 @@ private:
QByteArray prev_dat;
};
enum {
ColorsRole = Qt::UserRole + 1,
BytesRole = Qt::UserRole + 2
};
class MessageBytesDelegate : public QStyledItemDelegate {
Q_OBJECT
public:
MessageBytesDelegate(QObject *parent);
void paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const override;
QFont fixed_font;
int byte_width;
};
inline QString toHex(const QByteArray &dat) { return dat.toHex(' ').toUpper(); }
inline char toHex(uint value) { return "0123456789ABCDEF"[value & 0xF]; }
QString toHex(uint8_t byte);
QColor getColor(const dbcmanager::Signal *sig);
class NameValidator : public QRegExpValidator {

@ -17,7 +17,7 @@ ALT_DELTA = 30
MATCH_NUM = 10
REPORT_STATS = 10
EPHEM_CACHE = "/data/params/d/LaikadEphemeris"
EPHEM_CACHE = "/data/params/d/LaikadEphemerisV2"
DOWNLOAD_CACHE = "/tmp/comma_download_cache"
SERVER_LOG_FILE = "/tmp/fuzzy_server.log"

@ -39,7 +39,7 @@ class TestLaikad(unittest.TestCase):
def setUp(self):
# ensure laikad cold start
Params().remove("LaikadEphemeris")
Params().remove("LaikadEphemerisV2")
os.environ["LAIKAD_NO_INTERNET"] = "1"
managed_processes['laikad'].start()

Loading…
Cancel
Save