November 2nd, 2024 Patch

This commit is contained in:
FrogAi 2024-11-02 19:36:15 -07:00
parent 5145bdbd8d
commit 9c56143539
36 changed files with 282 additions and 260 deletions

View File

@ -277,7 +277,6 @@ Export('envCython')
# Qt build environment
qt_env = env.Clone()
qt_modules = ["Widgets", "Gui", "Core", "Network", "Concurrent", "Multimedia", "Quick", "Qml", "QuickWidgets", "Location", "Positioning", "DBus", "Xml"]
qt_libs = []

View File

@ -112,7 +112,7 @@ std::unordered_map<std::string, uint32_t> keys = {
{"CurrentRoute", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION},
{"DisableLogging", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION},
{"DisablePowerDown", PERSISTENT},
{"DisableUpdates", PERSISTENT | FROGPILOT_STORAGE},
{"DisableUpdates", PERSISTENT},
{"DisengageOnAccelerator", PERSISTENT | FROGPILOT_STORAGE},
{"DmModelInitialized", CLEAR_ON_ONROAD_TRANSITION},
{"DongleId", PERSISTENT},
@ -339,13 +339,8 @@ std::unordered_map<std::string, uint32_t> keys = {
{"FrogPilotMinutes", PERSISTENT | FROGPILOT_TRACKING},
{"FrogPilotToggles", PERSISTENT},
{"FrogPilotTogglesUpdated", PERSISTENT},
{"FrogsGoMoo", PERSISTENT},
{"FrogsGoMoosTweak", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_VEHICLES},
{"FullMap", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_VISUALS},
{"GameBoyCalibrationParams", PERSISTENT},
{"GameBoyDrives", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"GameBoyLiveTorqueParameters", PERSISTENT},
{"GameBoyScore", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"GasRegenCmd", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_VEHICLES},
{"GMapKey", PERSISTENT},
{"GoatScream", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_VISUALS},
@ -544,10 +539,6 @@ std::unordered_map<std::string, uint32_t> keys = {
{"TetheringEnabled", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_OTHER},
{"ThemeDownloadProgress", PERSISTENT},
{"ThemeUpdated", PERSISTENT},
{"TombRaiderCalibrationParams", PERSISTENT},
{"TombRaiderDrives", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"TombRaiderLiveTorqueParameters", PERSISTENT},
{"TombRaiderScore", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"ToyotaDoors", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_VEHICLES},
{"TrafficFollow", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"TrafficJerkAcceleration", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},

View File

@ -77,11 +77,9 @@ public:
inline void putBoolNonBlocking(const std::string &key, bool val) {
putNonBlocking(key, val ? "1" : "0");
}
void putIntNonBlocking(const std::string &key, const std::string &val);
inline void putIntNonBlocking(const std::string &key, int val) {
putNonBlocking(key, std::to_string(val));
}
void putFloatNonBlocking(const std::string &key, const std::string &val);
inline void putFloatNonBlocking(const std::string &key, float val) {
putNonBlocking(key, std::to_string(val));
}

View File

@ -21,11 +21,8 @@ FRAME_FINGERPRINT = 100 # 1s
EventName = car.CarEvent.EventName
def get_startup_event(car_recognized, controller_available, fw_seen, block_user, frogpilot_toggles):
if block_user:
return EventName.blockUser
else:
event = EventName.customStartupAlert
def get_startup_event(car_recognized, controller_available, fw_seen):
event = EventName.customStartupAlert
if not car_recognized:
if fw_seen:

View File

@ -1,5 +1,5 @@
from cereal import car
from openpilot.selfdrive.car.chrysler.values import ChryslerFlags, RAM_CARS
from openpilot.selfdrive.car.chrysler.values import RAM_CARS, ChryslerFlags
GearShifter = car.CarState.GearShifter
VisualAlert = car.CarControl.HUDControl.VisualAlert

View File

@ -38,7 +38,7 @@ NEURAL_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/neural_ff_
class CarInterface(CarInterfaceBase):
@staticmethod
def get_pid_accel_limits(CP, current_speed, cruise_speed, frogpilot_toggles):
def get_pid_accel_limits(CP, current_speed, cruise_speed):
return CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX
# Determined by iteratively plotting and minimizing error for f(angle, speed) = steer.

View File

@ -22,7 +22,7 @@ SETTINGS_BUTTONS_DICT = {CruiseSettings.DISTANCE: ButtonType.gapAdjustCruise, Cr
class CarInterface(CarInterfaceBase):
@staticmethod
def get_pid_accel_limits(CP, current_speed, cruise_speed, frogpilot_toggles):
def get_pid_accel_limits(CP, current_speed, cruise_speed):
if CP.carFingerprint in HONDA_BOSCH:
return CarControllerParams.BOSCH_ACCEL_MIN, CarControllerParams.BOSCH_ACCEL_MAX
elif CP.enableGasInterceptor:

View File

@ -22,6 +22,8 @@ from openpilot.selfdrive.controls.lib.drive_helpers import CRUISE_LONG_PRESS, V_
from openpilot.selfdrive.controls.lib.events import Events
from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel
from openpilot.selfdrive.frogpilot.frogpilot_variables import get_frogpilot_toggles
ButtonType = car.CarState.ButtonEvent.Type
FrogPilotButtonType = custom.FrogPilotCarState.ButtonEvent.Type
GearShifter = car.CarState.GearShifter
@ -223,6 +225,8 @@ class CarInterfaceBase(ABC):
self.CC: CarControllerBase = CarController(dbc_name, CP, self.VM)
# FrogPilot variables
self.frogpilot_toggles = get_frogpilot_toggles(True)
self.params = Params()
self.params_memory = Params("/dev/shm/params")
@ -231,15 +235,13 @@ class CarInterfaceBase(ABC):
comma_nnff_supported = self.check_comma_nn_ff_support(CP.carFingerprint)
nnff_supported = self.initialize_lat_torque_nn(CP.carFingerprint, eps_firmware)
lateral_tune = self.params.get_bool("LateralTune")
self.use_nnff = not comma_nnff_supported and nnff_supported and lateral_tune and self.params.get_bool("NNFF")
self.use_nnff_lite = not self.use_nnff and lateral_tune and self.params.get_bool("NNFFLite")
self.use_nnff = not comma_nnff_supported and nnff_supported and self.frogpilot_toggles.nnff
self.use_nnff_lite = not self.use_nnff and self.frogpilot_toggles.nnff_lite
self.always_on_lateral_disabled = False
self.belowSteerSpeed_shown = False
self.disable_belowSteerSpeed = False
self.disable_resumeRequired = False
self.is_gm = self.CP.carName == "gm"
self.prev_distance_button = False
self.resumeRequired_shown = False
self.traffic_mode_active = False
@ -247,6 +249,8 @@ class CarInterfaceBase(ABC):
self.gap_counter = 0
self.is_gm = self.CP.carName == "gm"
def get_ff_nn(self, x):
return self.lat_torque_nn_model.evaluate(x)
@ -263,7 +267,7 @@ class CarInterfaceBase(ABC):
return self.CC.update(c, self.CS, now_nanos, frogpilot_toggles)
@staticmethod
def get_pid_accel_limits(CP, current_speed, cruise_speed, frogpilot_toggles):
def get_pid_accel_limits(CP, current_speed, cruise_speed):
return ACCEL_MIN, ACCEL_MAX
@classmethod

View File

@ -1 +0,0 @@
{"input_std":[[9.281861],[1.8477924],[0.7977224],[0.047467366],[1.7969038],[1.8168812],[1.8351218],[1.785757],[1.7335743],[1.6658221],[1.5893887],[0.047346078],[0.0473731],[0.047383286],[0.047291175],[0.047300573],[0.04712479],[0.046799928]],"model_test_loss":0.027355343103408813,"input_size":18,"current_date_and_time":"2023-08-05_05-11-44","input_mean":[[21.655252],[-0.07694559],[-0.006081294],[-0.007598456],[-0.07309746],[-0.075890236],[-0.07804942],[-0.076106496],[-0.07184982],[-0.06528668],[-0.060404416],[-0.0077262702],[-0.0077046235],[-0.0076850485],[-0.007687444],[-0.007708868],[-0.0077959923],[-0.008017422]],"input_vars":["v_ego","lateral_accel","lateral_jerk","roll","lateral_accel_m03","lateral_accel_m02","lateral_accel_m01","lateral_accel_p03","lateral_accel_p06","lateral_accel_p10","lateral_accel_p15","roll_m03","roll_m02","roll_m01","roll_p03","roll_p06","roll_p10","roll_p15"],"output_size":1,"layers":[{"dense_1_b":[[-0.35776415],[-0.126288],[0.007988413],[0.03850029],[-0.056796823],[0.0072075897],[0.17376427]],"dense_1_W":[[0.010538558,6.7293744,-0.007391298,-1.035045,-0.47446147,1.0940393,0.08225446,-0.5795131,0.573115,1.82923,-0.16999252,0.8818023,0.03560901,-0.9470653,-1.042151,1.1532398,1.9009485,-1.2265956],[0.009010456,-1.3618345,0.039026346,0.22943486,-0.6669799,-0.768271,-0.16828564,-0.13406865,0.19760236,-0.18953702,-0.019137766,0.1468623,0.26367718,0.4732375,0.73679143,0.62450147,0.30198866,-0.93340015],[-0.044318866,2.2138615,9.620889,-0.66480356,-0.06849887,-0.038568456,-0.30580127,-0.088089585,0.31187677,0.5968372,-1.1462088,0.13234706,0.29166338,-0.69978577,-0.01790655,-0.097928315,-0.56950736,0.7560642],[1.3758256,0.8700429,-0.24295154,0.20832618,-0.7735097,1.0379355,-0.60753095,-0.5457418,-1.0892137,-0.6708325,0.24982774,0.09251328,0.08596103,-0.58034134,-0.3046114,-0.19754426,0.006461508,0.5989185],[0.06314328,-2.492993,-0.28200585,0.49902886,0.8513198,-0.5704965,1.0960953,-0.08426956,-0.76074624,0.10669376,0.02775254,-0.42194095,-0.34657434,-0.10863868,0.17019278,0.0963825,-0.10169116,0.21243806],[0.007984091,-1.9276509,-0.0013926353,0.04057924,1.4438432,1.3440262,-2.506722,1.700801,0.72410774,0.13471895,-0.18753268,0.7303607,0.018133093,-0.71643597,0.07050904,-0.30161944,0.085108586,0.061202843],[0.9413167,-0.9954305,-0.19510143,-0.4711845,-0.12398665,-0.45175523,1.0616771,0.28550953,-0.55543137,-0.21576759,-0.2364377,-0.012782618,-0.050565187,0.257694,-0.20975965,0.00022543047,-0.08760746,0.4983852]],"activation":"σ"},{"dense_2_W":[[-0.71804935,0.017023304,-0.099854074,-0.3262651,-0.402829,-0.12073083,0.13537839],[-0.44002575,-0.1071093,-0.58886194,-0.17319413,-0.21134079,0.23135148,0.0006880979],[-0.55711204,-0.8693639,-0.6443761,-0.7382846,0.18980889,-0.6082511,-0.63103676],[0.11338112,-0.5327033,0.2856197,0.32239884,-0.72682667,0.5302305,-0.45094746],[-0.35197002,-0.14440043,-0.025249843,-0.48697743,0.3340018,-0.25992322,0.0050561456],[0.34757507,0.15670523,-0.14263277,0.50704384,-0.020171141,0.6408679,-0.3074123],[0.40258837,-0.59363264,0.35948923,-0.060853776,-0.0072541097,0.89743376,-0.49789146],[-0.63476,0.29580453,0.1689314,-0.5061521,0.24901053,-0.23218995,0.57968193],[-0.66173035,0.50861925,-0.5845035,-0.6602214,0.8341883,-0.31437424,0.8046359],[0.038493533,0.15464582,-0.04848341,-0.57820857,-0.25891733,-0.47527292,0.21441916],[-0.15464531,-0.07454202,-0.8215851,-0.12614948,-0.5924209,0.00017916794,0.24154592],[0.6091424,-0.112086505,0.1144111,-0.31035227,-0.9237534,0.041003596,-0.3542808],[0.2989792,-0.23780549,0.116059326,-0.6056522,0.5499526,-0.9001413,0.5200723]],"activation":"σ","dense_2_b":[[-0.2638964],[-0.24607328],[-0.15493082],[-0.0071187904],[-0.23515384],[-0.09098133],[-0.034066215],[0.03609036],[-0.03842933],[-0.042302527],[-0.2439947],[-0.16342077],[-0.01030317]]},{"dense_3_W":[[0.45771673,-0.2084603,0.3570187,0.35835707,0.13684571,-0.582958,0.29889587,0.43543494,0.11841301,-0.26185623,-0.4988437,0.5752996,-0.28057483],[-0.19594137,0.050280698,-0.29057446,-0.2829161,-0.16987291,-0.21278952,-0.59946907,0.21295123,0.7040468,0.53549695,-0.52553934,-0.19560973,0.6233473],[-0.19091003,0.08669418,-0.5792192,0.57799137,-0.36263424,0.6037143,0.27898273,-0.30951327,-0.3572644,0.46720102,-0.5403428,0.32415462,-0.60570025]],"activation":"identity","dense_3_b":[[-0.0047377176],[0.023170695],[-0.021546118]]},{"dense_4_W":[[-0.12453941,-1.006034,0.96776205]],"dense_4_b":[[-0.02351544]],"activation":"identity"}]}

View File

@ -2,13 +2,13 @@ import math
from cereal import car
from openpilot.common.numpy_fast import clip, interp
from openpilot.common.params import Params
from openpilot.selfdrive.car import apply_meas_steer_torque_limits, apply_std_steer_angle_limits, common_fault_avoidance, create_gas_interceptor_command, make_can_msg, rate_limit
from openpilot.selfdrive.car.interfaces import CarControllerBase
from openpilot.selfdrive.car.toyota import toyotacan
from openpilot.selfdrive.car.toyota.values import CAR, STATIC_DSU_MSGS, NO_STOP_TIMER_CAR, TSS2_CAR, \
MIN_ACC_SPEED, PEDAL_TRANSITION, CarControllerParams, ToyotaFlags, \
UNSUPPORTED_DSU_CAR, STOP_AND_GO_CAR
from openpilot.selfdrive.controls.lib.drive_helpers import CRUISE_LONG_PRESS
from opendbc.can.packer import CANPacker
from openpilot.selfdrive.frogpilot.controls.lib.frogpilot_acceleration import get_max_allowed_accel
@ -60,9 +60,11 @@ class CarController(CarControllerBase):
self.accel = 0
# FrogPilot variables
params = Params()
self.doors_locked = False
self.reverse_cruise_active = False
self.cruise_timer = 0
self.previous_set_speed = 0
def update(self, CC, CS, now_nanos, frogpilot_toggles):
actuators = CC.actuators
@ -211,10 +213,10 @@ class CarController(CarControllerBase):
pcm_accel_cmd = min(pcm_accel_cmd, self.accel + ACCEL_WINDUP_LIMIT) if CC.longActive else 0.0
can_sends.append(toyotacan.create_accel_command(self.packer, pcm_accel_cmd, pcm_cancel_cmd, self.permit_braking, self.standstill_req, lead,
CS.acc_type, fcw_alert, self.distance_button, frogpilot_toggles))
CS.acc_type, fcw_alert, self.distance_button, self.reverse_cruise_active))
self.accel = pcm_accel_cmd
else:
can_sends.append(toyotacan.create_accel_command(self.packer, 0, pcm_cancel_cmd, True, False, lead, CS.acc_type, False, self.distance_button, frogpilot_toggles))
can_sends.append(toyotacan.create_accel_command(self.packer, 0, pcm_cancel_cmd, True, False, lead, CS.acc_type, False, self.distance_button, self.reverse_cruise_active))
if self.frame % 2 == 0 and self.CP.enableGasInterceptor and self.CP.openpilotLongitudinalControl:
# send exactly zero if gas cmd is zero. Interceptor will send the max between read value and gas cmd.
@ -258,6 +260,14 @@ class CarController(CarControllerBase):
new_actuators.steeringAngleDeg = self.last_angle
new_actuators.accel = self.accel
# FrogPilot Toyota carcontroller functions
if False: #self.previous_set_speed != CS.out.cruiseState.speedCluster:
self.cruise_timer = CRUISE_LONG_PRESS
elif self.cruise_timer > 0:
self.cruise_timer -= 1
else:
self.previous_set_speed = CS.out.cruiseState.speedCluster
# Lock doors when in drive / unlock doors when in park
if not self.doors_locked and CS.out.gearShifter != PARK:
if frogpilot_toggles.lock_doors:
@ -268,5 +278,8 @@ class CarController(CarControllerBase):
can_sends.append(make_can_msg(0x750, UNLOCK_CMD, 0))
self.doors_locked = False
self.reverse_cruise_active = frogpilot_toggles.reverse_cruise_increase
self.reverse_cruise_active &= self.cruise_timer <= 0
self.frame += 1
return new_actuators, can_sends

View File

@ -24,21 +24,22 @@ TEMP_STEER_FAULTS = (0, 9, 11, 21, 25)
# - prolonged high driver torque: 17 (permanent)
PERM_STEER_FAULTS = (3, 17)
# Traffic signals for Speed Limit Controller - Credit goes to the DragonPilot team!
@staticmethod
def calculate_speed_limit(cp_cam, frogpilot_toggles):
signals = ["TSGN1", "SPDVAL1", "SPLSGN1", "TSGN2", "SPLSGN2", "TSGN3", "SPLSGN3", "TSGN4", "SPLSGN4"]
traffic_signals = {signal: cp_cam.vl["RSA1"].get(signal, cp_cam.vl["RSA2"].get(signal)) for signal in signals}
tsgn1 = traffic_signals.get("TSGN1", None)
spdval1 = traffic_signals.get("SPDVAL1", None)
tsgn1 = traffic_signals.get("TSGN1")
spdval1 = traffic_signals.get("SPDVAL1")
if tsgn1 == 1 and not frogpilot_toggles.force_mph_dashboard:
return spdval1 * CV.KPH_TO_MS
elif tsgn1 == 36 or frogpilot_toggles.force_mph_dashboard:
return spdval1 * CV.MPH_TO_MS
else:
return 0
return 0
class CarState(CarStateBase):
def __init__(self, CP):

View File

@ -15,9 +15,8 @@ SteerControlType = car.CarParams.SteerControlType
class CarInterface(CarInterfaceBase):
@staticmethod
def get_pid_accel_limits(CP, current_speed, cruise_speed, frogpilot_toggles):
CCP = CarControllerParams(CP)
return CCP.ACCEL_MIN, CCP.ACCEL_MAX
def get_pid_accel_limits(CP, current_speed, cruise_speed):
return CarControllerParams(CP).ACCEL_MIN, CarControllerParams(CP).ACCEL_MAX
@staticmethod
def _get_params(ret, candidate, fingerprint, car_fw, disable_openpilot_long, experimental_long, docs, params):

View File

@ -33,7 +33,7 @@ def create_lta_steer_command(packer, steer_control_type, steer_angle, steer_req,
return packer.make_can_msg("STEERING_LTA", 0, values)
def create_accel_command(packer, accel, pcm_cancel, permit_braking, standstill_req, lead, acc_type, fcw_alert, distance, frogpilot_toggles):
def create_accel_command(packer, accel, pcm_cancel, permit_braking, standstill_req, lead, acc_type, fcw_alert, distance, reverse_cruise_active):
# TODO: find the exact canceling bit that does not create a chime
values = {
"ACCEL_CMD": accel, # compensated accel command
@ -43,7 +43,7 @@ def create_accel_command(packer, accel, pcm_cancel, permit_braking, standstill_r
"PERMIT_BRAKING": permit_braking,
"RELEASE_STANDSTILL": not standstill_req,
"CANCEL_REQ": pcm_cancel,
"ALLOW_LONG_PRESS": 2 if frogpilot_toggles.reverse_cruise_increase else 1,
"ALLOW_LONG_PRESS": 2 if reverse_cruise_active else 1,
"ACC_CUT_IN": fcw_alert, # only shown when ACC enabled
}
return packer.make_can_msg("ACC_CONTROL", 0, values)

View File

@ -36,7 +36,7 @@ class CarControllerParams:
self.ACCEL_MAX = 1.5 # m/s2, lower than allowed 2.0 m/s^2 for tuning reasons
self.ACCEL_MIN = -3.5 # m/s2
if CP.lateralTuning.which == 'torque':
if CP.lateralTuning.which() == 'torque':
self.STEER_DELTA_UP = 15 # 1.0s time to peak torque
self.STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50)
else:

View File

@ -80,7 +80,6 @@ class Controls:
# Ensure the current branch is cached, otherwise the first iteration of controlsd lags
self.branch = get_short_branch()
self.block_user = self.branch == "FrogPilot-Development" and self.params.get("DongleId", encoding='utf-8') != "FrogsGoMoo"
# Setup sockets
self.pm = messaging.PubMaster(['controlsState', 'carControl', 'onroadEvents', 'frogpilotCarControl'])
@ -164,7 +163,7 @@ class Controls:
self.can_log_mono_time = 0
self.startup_event = get_startup_event(car_recognized, not self.CP.passive, len(self.CP.carFw) > 0, self.block_user, get_frogpilot_toggles(True))
self.startup_event = get_startup_event(car_recognized, not self.CP.passive, len(self.CP.carFw) > 0)
if not sounds_available:
self.events.add(EventName.soundsUnavailable, static=True)
@ -194,10 +193,9 @@ class Controls:
self.resume_previously_pressed = False
self.steer_saturated_event_triggered = False
self.block_user = self.branch == "FrogPilot-Development" and self.params.get("DongleId", encoding='utf-8') != "FrogsGoMoo"
self.radarless_model = self.frogpilot_toggles.radarless_model
self.use_old_long = self.CP.carName == "hyundai" and not self.params.get_bool("NewLongAPI")
self.use_old_long |= self.CP.carName == "gm" and not self.params.get_bool("NewLongAPIGM")
self.use_old_long = self.frogpilot_toggles.old_long_api
self.display_timer = 0
@ -430,7 +428,7 @@ class Controls:
self.events.add_from_msg(self.sm['frogpilotPlan'].frogpilotEvents)
if self.block_user:
return EventName.blockUser
self.events.add(EventName.blockUser, static=True)
def data_sample(self):
"""Receive data from sockets"""
@ -618,7 +616,7 @@ class Controls:
if not self.joystick_mode:
# accel PID loop
pid_accel_limits = self.CI.get_pid_accel_limits(self.CP, CS.vEgo, self.v_cruise_helper.v_cruise_kph * CV.KPH_TO_MS, self.frogpilot_toggles)
pid_accel_limits = self.CI.get_pid_accel_limits(self.CP, CS.vEgo, self.v_cruise_helper.v_cruise_kph * CV.KPH_TO_MS)
if self.frogpilot_toggles.sport_plus:
pid_accel_limits = (pid_accel_limits[0], get_max_allowed_accel(CS.vEgo))

View File

@ -393,7 +393,7 @@ def torque_nn_load_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubM
"NNFF Torque Controller loaded",
model_name,
AlertStatus.frogpilot, AlertSize.mid,
Priority.LOW, VisualAlert.none, AudibleAlert.none, 5.0)
Priority.LOW, VisualAlert.none, AudibleAlert.engage, 5.0)
EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = {
@ -1023,8 +1023,8 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = {
# FrogPilot Events
EventName.blockUser: {
ET.NO_ENTRY: Alert(
"Please don't use the 'Development' branch!",
ET.PERMANENT: Alert(
"Don't use the 'Development' branch!",
"Forcing you into 'Dashcam Mode' for your safety",
AlertStatus.userPrompt, AlertSize.mid,
Priority.HIGHEST, VisualAlert.none, AudibleAlert.none, 1.),

View File

@ -205,7 +205,7 @@ def get_lead(v_ego: float, ready: bool, tracks: dict[int, Track], lead_msg: capn
lead_dict = closest_track.get_RadarState()
if 'dRel' in lead_dict:
lead_dict['dRel'] -= max(frogpilot_toggles.increased_stopped_distance + min(10 - v_ego, 0), 0) if not frogpilotCarState.trafficModeActive else 0
lead_dict['dRel'] -= frogpilot_toggles.increased_stopped_distance if not frogpilotCarState.trafficModeActive else 0
return lead_dict

View File

@ -6,7 +6,7 @@ from openpilot.selfdrive.frogpilot.frogpilot_utilities import delete_file, is_ur
GITHUB_URL = "https://raw.githubusercontent.com/FrogAi/FrogPilot-Resources/"
GITLAB_URL = "https://gitlab.com/FrogAi/FrogPilot-Resources/-/raw/"
def download_file(cancel_param, destination, progress_param, url, download_param, params_memory):
def download_file(cancel_param, destination, temp_destination, progress_param, url, download_param, params_memory):
try:
os.makedirs(os.path.dirname(destination), exist_ok=True)
total_size = get_remote_file_size(url)
@ -14,11 +14,11 @@ def download_file(cancel_param, destination, progress_param, url, download_param
return
downloaded_size = 0
with requests.get(url, stream=True, timeout=5) as response, open(destination, 'wb') as file:
with requests.get(url, stream=True, timeout=5) as response, open(temp_destination, 'wb') as file:
response.raise_for_status()
for chunk in response.iter_content(chunk_size=8192):
if params_memory.get_bool(cancel_param):
handle_error(destination, "Download cancelled.", "Download cancelled.", download_param, progress_param, params_memory)
handle_error(temp_destination, "Download cancelled.", "Download cancelled.", download_param, progress_param, params_memory)
return
if chunk:
@ -31,15 +31,17 @@ def download_file(cancel_param, destination, progress_param, url, download_param
else:
params_memory.put(progress_param, "Verifying authenticity...")
except Exception as e:
handle_request_error(e, destination, download_param, progress_param, params_memory)
handle_request_error(e, temp_destination, download_param, progress_param, params_memory)
def handle_error(destination, error_message, error, download_param, progress_param, params_memory):
print(f"Error occurred: {error}")
if destination:
delete_file(destination)
if download_param:
params_memory.remove(download_param)
if progress_param:
if progress_param and "404" not in error_message:
print(f"Error occurred: {error}")
params_memory.put(progress_param, error_message)
def handle_request_error(error, destination, download_param, progress_param, params_memory):
@ -51,9 +53,6 @@ def handle_request_error(error, destination, download_param, progress_param, par
}
error_message = error_map.get(type(error), "Unexpected error.")
if isinstance(error, requests.HTTPError) and error.response and error.response.status_code == 404:
return
handle_error(destination, f"Failed: {error_message}", error, download_param, progress_param, params_memory)
def get_remote_file_size(url):
@ -61,12 +60,18 @@ def get_remote_file_size(url):
response = requests.head(url, headers={'Accept-Encoding': 'identity'}, timeout=5)
if response.status_code == 404:
print(f"URL not found: {url}")
return None
return 0
response.raise_for_status()
return int(response.headers.get('Content-Length', 0))
except requests.HTTPError as e:
if e.response and e.response.status_code == 404:
print(f"URL not found: {url}")
return 0
handle_request_error(e, None, None, None, None)
return 0
except Exception as e:
handle_request_error(e, None, None, None, None)
return None
return 0
def get_repository_url():
if is_url_pingable("https://github.com"):
@ -75,22 +80,23 @@ def get_repository_url():
return GITLAB_URL
return None
def verify_download(file_path, url, initial_download=True):
def verify_download(file_path, temp_file_path, url, initial_download=True):
remote_file_size = get_remote_file_size(url)
if remote_file_size is None:
print(f"Error fetching remote size for {file_path}")
return False if initial_download else True
if not os.path.isfile(file_path):
print(f"File not found: {file_path}")
if not os.path.isfile(temp_file_path):
print(f"File not found: {temp_file_path}")
return False
try:
if remote_file_size != os.path.getsize(file_path):
print(f"File size mismatch for {file_path}")
if remote_file_size != os.path.getsize(temp_file_path):
print(f"File size mismatch for {temp_file_path}")
return False
except Exception as e:
print(f"An unexpected error occurred while trying to verify the {file_path} download: {e}")
print(f"An unexpected error occurred while trying to verify the {temp_file_path} download: {e}")
return False
os.rename(temp_file_path, file_path)
return True

View File

@ -73,8 +73,8 @@ class ModelManager:
else:
return {file['name'].replace('.thneed', ''): file['size'] for file in thneed_files if 'size' in file}
except requests.RequestException as e:
raise ConnectionError(f"Failed to fetch model sizes from {'GitHub' if 'github' in repo_url else 'GitLab'}: {e}")
except:
return {}
@staticmethod
def copy_default_model():
@ -92,40 +92,41 @@ class ModelManager:
shutil.copyfile(source_path, default_model_path)
print(f"Copied the default model from {source_path} to {default_model_path}")
def handle_verification_failure(self, model, model_path):
def handle_verification_failure(self, model, model_path, temp_model_path):
if self.params_memory.get_bool(self.cancel_download_param):
return
print(f"Verification failed for model {model}. Retrying from GitLab...")
model_url = f"{GITLAB_URL}Models/{model}.thneed"
download_file(self.cancel_download_param, model_path, self.download_progress_param, model_url, self.download_param, self.params_memory)
download_file(self.cancel_download_param, model_path, temp_model_path, self.download_progress_param, model_url, self.download_param, self.params_memory)
if verify_download(model_path, model_url):
if verify_download(model_path, temp_model_path, model_url):
print(f"Model {model} redownloaded and verified successfully from GitLab.")
else:
handle_error(model_path, "GitLab verification failed", "Verification failed", self.download_param, self.download_progress_param, self.params_memory)
def download_model(self, model_to_download):
model_path = os.path.join(MODELS_PATH, f"{model_to_download}.thneed")
temp_model_path = f"{os.path.splitext(model_path)[0]}_temp.thneed"
if os.path.isfile(model_path):
handle_error(model_path, "Model already exists...", "Model already exists...", self.download_param, self.download_progress_param, self.params_memory)
return
repo_url = get_repository_url()
if not repo_url:
handle_error(model_path, "GitHub and GitLab are offline...", "Repository unavailable", self.download_param, self.download_progress_param, self.params_memory)
handle_error(temp_model_path, "GitHub and GitLab are offline...", "Repository unavailable", self.download_param, self.download_progress_param, self.params_memory)
return
model_url = f"{repo_url}Models/{model_to_download}.thneed"
print(f"Downloading model: {model_to_download}")
download_file(self.cancel_download_param, model_path, self.download_progress_param, model_url, self.download_param, self.params_memory)
download_file(self.cancel_download_param, model_path, temp_model_path, self.download_progress_param, model_url, self.download_param, self.params_memory)
if verify_download(model_path, model_url):
if verify_download(model_path, temp_model_path, model_url):
print(f"Model {model_to_download} downloaded and verified successfully!")
self.params_memory.put(self.download_progress_param, "Downloaded!")
self.params_memory.remove(self.download_param)
else:
self.handle_verification_failure(model_to_download, model_path)
self.handle_verification_failure(model_to_download, model_path, temp_model_path)
def queue_model_download(self, model, model_name=None):
while self.params_memory.get(self.download_param, encoding='utf-8'):

View File

@ -261,7 +261,7 @@ class ThemeManager:
self.params_memory.put(DOWNLOAD_PROGRESS_PARAM, "Theme already exists...")
self.params_memory.remove(theme_param)
def handle_verification_failure(self, extentions, theme_component, theme_name, theme_param, download_path):
def handle_verification_failure(self, extensions, theme_component, theme_name, theme_param, download_path):
if theme_component == "distance_icons":
download_link = f"{GITLAB_URL}Distance-Icons/{theme_name}"
elif theme_component == "steering_wheels":
@ -269,13 +269,14 @@ class ThemeManager:
else:
download_link = f"{GITLAB_URL}Themes/{theme_name}/{theme_component}"
for ext in extentions:
for ext in extensions:
theme_path = download_path + ext
temp_theme_path = f"{os.path.splitext(theme_path)[0]}_temp{ext}"
theme_url = download_link + ext
print(f"Downloading theme from GitLab: {theme_name}")
download_file(CANCEL_DOWNLOAD_PARAM, theme_path, DOWNLOAD_PROGRESS_PARAM, theme_url, theme_param, self.params_memory)
download_file(CANCEL_DOWNLOAD_PARAM, theme_path, temp_theme_path, DOWNLOAD_PROGRESS_PARAM, theme_url, theme_param, self.params_memory)
if verify_download(theme_path, theme_url):
if verify_download(theme_path, temp_theme_path, theme_url):
print(f"Theme {theme_name} downloaded and verified successfully from GitLab!")
if ext == ".zip":
self.params_memory.put(DOWNLOAD_PROGRESS_PARAM, "Unpacking theme...")
@ -296,27 +297,29 @@ class ThemeManager:
if theme_component == "distance_icons":
download_link = f"{repo_url}Distance-Icons/{theme_name}"
download_path = os.path.join(THEME_SAVE_PATH, theme_component, theme_name)
extentions = [".zip"]
extensions = [".zip"]
elif theme_component == "steering_wheels":
download_link = f"{repo_url}Steering-Wheels/{theme_name}"
download_path = os.path.join(THEME_SAVE_PATH, theme_component, theme_name)
extentions = [".gif", ".png"]
extensions = [".gif", ".png"]
else:
download_link = f"{repo_url}Themes/{theme_name}/{theme_component}"
download_path = os.path.join(THEME_SAVE_PATH, "theme_packs", theme_name, theme_component)
extentions = [".zip"]
extensions = [".zip"]
for ext in extentions:
for ext in extensions:
theme_path = download_path + ext
temp_theme_path = f"{os.path.splitext(theme_path)[0]}_temp{ext}"
if os.path.isfile(theme_path):
handle_error(theme_path, "Theme already exists...", "Theme already exists...", theme_param, DOWNLOAD_PROGRESS_PARAM, self.params_memory)
return
theme_url = download_link + ext
print(f"Downloading theme from GitHub: {theme_name}")
download_file(CANCEL_DOWNLOAD_PARAM, theme_path, DOWNLOAD_PROGRESS_PARAM, theme_url, theme_param, self.params_memory)
download_file(CANCEL_DOWNLOAD_PARAM, theme_path, temp_theme_path, DOWNLOAD_PROGRESS_PARAM, theme_url, theme_param, self.params_memory)
if verify_download(theme_path, theme_url):
if verify_download(theme_path, temp_theme_path, theme_url):
print(f"Theme {theme_name} downloaded and verified successfully from GitHub!")
if ext == ".zip":
self.params_memory.put(DOWNLOAD_PROGRESS_PARAM, "Unpacking theme...")
@ -325,7 +328,7 @@ class ThemeManager:
self.params_memory.remove(theme_param)
return
self.handle_verification_failure(extentions, theme_component, theme_name, theme_param, download_path)
self.handle_verification_failure(extensions, theme_component, theme_name, theme_param, download_path)
def update_theme_params(self, downloadable_colors, downloadable_distance_icons, downloadable_icons, downloadable_signals, downloadable_sounds, downloadable_wheels):
def filter_existing_assets(assets, subfolder):

View File

@ -86,10 +86,10 @@ class FrogPilotPlanner:
self.v_cruise = self.frogpilot_vcruise.update(carState, controlsState, frogpilotCarControl, frogpilotCarState, frogpilotNavigation, modelData, v_cruise, v_ego, frogpilot_toggles)
def set_lead_status(self, frogpilotCarState, v_ego, frogpilot_toggles):
distance_offset = max(frogpilot_toggles.increased_stopped_distance + min(10 - v_ego, 0), 0) if not frogpilotCarState.trafficModeActive else 0
distance_offset = frogpilot_toggles.increased_stopped_distance if not frogpilotCarState.trafficModeActive else 0
following_lead = self.lead_one.status
following_lead &= 1 < self.lead_one.dRel - distance_offset < self.model_length + STOP_DISTANCE
following_lead &= 1 < self.lead_one.dRel < self.model_length + STOP_DISTANCE + distance_offset
following_lead &= v_ego > CRUISING_SPEED or self.tracking_lead
self.tracking_lead_mac.add_data(following_lead)

View File

@ -40,12 +40,12 @@ class SpeedLimitController:
def get_map_speed_limit(self, v_ego, frogpilot_toggles):
map_speed_limit = self.params_memory.get_float("MapSpeedLimit")
next_map_speed_limit = json.loads(self.params_memory.get("NextMapSpeedLimit"))
next_map_speed_limit = json.loads(self.params_memory.get("NextMapSpeedLimit", "{}"))
next_map_speed_limit_lat = next_map_speed_limit.get("latitude", 0)
next_map_speed_limit_lon = next_map_speed_limit.get("longitude", 0)
next_map_speed_limit_value = next_map_speed_limit.get("speedlimit", 0)
position = json.loads(self.params_memory.get("LastGPSPosition"))
position = json.loads(self.params_memory.get("LastGPSPosition", "{}"))
lat = position.get("latitude", 0)
lon = position.get("longitude", 0)

View File

@ -3,6 +3,8 @@ import os
import threading
import time
import openpilot.system.sentry as sentry
from cereal import messaging
from openpilot.common.params import Params
from openpilot.common.realtime import Priority, config_realtime_process
@ -85,11 +87,11 @@ def check_assets(model_manager, theme_manager, params, params_memory):
run_thread_with_lock("download_theme", theme_manager.download_theme, (asset_type, asset_to_download, param))
def update_checks(automatic_updates, model_manager, now, screen_off, started, theme_manager, time_validated, params, params_memory):
def update_checks(automatic_updates, frogs_go_moo, model_manager, now, screen_off, started, theme_manager, time_validated, params, params_memory):
if not (is_url_pingable("https://github.com") or is_url_pingable("https://gitlab.com")):
return
if automatic_updates and screen_off:
if automatic_updates and (screen_off or frogs_go_moo):
automatic_update_check(started, params)
if time_validated:
@ -136,7 +138,6 @@ def frogpilot_thread():
model_manager = ModelManager()
theme_manager = ThemeManager()
frogpilot_variables.update(False)
theme_manager.update_active_theme()
run_update_checks = False
@ -152,6 +153,10 @@ def frogpilot_thread():
toggles_last_updated = None
error_log = os.path.join(sentry.CRASHES_DIR, 'error.txt')
if os.path.isfile(error_log):
os.remove(error_log)
pm = messaging.PubMaster(['frogpilotPlan'])
sm = messaging.SubMaster(['carState', 'controlsState', 'deviceState', 'modelV2', 'radarState',
'frogpilotCarControl', 'frogpilotCarState', 'frogpilotNavigation'],
@ -184,6 +189,9 @@ def frogpilot_thread():
elif started and not started_previously:
radarless_model = frogpilot_toggles.radarless_model
if os.path.isfile(error_log):
os.remove(error_log)
if started and sm.updated['modelV2']:
frogpilot_planner.update(sm['carState'], sm['controlsState'], sm['frogpilotCarControl'], sm['frogpilotCarState'],
sm['frogpilotNavigation'], sm['modelV2'], radarless_model, sm['radarState'], frogpilot_toggles)
@ -201,12 +209,12 @@ def frogpilot_thread():
check_assets(model_manager, theme_manager, params, params_memory)
if params_memory.get_bool("ManualUpdateInitiated"):
run_thread_with_lock("update_checks", update_checks, (False, model_manager, now, screen_off, started, theme_manager, time_validated, params, params_memory))
run_thread_with_lock("update_checks", update_checks, (False, frogs_go_moo, model_manager, now, screen_off, started, theme_manager, time_validated, params, params_memory))
run_thread_with_lock("update_themes", theme_manager.update_themes())
elif now.second == 0:
run_update_checks = not screen_off and not started or now.minute % 15 == 0 or frogs_go_moo
elif run_update_checks:
run_thread_with_lock("update_checks", update_checks, (frogpilot_toggles.automatic_updates, model_manager, now, screen_off, started, theme_manager, time_validated, params, params_memory))
run_thread_with_lock("update_checks", update_checks, (frogpilot_toggles.automatic_updates, frogs_go_moo, model_manager, now, screen_off, started, theme_manager, time_validated, params, params_memory))
if time_validated:
theme_manager.update_holiday()

View File

@ -29,8 +29,12 @@ TO_RADIANS = math.pi / 180 # Conversion factor from
def get_frogpilot_toggles(block=False):
toggles_dict = json.loads(Params().get("FrogPilotToggles", block=block))
return SimpleNamespace(**toggles_dict)
while block:
namespace = SimpleNamespace(**json.loads(Params().get("FrogPilotToggles", block=True)))
if namespace != SimpleNamespace():
return namespace
time.sleep(0.1)
return SimpleNamespace(**json.loads(Params().get("FrogPilotToggles")))
def has_prime():
@ -143,7 +147,7 @@ frogpilot_default_params: list[tuple[str, str | bytes]] = [
("ForceStandstill", "0"),
("ForceStops", "0"),
("FPSCounter", "1"),
("FrogPilotToggles", "{}"),
("FrogPilotToggles", ""),
("FrogsGoMoosTweak", "1"),
("FullMap", "0"),
("GasRegenCmd", "1"),
@ -543,7 +547,7 @@ class FrogPilotVariables:
toggle.increase_thermal_limits = toggle.device_management and self.params.get_bool("IncreaseThermalLimits")
toggle.low_voltage_shutdown = clip(self.params.get_float("LowVoltageShutdown"), VBATT_PAUSE_CHARGING, 12.5) if toggle.device_management else VBATT_PAUSE_CHARGING
toggle.no_logging = toggle.device_management and self.params.get_bool("NoLogging")
toggle.no_uploads = toggle.device_management and self.params.get_bool("NoUploads")
toggle.no_uploads = toggle.device_management and self.params.get_bool("NoUploads") and not self.params.get_bool("DisableOnroadUploads")
toggle.offline_mode = toggle.device_management and self.params.get_bool("OfflineMode")
toggle.experimental_gm_tune = openpilot_longitudinal and car_make == "gm" and self.params.get_bool("ExperimentalGMTune")
@ -565,7 +569,7 @@ class FrogPilotVariables:
toggle.lateral_tuning = self.params.get_bool("LateralTune")
toggle.nnff = toggle.lateral_tuning and self.params.get_bool("NNFF")
toggle.smooth_curve_handling = toggle.lateral_tuning and self.params.get_bool("NNFFLite")
toggle.nnff_lite = toggle.lateral_tuning and self.params.get_bool("NNFFLite")
toggle.taco_tune = toggle.lateral_tuning and self.params.get_bool("TacoTune")
toggle.use_turn_desires = toggle.lateral_tuning and self.params.get_bool("TurnDesires")
@ -628,11 +632,11 @@ class FrogPilotVariables:
toggle.show_speed_limit_offset = toggle.navigation_ui and self.params.get_bool("ShowSLCOffset")
toggle.speed_limit_vienna = toggle.navigation_ui and self.params.get_bool("UseVienna")
toggle.new_long_api_gm = openpilot_longitudinal and car_make == "gm" and self.params.get_bool("NewLongAPIGM")
toggle.new_long_api_hkg = openpilot_longitudinal and car_make == "hyundai" and self.params.get_bool("NewLongAPI")
toggle.new_toyota_tune = openpilot_longitudinal and car_make == "toyota" and self.params.get_bool("NewToyotaTune")
toggle.old_long_api = openpilot_longitudinal and car_make == "gm" and not self.params.get_bool("NewLongAPIGM")
toggle.old_long_api |= openpilot_longitudinal and car_make == "hyundai" and not self.params.get_bool("NewLongAPI")
toggle.personalize_openpilot = self.params.get_bool("PersonalizeOpenpilot")
toggle.color_scheme = self.params.get("CustomColors", encoding='utf-8') if toggle.personalize_openpilot else "stock"
toggle.distance_icons = self.params.get("CustomDistanceIcons", encoding='utf-8') if toggle.personalize_openpilot else "stock"
@ -752,8 +756,8 @@ class FrogPilotVariables:
toggle.conditional_lead = toggle.conditional_experimental_mode and self.default_frogpilot_toggles.CELead
toggle.conditional_slower_lead = toggle.conditional_lead and self.default_frogpilot_toggles.CESlowerLead
toggle.conditional_stopped_lead = toggle.conditional_lead and self.default_frogpilot_toggles.CEStoppedLead
toggle.conditional_limit = self.default_frogpilot_toggles.CESpeed * speed_conversion if toggle.conditional_experimental_mode else 0
toggle.conditional_limit_lead = self.default_frogpilot_toggles.CESpeedLead * speed_conversion if toggle.conditional_experimental_mode else 0
toggle.conditional_limit = float(self.default_frogpilot_toggles.CESpeed) * speed_conversion if toggle.conditional_experimental_mode else 0
toggle.conditional_limit_lead = float(self.default_frogpilot_toggles.CESpeedLead) * speed_conversion if toggle.conditional_experimental_mode else 0
toggle.conditional_navigation = toggle.conditional_experimental_mode and self.default_frogpilot_toggles.CENavigation
toggle.conditional_navigation_intersections = toggle.conditional_navigation and self.default_frogpilot_toggles.CENavigationIntersections
toggle.conditional_navigation_lead = toggle.conditional_navigation and self.default_frogpilot_toggles.CENavigationLead
@ -768,8 +772,8 @@ class FrogPilotVariables:
toggle.crosstrek_torque = car_model == "SUBARU_IMPREZA" and self.default_frogpilot_toggles.CrosstrekTorque
toggle.curve_speed_controller = openpilot_longitudinal and self.default_frogpilot_toggles.CurveSpeedControl
toggle.curve_sensitivity = self.default_frogpilot_toggles.CurveSensitivity / 100 if toggle.curve_speed_controller else 1
toggle.turn_aggressiveness = self.default_frogpilot_toggles.TurnAggressiveness / 100 if toggle.curve_speed_controller else 1
toggle.curve_sensitivity = float(self.default_frogpilot_toggles.CurveSensitivity) / 100 if toggle.curve_speed_controller else 1
toggle.turn_aggressiveness = float(self.default_frogpilot_toggles.TurnAggressiveness) / 100 if toggle.curve_speed_controller else 1
toggle.disable_curve_speed_smoothing = toggle.curve_speed_controller and self.default_frogpilot_toggles.DisableCurveSpeedSmoothing
toggle.map_turn_speed_controller = toggle.curve_speed_controller and self.default_frogpilot_toggles.MTSCEnabled
toggle.mtsc_curvature_check = toggle.map_turn_speed_controller and self.default_frogpilot_toggles.MTSCCurvatureCheck
@ -777,32 +781,32 @@ class FrogPilotVariables:
toggle.custom_personalities = openpilot_longitudinal and self.default_frogpilot_toggles.CustomPersonalities
toggle.aggressive_profile = toggle.custom_personalities and self.default_frogpilot_toggles.AggressivePersonalityProfile
toggle.aggressive_jerk_deceleration = self.default_frogpilot_toggles.AggressiveJerkDeceleration / 100 if toggle.aggressive_profile else 0.5
toggle.aggressive_jerk_danger = self.default_frogpilot_toggles.AggressiveJerkDanger / 100 if toggle.aggressive_profile else 1.0
toggle.aggressive_jerk_speed = self.default_frogpilot_toggles.AggressiveJerkSpeed / 100 if toggle.aggressive_profile else 0.5
toggle.aggressive_jerk_speed_decrease = self.default_frogpilot_toggles.AggressiveJerkSpeedDecrease / 100 if toggle.aggressive_profile else 0.5
toggle.aggressive_follow = self.default_frogpilot_toggles.AggressiveFollow if toggle.aggressive_profile else 1.25
toggle.aggressive_jerk_deceleration = float(self.default_frogpilot_toggles.AggressiveJerkDeceleration) / 100 if toggle.aggressive_profile else 0.5
toggle.aggressive_jerk_danger = float(self.default_frogpilot_toggles.AggressiveJerkDanger) / 100 if toggle.aggressive_profile else 1.0
toggle.aggressive_jerk_speed = float(self.default_frogpilot_toggles.AggressiveJerkSpeed) / 100 if toggle.aggressive_profile else 0.5
toggle.aggressive_jerk_speed_decrease = float(self.default_frogpilot_toggles.AggressiveJerkSpeedDecrease) / 100 if toggle.aggressive_profile else 0.5
toggle.aggressive_follow = float(self.default_frogpilot_toggles.AggressiveFollow) if toggle.aggressive_profile else 1.25
toggle.standard_profile = toggle.custom_personalities and self.default_frogpilot_toggles.StandardPersonalityProfile
toggle.standard_jerk_acceleration = self.default_frogpilot_toggles.StandardJerkAcceleration / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_deceleration = self.default_frogpilot_toggles.StandardJerkDeceleration / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_danger = self.default_frogpilot_toggles.StandardJerkDanger / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_speed = self.default_frogpilot_toggles.StandardJerkSpeed / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_speed_decrease = self.default_frogpilot_toggles.StandardJerkSpeedDecrease / 100 if toggle.standard_profile else 1.0
toggle.standard_follow = self.default_frogpilot_toggles.StandardFollow if toggle.standard_profile else 1.45
toggle.standard_jerk_acceleration = float(self.default_frogpilot_toggles.StandardJerkAcceleration) / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_deceleration = float(self.default_frogpilot_toggles.StandardJerkDeceleration) / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_danger = float(self.default_frogpilot_toggles.StandardJerkDanger) / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_speed = float(self.default_frogpilot_toggles.StandardJerkSpeed) / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_speed_decrease = float(self.default_frogpilot_toggles.StandardJerkSpeedDecrease) / 100 if toggle.standard_profile else 1.0
toggle.standard_follow = float(self.default_frogpilot_toggles.StandardFollow) if toggle.standard_profile else 1.45
toggle.relaxed_profile = toggle.custom_personalities and self.default_frogpilot_toggles.RelaxedPersonalityProfile
toggle.relaxed_jerk_acceleration = self.default_frogpilot_toggles.RelaxedJerkAcceleration / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_deceleration = self.default_frogpilot_toggles.RelaxedJerkDeceleration / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_danger = self.default_frogpilot_toggles.RelaxedJerkDanger / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_speed = self.default_frogpilot_toggles.RelaxedJerkSpeed / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_speed_decrease = self.default_frogpilot_toggles.RelaxedJerkSpeedDecrease / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_follow = self.default_frogpilot_toggles.RelaxedFollow if toggle.relaxed_profile else 1.75
toggle.relaxed_jerk_acceleration = float(self.default_frogpilot_toggles.RelaxedJerkAcceleration) / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_deceleration = float(self.default_frogpilot_toggles.RelaxedJerkDeceleration) / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_danger = float(self.default_frogpilot_toggles.RelaxedJerkDanger) / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_speed = float(self.default_frogpilot_toggles.RelaxedJerkSpeed) / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_speed_decrease = float(self.default_frogpilot_toggles.RelaxedJerkSpeedDecrease) / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_follow = float(self.default_frogpilot_toggles.RelaxedFollow) if toggle.relaxed_profile else 1.75
toggle.traffic_profile = toggle.custom_personalities and self.default_frogpilot_toggles.TrafficPersonalityProfile
toggle.traffic_mode_jerk_acceleration = [self.default_frogpilot_toggles.TrafficJerkAcceleration / 100, toggle.aggressive_jerk_acceleration] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_jerk_deceleration = [self.default_frogpilot_toggles.TrafficJerkDeceleration / 100, toggle.aggressive_jerk_deceleration] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_jerk_danger = [self.default_frogpilot_toggles.TrafficJerkDanger / 100, toggle.aggressive_jerk_danger] if toggle.traffic_profile else [1.0, 1.0]
toggle.traffic_mode_jerk_speed = [self.default_frogpilot_toggles.TrafficJerkSpeed / 100, toggle.aggressive_jerk_speed] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_jerk_speed_decrease = [self.default_frogpilot_toggles.TrafficJerkSpeedDecrease / 100, toggle.aggressive_jerk_speed_decrease] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_t_follow = [self.default_frogpilot_toggles.TrafficFollow, toggle.aggressive_follow] if toggle.traffic_profile else [0.5, 1.0]
toggle.traffic_mode_jerk_acceleration = [float(self.default_frogpilot_toggles.TrafficJerkAcceleration) / 100, toggle.aggressive_jerk_acceleration] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_jerk_deceleration = [float(self.default_frogpilot_toggles.TrafficJerkDeceleration) / 100, toggle.aggressive_jerk_deceleration] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_jerk_danger = [float(self.default_frogpilot_toggles.TrafficJerkDanger) / 100, toggle.aggressive_jerk_danger] if toggle.traffic_profile else [1.0, 1.0]
toggle.traffic_mode_jerk_speed = [float(self.default_frogpilot_toggles.TrafficJerkSpeed) / 100, toggle.aggressive_jerk_speed] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_jerk_speed_decrease = [float(self.default_frogpilot_toggles.TrafficJerkSpeedDecrease) / 100, toggle.aggressive_jerk_speed_decrease] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_t_follow = [float(self.default_frogpilot_toggles.TrafficFollow), toggle.aggressive_follow] if toggle.traffic_profile else [0.5, 1.0]
toggle.custom_ui = self.default_frogpilot_toggles.CustomUI
toggle.acceleration_path = toggle.custom_ui and self.default_frogpilot_toggles.AccelerationPath
@ -839,10 +843,10 @@ class FrogPilotVariables:
toggle.use_si_metrics = toggle.developer_ui and self.default_frogpilot_toggles.UseSI
toggle.device_management = self.default_frogpilot_toggles.DeviceManagement
device_shutdown_setting = self.default_frogpilot_toggles.DeviceShutdown if toggle.device_management else 33
device_shutdown_setting = float(self.default_frogpilot_toggles.DeviceShutdown) if toggle.device_management else 33
toggle.device_shutdown_time = (device_shutdown_setting - 3) * 3600 if device_shutdown_setting >= 4 else device_shutdown_setting * (60 * 15)
toggle.increase_thermal_limits = toggle.device_management and self.default_frogpilot_toggles.IncreaseThermalLimits
toggle.low_voltage_shutdown = clip(self.default_frogpilot_toggles.LowVoltageShutdown, VBATT_PAUSE_CHARGING, 12.5) if toggle.device_management else VBATT_PAUSE_CHARGING
toggle.low_voltage_shutdown = clip(float(self.default_frogpilot_toggles.LowVoltageShutdown), VBATT_PAUSE_CHARGING, 12.5) if toggle.device_management else VBATT_PAUSE_CHARGING
toggle.no_logging = toggle.device_management and self.default_frogpilot_toggles.NoLogging
toggle.no_uploads = toggle.device_management and self.default_frogpilot_toggles.NoUploads
toggle.offline_mode = toggle.device_management and self.default_frogpilot_toggles.OfflineMode
@ -858,15 +862,15 @@ class FrogPilotVariables:
toggle.lane_change_customizations = self.default_frogpilot_toggles.LaneChangeCustomizations
toggle.lane_change_delay = self.default_frogpilot_toggles.LaneChangeTime if toggle.lane_change_customizations else 0
toggle.lane_detection_width = self.default_frogpilot_toggles.LaneDetectionWidth * distance_conversion if toggle.lane_change_customizations else 0
toggle.lane_detection_width = float(self.default_frogpilot_toggles.LaneDetectionWidth) * distance_conversion if toggle.lane_change_customizations else 0
toggle.lane_detection = toggle.lane_detection_width != 0
toggle.minimum_lane_change_speed = self.default_frogpilot_toggles.MinimumLaneChangeSpeed * speed_conversion if toggle.lane_change_customizations else LANE_CHANGE_SPEED_MIN
toggle.minimum_lane_change_speed = float(self.default_frogpilot_toggles.MinimumLaneChangeSpeed) * speed_conversion if toggle.lane_change_customizations else LANE_CHANGE_SPEED_MIN
toggle.nudgeless = toggle.lane_change_customizations and self.default_frogpilot_toggles.NudgelessLaneChange
toggle.one_lane_change = toggle.lane_change_customizations and self.default_frogpilot_toggles.OneLaneChange
toggle.lateral_tuning = self.default_frogpilot_toggles.LateralTune
toggle.nnff = toggle.lateral_tuning and self.default_frogpilot_toggles.NNFF
toggle.smooth_curve_handling = toggle.lateral_tuning and self.default_frogpilot_toggles.NNFFLite
toggle.nnff_lite = toggle.lateral_tuning and self.default_frogpilot_toggles.NNFFLite
toggle.taco_tune = toggle.lateral_tuning and self.default_frogpilot_toggles.TacoTune
toggle.use_turn_desires = toggle.lateral_tuning and self.default_frogpilot_toggles.TurnDesires
@ -874,9 +878,9 @@ class FrogPilotVariables:
toggle.human_acceleration = toggle.longitudinal_tuning and self.default_frogpilot_toggles.HumanAcceleration
toggle.human_following = toggle.longitudinal_tuning and self.default_frogpilot_toggles.HumanFollowing
toggle.increased_stopped_distance = self.default_frogpilot_toggles.IncreasedStoppedDistance * distance_conversion if toggle.longitudinal_tuning else 0
toggle.lead_detection_probability = clip(self.default_frogpilot_toggles.LeadDetectionThreshold / 100, 0.01, 0.99) if toggle.longitudinal_tuning else 0.5
toggle.max_desired_acceleration = clip(self.default_frogpilot_toggles.MaxDesiredAcceleration, 0.1, 4.0) if toggle.longitudinal_tuning else 4.0
toggle.increased_stopped_distance = float(self.default_frogpilot_toggles.IncreasedStoppedDistance) * distance_conversion if toggle.longitudinal_tuning else 0
toggle.lead_detection_probability = clip(float(self.default_frogpilot_toggles.LeadDetectionThreshold) / 100, 0.01, 0.99) if toggle.longitudinal_tuning else 0.5
toggle.max_desired_acceleration = clip(float(self.default_frogpilot_toggles.MaxDesiredAcceleration), 0.1, 4.0) if toggle.longitudinal_tuning else 4.0
toggle.model = DEFAULT_MODEL
toggle.part_model_param = ""
@ -886,10 +890,10 @@ class FrogPilotVariables:
toggle.model_ui = self.default_frogpilot_toggles.ModelUI
toggle.dynamic_path_width = toggle.model_ui and self.default_frogpilot_toggles.DynamicPathWidth
toggle.lane_line_width = self.default_frogpilot_toggles.LaneLinesWidth * small_distance_conversion / 200 if toggle.model_ui else 0.025
toggle.path_edge_width = self.default_frogpilot_toggles.PathEdgeWidth if toggle.model_ui else 20
toggle.path_width = self.default_frogpilot_toggles.PathWidth * distance_conversion / 2 if toggle.model_ui else 0.9
toggle.road_edge_width = self.default_frogpilot_toggles.RoadEdgesWidth * small_distance_conversion / 200 if toggle.model_ui else 0.025
toggle.lane_line_width = float(self.default_frogpilot_toggles.LaneLinesWidth) * small_distance_conversion / 200 if toggle.model_ui else 0.025
toggle.path_edge_width = float(self.default_frogpilot_toggles.PathEdgeWidth) if toggle.model_ui else 20
toggle.path_width = float(self.default_frogpilot_toggles.PathWidth) * distance_conversion / 2 if toggle.model_ui else 0.9
toggle.road_edge_width = float(self.default_frogpilot_toggles.RoadEdgesWidth) * small_distance_conversion / 200 if toggle.model_ui else 0.025
toggle.show_stopping_point = toggle.model_ui and self.default_frogpilot_toggles.ShowStoppingPoint
toggle.show_stopping_point_metrics = toggle.show_stopping_point and self.default_frogpilot_toggles.ShowStoppingPointMetrics
toggle.unlimited_road_ui_length = toggle.model_ui and self.default_frogpilot_toggles.UnlimitedLength
@ -902,17 +906,17 @@ class FrogPilotVariables:
toggle.show_speed_limit_offset = toggle.navigation_ui and self.default_frogpilot_toggles.ShowSLCOffset
toggle.speed_limit_vienna = toggle.navigation_ui and self.default_frogpilot_toggles.UseVienna
toggle.new_long_api_gm = openpilot_longitudinal and car_make == "gm" and self.default_frogpilot_toggles.NewLongAPIGM
toggle.new_long_api_hkg = openpilot_longitudinal and car_make == "hyundai" and self.default_frogpilot_toggles.NewLongAPI
toggle.old_long_api = openpilot_longitudinal and car_make == "gm" and not self.default_frogpilot_toggles.NewLongAPIGM
toggle.old_long_api |= openpilot_longitudinal and car_make == "hyundai" and not self.default_frogpilot_toggles.NewLongAPI
toggle.new_toyota_tune = openpilot_longitudinal and car_make == "toyota" and self.default_frogpilot_toggles.NewToyotaTune
toggle.quality_of_life_lateral = self.default_frogpilot_toggles.QOLLateral
toggle.pause_lateral_below_speed = self.default_frogpilot_toggles.PauseLateralSpeed * speed_conversion if toggle.quality_of_life_lateral else 0
toggle.pause_lateral_below_speed = float(self.default_frogpilot_toggles.PauseLateralSpeed) * speed_conversion if toggle.quality_of_life_lateral else 0
toggle.quality_of_life_longitudinal = self.default_frogpilot_toggles.QOLLongitudinal
toggle.custom_cruise_increase = self.default_frogpilot_toggles.CustomCruise if toggle.quality_of_life_longitudinal and not pcm_cruise else 1
toggle.custom_cruise_increase_long = self.default_frogpilot_toggles.CustomCruiseLong if toggle.quality_of_life_longitudinal and not pcm_cruise else 5
toggle.custom_cruise_increase = float(self.default_frogpilot_toggles.CustomCruise) if toggle.quality_of_life_longitudinal and not pcm_cruise else 1
toggle.custom_cruise_increase_long = float(self.default_frogpilot_toggles.CustomCruiseLong) if toggle.quality_of_life_longitudinal and not pcm_cruise else 5
toggle.force_standstill = toggle.quality_of_life_longitudinal and self.default_frogpilot_toggles.ForceStandstill
toggle.force_stops = toggle.quality_of_life_longitudinal and self.default_frogpilot_toggles.ForceStops
toggle.map_gears = toggle.quality_of_life_longitudinal and self.default_frogpilot_toggles.MapGears
@ -920,7 +924,7 @@ class FrogPilotVariables:
toggle.map_deceleration = toggle.map_gears and self.default_frogpilot_toggles.MapDeceleration
toggle.pause_lateral_below_signal = toggle.pause_lateral_below_speed != 0 and self.default_frogpilot_toggles.PauseLateralOnSignal
toggle.reverse_cruise_increase = toggle.quality_of_life_longitudinal and pcm_cruise and self.default_frogpilot_toggles.ReverseCruise
toggle.set_speed_offset = self.default_frogpilot_toggles.SetSpeedOffset * (1 if toggle.is_metric else CV.MPH_TO_KPH) if toggle.quality_of_life_longitudinal and not pcm_cruise else 0
toggle.set_speed_offset = float(self.default_frogpilot_toggles.SetSpeedOffset) * (1 if toggle.is_metric else CV.MPH_TO_KPH) if toggle.quality_of_life_longitudinal and not pcm_cruise else 0
toggle.camera_view = self.default_frogpilot_toggles.CameraView if toggle.quality_of_life_visuals else 0
toggle.driver_camera_in_reverse = toggle.quality_of_life_visuals and self.default_frogpilot_toggles.DriverCamera
@ -930,17 +934,17 @@ class FrogPilotVariables:
toggle.random_events = self.default_frogpilot_toggles.RandomEvents
toggle.screen_management = self.default_frogpilot_toggles.ScreenManagement
toggle.screen_brightness = self.default_frogpilot_toggles.ScreenBrightness if toggle.screen_management else 101
toggle.screen_brightness_onroad = self.default_frogpilot_toggles.ScreenBrightnessOnroad if toggle.screen_management else 101
toggle.screen_brightness = float(self.default_frogpilot_toggles.ScreenBrightness) if toggle.screen_management else 101
toggle.screen_brightness_onroad = float(self.default_frogpilot_toggles.ScreenBrightnessOnroad) if toggle.screen_management else 101
toggle.screen_recorder = toggle.screen_management and self.default_frogpilot_toggles.ScreenRecorder
toggle.screen_timeout = self.default_frogpilot_toggles.ScreenTimeout if toggle.screen_management else 30
toggle.screen_timeout_onroad = self.default_frogpilot_toggles.ScreenTimeoutOnroad if toggle.screen_management else 10
toggle.screen_timeout = float(self.default_frogpilot_toggles.ScreenTimeout) if toggle.screen_management else 30
toggle.screen_timeout_onroad = float(self.default_frogpilot_toggles.ScreenTimeoutOnroad) if toggle.screen_management else 10
toggle.sng_hack = openpilot_longitudinal and car_make == "toyota" and self.default_frogpilot_toggles.SNGHack
toggle.force_mph_dashboard = toggle.speed_limit_controller and self.default_frogpilot_toggles.ForceMPHDashboard
toggle.map_speed_lookahead_higher = self.default_frogpilot_toggles.SLCLookaheadHigher if toggle.speed_limit_controller else 0
toggle.map_speed_lookahead_lower = self.default_frogpilot_toggles.SLCLookaheadLower if toggle.speed_limit_controller else 0
toggle.map_speed_lookahead_higher = float(self.default_frogpilot_toggles.SLCLookaheadHigher) if toggle.speed_limit_controller else 0
toggle.map_speed_lookahead_lower = float(self.default_frogpilot_toggles.SLCLookaheadLower) if toggle.speed_limit_controller else 0
toggle.set_speed_limit = toggle.speed_limit_controller and self.default_frogpilot_toggles.SetSpeedLimit
slc_fallback_method = self.default_frogpilot_toggles.SLCFallback if toggle.speed_limit_controller else 0
toggle.slc_fallback_experimental_mode = toggle.speed_limit_controller and slc_fallback_method == 1
@ -1003,38 +1007,38 @@ class FrogPilotVariables:
toggle.crosstrek_torque = car_model == "SUBARU_IMPREZA" and self.default_frogpilot_toggles.CrosstrekTorque
toggle.curve_sensitivity = self.default_frogpilot_toggles.CurveSensitivity / 100 if toggle.curve_speed_controller else 1
toggle.turn_aggressiveness = self.default_frogpilot_toggles.TurnAggressiveness / 100 if toggle.curve_speed_controller else 1
toggle.curve_sensitivity = float(self.default_frogpilot_toggles.CurveSensitivity) / 100 if toggle.curve_speed_controller else 1
toggle.turn_aggressiveness = float(self.default_frogpilot_toggles.TurnAggressiveness) / 100 if toggle.curve_speed_controller else 1
toggle.mtsc_curvature_check = toggle.map_turn_speed_controller and self.default_frogpilot_toggles.MTSCCurvatureCheck
toggle.custom_personalities = openpilot_longitudinal and self.default_frogpilot_toggles.CustomPersonalities
toggle.aggressive_profile = toggle.custom_personalities and self.default_frogpilot_toggles.AggressivePersonalityProfile
toggle.aggressive_jerk_deceleration = self.default_frogpilot_toggles.AggressiveJerkDeceleration / 100 if toggle.aggressive_profile else 0.5
toggle.aggressive_jerk_danger = self.default_frogpilot_toggles.AggressiveJerkDanger / 100 if toggle.aggressive_profile else 1.0
toggle.aggressive_jerk_speed = self.default_frogpilot_toggles.AggressiveJerkSpeed / 100 if toggle.aggressive_profile else 0.5
toggle.aggressive_jerk_speed_decrease = self.default_frogpilot_toggles.AggressiveJerkSpeedDecrease / 100 if toggle.aggressive_profile else 0.5
toggle.aggressive_follow = self.default_frogpilot_toggles.AggressiveFollow if toggle.aggressive_profile else 1.25
toggle.aggressive_jerk_deceleration = float(self.default_frogpilot_toggles.AggressiveJerkDeceleration) / 100 if toggle.aggressive_profile else 0.5
toggle.aggressive_jerk_danger = float(self.default_frogpilot_toggles.AggressiveJerkDanger) / 100 if toggle.aggressive_profile else 1.0
toggle.aggressive_jerk_speed = float(self.default_frogpilot_toggles.AggressiveJerkSpeed) / 100 if toggle.aggressive_profile else 0.5
toggle.aggressive_jerk_speed_decrease = float(self.default_frogpilot_toggles.AggressiveJerkSpeedDecrease) / 100 if toggle.aggressive_profile else 0.5
toggle.aggressive_follow = float(self.default_frogpilot_toggles.AggressiveFollow) if toggle.aggressive_profile else 1.25
toggle.standard_profile = toggle.custom_personalities and self.default_frogpilot_toggles.StandardPersonalityProfile
toggle.standard_jerk_acceleration = self.default_frogpilot_toggles.StandardJerkAcceleration / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_deceleration = self.default_frogpilot_toggles.StandardJerkDeceleration / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_danger = self.default_frogpilot_toggles.StandardJerkDanger / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_speed = self.default_frogpilot_toggles.StandardJerkSpeed / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_speed_decrease = self.default_frogpilot_toggles.StandardJerkSpeedDecrease / 100 if toggle.standard_profile else 1.0
toggle.standard_follow = self.default_frogpilot_toggles.StandardFollow if toggle.standard_profile else 1.45
toggle.standard_jerk_acceleration = float(self.default_frogpilot_toggles.StandardJerkAcceleration) / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_deceleration = float(self.default_frogpilot_toggles.StandardJerkDeceleration) / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_danger = float(self.default_frogpilot_toggles.StandardJerkDanger) / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_speed = float(self.default_frogpilot_toggles.StandardJerkSpeed) / 100 if toggle.standard_profile else 1.0
toggle.standard_jerk_speed_decrease = float(self.default_frogpilot_toggles.StandardJerkSpeedDecrease) / 100 if toggle.standard_profile else 1.0
toggle.standard_follow = float(self.default_frogpilot_toggles.StandardFollow) if toggle.standard_profile else 1.45
toggle.relaxed_profile = toggle.custom_personalities and self.default_frogpilot_toggles.RelaxedPersonalityProfile
toggle.relaxed_jerk_acceleration = self.default_frogpilot_toggles.RelaxedJerkAcceleration / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_deceleration = self.default_frogpilot_toggles.RelaxedJerkDeceleration / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_danger = self.default_frogpilot_toggles.RelaxedJerkDanger / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_speed = self.default_frogpilot_toggles.RelaxedJerkSpeed / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_speed_decrease = self.default_frogpilot_toggles.RelaxedJerkSpeedDecrease / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_follow = self.default_frogpilot_toggles.RelaxedFollow if toggle.relaxed_profile else 1.75
toggle.relaxed_jerk_acceleration = float(self.default_frogpilot_toggles.RelaxedJerkAcceleration) / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_deceleration = float(self.default_frogpilot_toggles.RelaxedJerkDeceleration) / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_danger = float(self.default_frogpilot_toggles.RelaxedJerkDanger) / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_speed = float(self.default_frogpilot_toggles.RelaxedJerkSpeed) / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_jerk_speed_decrease = float(self.default_frogpilot_toggles.RelaxedJerkSpeedDecrease) / 100 if toggle.relaxed_profile else 1.0
toggle.relaxed_follow = float(self.default_frogpilot_toggles.RelaxedFollow) if toggle.relaxed_profile else 1.75
toggle.traffic_profile = toggle.custom_personalities and self.default_frogpilot_toggles.TrafficPersonalityProfile
toggle.traffic_mode_jerk_acceleration = [self.default_frogpilot_toggles.TrafficJerkAcceleration / 100, toggle.aggressive_jerk_acceleration] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_jerk_deceleration = [self.default_frogpilot_toggles.TrafficJerkDeceleration / 100, toggle.aggressive_jerk_deceleration] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_jerk_danger = [self.default_frogpilot_toggles.TrafficJerkDanger / 100, toggle.aggressive_jerk_danger] if toggle.traffic_profile else [1.0, 1.0]
toggle.traffic_mode_jerk_speed = [self.default_frogpilot_toggles.TrafficJerkSpeed / 100, toggle.aggressive_jerk_speed] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_jerk_speed_decrease = [self.default_frogpilot_toggles.TrafficJerkSpeedDecrease / 100, toggle.aggressive_jerk_speed_decrease] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_t_follow = [self.default_frogpilot_toggles.TrafficFollow, toggle.aggressive_follow] if toggle.traffic_profile else [0.5, 1.0]
toggle.traffic_mode_jerk_acceleration = [float(self.default_frogpilot_toggles.TrafficJerkAcceleration) / 100, toggle.aggressive_jerk_acceleration] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_jerk_deceleration = [float(self.default_frogpilot_toggles.TrafficJerkDeceleration) / 100, toggle.aggressive_jerk_deceleration] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_jerk_danger = [float(self.default_frogpilot_toggles.TrafficJerkDanger) / 100, toggle.aggressive_jerk_danger] if toggle.traffic_profile else [1.0, 1.0]
toggle.traffic_mode_jerk_speed = [float(self.default_frogpilot_toggles.TrafficJerkSpeed) / 100, toggle.aggressive_jerk_speed] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_jerk_speed_decrease = [float(self.default_frogpilot_toggles.TrafficJerkSpeedDecrease) / 100, toggle.aggressive_jerk_speed_decrease] if toggle.traffic_profile else [0.5, 0.5]
toggle.traffic_mode_t_follow = [float(self.default_frogpilot_toggles.TrafficFollow), toggle.aggressive_follow] if toggle.traffic_profile else [0.5, 1.0]
toggle.adjacent_paths = toggle.custom_ui and self.default_frogpilot_toggles.AdjacentPath
@ -1064,7 +1068,7 @@ class FrogPilotVariables:
toggle.device_management = self.default_frogpilot_toggles.DeviceManagement
toggle.increase_thermal_limits = toggle.device_management and self.default_frogpilot_toggles.IncreaseThermalLimits
toggle.low_voltage_shutdown = clip(self.default_frogpilot_toggles.LowVoltageShutdown, VBATT_PAUSE_CHARGING, 12.5) if toggle.device_management else VBATT_PAUSE_CHARGING
toggle.low_voltage_shutdown = clip(float(self.default_frogpilot_toggles.LowVoltageShutdown), VBATT_PAUSE_CHARGING, 12.5) if toggle.device_management else VBATT_PAUSE_CHARGING
toggle.no_logging = toggle.device_management and self.default_frogpilot_toggles.NoLogging
toggle.no_uploads = toggle.device_management and self.default_frogpilot_toggles.NoUploads
toggle.offline_mode = toggle.device_management and self.default_frogpilot_toggles.OfflineMode
@ -1073,19 +1077,19 @@ class FrogPilotVariables:
toggle.frogsgomoo_tweak = openpilot_longitudinal and car_make == "toyota" and self.default_frogpilot_toggles.FrogsGoMoosTweak
toggle.lane_detection_width = self.default_frogpilot_toggles.LaneDetectionWidth * distance_conversion if toggle.lane_change_customizations else 0
toggle.lane_detection_width = float(self.default_frogpilot_toggles.LaneDetectionWidth) * distance_conversion if toggle.lane_change_customizations else 0
toggle.lane_detection = toggle.lane_detection_width != 0
toggle.minimum_lane_change_speed = self.default_frogpilot_toggles.MinimumLaneChangeSpeed * speed_conversion if toggle.lane_change_customizations else LANE_CHANGE_SPEED_MIN
toggle.minimum_lane_change_speed = float(self.default_frogpilot_toggles.MinimumLaneChangeSpeed) * speed_conversion if toggle.lane_change_customizations else LANE_CHANGE_SPEED_MIN
toggle.lateral_tuning = self.default_frogpilot_toggles.LateralTune
toggle.smooth_curve_handling = toggle.lateral_tuning and self.default_frogpilot_toggles.NNFFLite
toggle.nnff_lite = toggle.lateral_tuning and self.default_frogpilot_toggles.NNFFLite
toggle.taco_tune = toggle.lateral_tuning and self.default_frogpilot_toggles.TacoTune
toggle.use_turn_desires = toggle.lateral_tuning and self.default_frogpilot_toggles.TurnDesires
toggle.long_pitch = openpilot_longitudinal and car_make == "gm" and self.default_frogpilot_toggles.LongPitch
toggle.lead_detection_probability = clip(self.default_frogpilot_toggles.LeadDetectionThreshold / 100, 0.01, 0.99) if toggle.longitudinal_tuning else 0.5
toggle.max_desired_acceleration = clip(self.default_frogpilot_toggles.MaxDesiredAcceleration, 0.1, 4.0) if toggle.longitudinal_tuning else 4.0
toggle.lead_detection_probability = clip(float(self.default_frogpilot_toggles.LeadDetectionThreshold) / 100, 0.01, 0.99) if toggle.longitudinal_tuning else 0.5
toggle.max_desired_acceleration = clip(float(self.default_frogpilot_toggles.MaxDesiredAcceleration), 0.1, 4.0) if toggle.longitudinal_tuning else 4.0
toggle.model = DEFAULT_MODEL
toggle.part_model_param = ""
@ -1095,10 +1099,10 @@ class FrogPilotVariables:
toggle.model_ui = self.default_frogpilot_toggles.ModelUI
toggle.dynamic_path_width = toggle.model_ui and self.default_frogpilot_toggles.DynamicPathWidth
toggle.lane_line_width = self.default_frogpilot_toggles.LaneLinesWidth * small_distance_conversion / 200 if toggle.model_ui else 0.025
toggle.path_edge_width = self.default_frogpilot_toggles.PathEdgeWidth if toggle.model_ui else 20
toggle.path_width = self.default_frogpilot_toggles.PathWidth * distance_conversion / 2 if toggle.model_ui else 0.9
toggle.road_edge_width = self.default_frogpilot_toggles.RoadEdgesWidth * small_distance_conversion / 200 if toggle.model_ui else 0.025
toggle.lane_line_width = float(self.default_frogpilot_toggles.LaneLinesWidth) * small_distance_conversion / 200 if toggle.model_ui else 0.025
toggle.path_edge_width = float(self.default_frogpilot_toggles.PathEdgeWidth) if toggle.model_ui else 20
toggle.path_width = float(self.default_frogpilot_toggles.PathWidth) * distance_conversion / 2 if toggle.model_ui else 0.9
toggle.road_edge_width = float(self.default_frogpilot_toggles.RoadEdgesWidth) * small_distance_conversion / 200 if toggle.model_ui else 0.025
toggle.show_stopping_point = toggle.model_ui and self.default_frogpilot_toggles.ShowStoppingPoint
toggle.show_stopping_point_metrics = toggle.show_stopping_point and self.default_frogpilot_toggles.ShowStoppingPointMetrics
toggle.unlimited_road_ui_length = toggle.model_ui and self.default_frogpilot_toggles.UnlimitedLength
@ -1108,38 +1112,38 @@ class FrogPilotVariables:
toggle.show_speed_limit_offset = toggle.navigation_ui and self.default_frogpilot_toggles.ShowSLCOffset
toggle.speed_limit_vienna = toggle.navigation_ui and self.default_frogpilot_toggles.UseVienna
toggle.new_long_api_gm = openpilot_longitudinal and car_make == "gm" and self.default_frogpilot_toggles.NewLongAPIGM
toggle.new_long_api_hkg = openpilot_longitudinal and car_make == "hyundai" and self.default_frogpilot_toggles.NewLongAPI
toggle.old_long_api = openpilot_longitudinal and car_make == "gm" and not self.default_frogpilot_toggles.NewLongAPIGM
toggle.old_long_api |= openpilot_longitudinal and car_make == "hyundai" and not self.default_frogpilot_toggles.NewLongAPI
toggle.new_toyota_tune = openpilot_longitudinal and car_make == "toyota" and self.default_frogpilot_toggles.NewToyotaTune
toggle.quality_of_life_lateral = self.default_frogpilot_toggles.QOLLateral
toggle.pause_lateral_below_speed = self.default_frogpilot_toggles.PauseLateralSpeed * speed_conversion if toggle.quality_of_life_lateral else 0
toggle.pause_lateral_below_speed = float(self.default_frogpilot_toggles.PauseLateralSpeed) * speed_conversion if toggle.quality_of_life_lateral else 0
toggle.custom_cruise_increase = self.default_frogpilot_toggles.CustomCruise if toggle.quality_of_life_longitudinal and not pcm_cruise else 1
toggle.custom_cruise_increase_long = self.default_frogpilot_toggles.CustomCruiseLong if toggle.quality_of_life_longitudinal and not pcm_cruise else 5
toggle.custom_cruise_increase = float(self.default_frogpilot_toggles.CustomCruise) if toggle.quality_of_life_longitudinal and not pcm_cruise else 1
toggle.custom_cruise_increase_long = float(self.default_frogpilot_toggles.CustomCruiseLong) if toggle.quality_of_life_longitudinal and not pcm_cruise else 5
toggle.force_standstill = toggle.quality_of_life_longitudinal and self.default_frogpilot_toggles.ForceStandstill
toggle.force_stops = toggle.quality_of_life_longitudinal and self.default_frogpilot_toggles.ForceStops
toggle.pause_lateral_below_signal = toggle.pause_lateral_below_speed != 0 and self.default_frogpilot_toggles.PauseLateralOnSignal
toggle.reverse_cruise_increase = toggle.quality_of_life_longitudinal and pcm_cruise and self.default_frogpilot_toggles.ReverseCruise
toggle.set_speed_offset = self.default_frogpilot_toggles.SetSpeedOffset * (1 if toggle.is_metric else CV.MPH_TO_KPH) if toggle.quality_of_life_longitudinal and not pcm_cruise else 0
toggle.set_speed_offset = float(self.default_frogpilot_toggles.SetSpeedOffset) * (1 if toggle.is_metric else CV.MPH_TO_KPH) if toggle.quality_of_life_longitudinal and not pcm_cruise else 0
toggle.quality_of_life_visuals = self.default_frogpilot_toggles.QOLVisuals
toggle.camera_view = self.default_frogpilot_toggles.CameraView if toggle.quality_of_life_visuals else 0
toggle.standby_mode = toggle.quality_of_life_visuals and self.default_frogpilot_toggles.StandbyMode
toggle.screen_management = self.default_frogpilot_toggles.ScreenManagement
toggle.screen_brightness = self.default_frogpilot_toggles.ScreenBrightness if toggle.screen_management else 101
toggle.screen_brightness_onroad = self.default_frogpilot_toggles.ScreenBrightnessOnroad if toggle.screen_management else 101
toggle.screen_brightness = float(self.default_frogpilot_toggles.ScreenBrightness) if toggle.screen_management else 101
toggle.screen_brightness_onroad = float(self.default_frogpilot_toggles.ScreenBrightnessOnroad) if toggle.screen_management else 101
toggle.screen_recorder = toggle.screen_management and self.default_frogpilot_toggles.ScreenRecorder
toggle.screen_timeout = self.default_frogpilot_toggles.ScreenTimeout if toggle.screen_management else 30
toggle.screen_timeout_onroad = self.default_frogpilot_toggles.ScreenTimeoutOnroad if toggle.screen_management else 10
toggle.screen_timeout = float(self.default_frogpilot_toggles.ScreenTimeout) if toggle.screen_management else 30
toggle.screen_timeout_onroad = float(self.default_frogpilot_toggles.ScreenTimeoutOnroad) if toggle.screen_management else 10
toggle.sng_hack = openpilot_longitudinal and car_make == "toyota" and self.default_frogpilot_toggles.SNGHack
toggle.force_mph_dashboard = toggle.speed_limit_controller and self.default_frogpilot_toggles.ForceMPHDashboard
toggle.map_speed_lookahead_higher = self.default_frogpilot_toggles.SLCLookaheadHigher if toggle.speed_limit_controller else 0
toggle.map_speed_lookahead_lower = self.default_frogpilot_toggles.SLCLookaheadLower if toggle.speed_limit_controller else 0
toggle.map_speed_lookahead_higher = float(self.default_frogpilot_toggles.SLCLookaheadHigher) if toggle.speed_limit_controller else 0
toggle.map_speed_lookahead_lower = float(self.default_frogpilot_toggles.SLCLookaheadLower) if toggle.speed_limit_controller else 0
toggle.set_speed_limit = toggle.speed_limit_controller and self.default_frogpilot_toggles.SetSpeedLimit
toggle.speed_limit_priority1 = self.default_frogpilot_toggles.SLCPriority1 if toggle.speed_limit_controller else None
toggle.speed_limit_priority2 = self.default_frogpilot_toggles.SLCPriority2 if toggle.speed_limit_controller else None

View File

@ -225,7 +225,7 @@ FrogPilotThemesPanel::FrogPilotThemesPanel(FrogPilotSettingsWindow *parent) : Fr
QString selectedIconPack = formatIconNameForStorage(iconPackToDelete);
for (const QFileInfo &dirInfo : dirList) {
if (dirInfo.fileName() == selectedIconPack) {
QDir iconPackDir(dirInfo.absoluteFilePath() + "/distance_icons");
QDir iconPackDir(dirInfo.absoluteFilePath());
if (iconPackDir.exists()) {
iconPackDir.removeRecursively();
}
@ -892,6 +892,8 @@ FrogPilotThemesPanel::FrogPilotThemesPanel(FrogPilotSettingsWindow *parent) : Fr
QObject::connect(parent, &FrogPilotSettingsWindow::closeParentToggle, this, &FrogPilotThemesPanel::hideToggles);
QObject::connect(uiState(), &UIState::uiUpdate, this, &FrogPilotThemesPanel::updateState);
hideToggles();
}
void FrogPilotThemesPanel::showEvent(QShowEvent *event) {
@ -932,6 +934,7 @@ void FrogPilotThemesPanel::updateState(const UIState &s) {
});
paramsMemory.remove("ThemeDownloadProgress");
colorDownloading = false;
distanceIconDownloading = false;
iconDownloading = false;
signalDownloading = false;
soundDownloading = false;
@ -939,6 +942,7 @@ void FrogPilotThemesPanel::updateState(const UIState &s) {
wheelDownloading = false;
colorsDownloaded = params.get("DownloadableColors").empty();
distanceIconsDownloaded = params.get("DownloadableDistanceIcons").empty();
iconsDownloaded = params.get("DownloadableIcons").empty();
signalsDownloaded = params.get("DownloadableSignals").empty();
soundsDownloaded = params.get("DownloadableSounds").empty();

View File

@ -43,17 +43,17 @@ QColor loadThemeColors(const QString &colorKey, bool clearCache) {
);
}
bool FrogPilotConfirmationDialog::toggle(const QString &prompt_text, const QString &confirm_text, QWidget *parent) {
ConfirmationDialog d(prompt_text, confirm_text, tr("Reboot Later"), false, parent);
bool FrogPilotConfirmationDialog::toggle(const QString &prompt_text, const QString &confirm_text, QWidget *parent, const bool isLong) {
ConfirmationDialog d(prompt_text, confirm_text, tr("Reboot Later"), false, parent, isLong);
return d.exec();
}
bool FrogPilotConfirmationDialog::toggleAlert(const QString &prompt_text, const QString &button_text, QWidget *parent) {
ConfirmationDialog d(prompt_text, button_text, "", false, parent);
bool FrogPilotConfirmationDialog::toggleAlert(const QString &prompt_text, const QString &button_text, QWidget *parent, const bool isLong) {
ConfirmationDialog d(prompt_text, button_text, "", false, parent, isLong);
return d.exec();
}
bool FrogPilotConfirmationDialog::yesorno(const QString &prompt_text, QWidget *parent) {
ConfirmationDialog d(prompt_text, tr("Yes"), tr("No"), false, parent);
bool FrogPilotConfirmationDialog::yesorno(const QString &prompt_text, QWidget *parent, const bool isLong) {
ConfirmationDialog d(prompt_text, tr("Yes"), tr("No"), false, parent, isLong);
return d.exec();
}

View File

@ -46,9 +46,9 @@ class FrogPilotConfirmationDialog : public ConfirmationDialog {
public:
explicit FrogPilotConfirmationDialog(const QString &prompt_text, const QString &confirm_text,
const QString &cancel_text, const bool rich, QWidget *parent);
static bool toggle(const QString &prompt_text, const QString &confirm_text, QWidget *parent);
static bool toggleAlert(const QString &prompt_text, const QString &button_text, QWidget *parent);
static bool yesorno(const QString &prompt_text, QWidget *parent);
static bool toggle(const QString &prompt_text, const QString &confirm_text, QWidget *parent, const bool isLong=false);
static bool toggleAlert(const QString &prompt_text, const QString &button_text, QWidget *parent, const bool isLong=false);
static bool yesorno(const QString &prompt_text, QWidget *parent, const bool isLong=false);
};
class FrogPilotListWidget : public QWidget {

View File

@ -501,29 +501,29 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) {
int openpilotHours = params.getInt("openpilotMinutes") / 60;
if (frogpilotHours < 1 && openpilotHours < 100) {
if (FrogPilotConfirmationDialog::toggleAlert(tr("Welcome to FrogPilot! Since you're new to FrogPilot, the 'Basic' toggle preset has been applied, but you can change this at any time via the 'Customization Level' button!"), tr("Sounds good!"), this)) {
if (FrogPilotConfirmationDialog::toggleAlert(tr("Welcome to FrogPilot! Since you're new to FrogPilot, the 'Basic' toggle preset has been applied, but you can change this at any time via the 'Customization Level' button!"), tr("Sounds good!"), this, true)) {
params.putBoolNonBlocking("CustomizationLevelConfirmed", true);
params.putIntNonBlocking("CustomizationLevel", 0);
}
} else if (frogpilotHours < 50 && openpilotHours < 100) {
if (FrogPilotConfirmationDialog::toggleAlert(tr("Since you're fairly new to FrogPilot, the 'Basic' toggle preset has been applied, but you can change this at any time via the 'Customization Level' button!"), tr("Sounds good!"), this)) {
if (FrogPilotConfirmationDialog::toggleAlert(tr("Since you're fairly new to FrogPilot, the 'Basic' toggle preset has been applied, but you can change this at any time via the 'Customization Level' button!"), tr("Sounds good!"), this, true)) {
params.putBoolNonBlocking("CustomizationLevelConfirmed", true);
params.putIntNonBlocking("CustomizationLevel", 0);
}
} else if (frogpilotHours < 100) {
if (openpilotHours >= 100 && frogpilotHours < 100) {
if (FrogPilotConfirmationDialog::toggleAlert(tr("Since you're experienced with openpilot, the 'Standard' toggle preset has been applied, but you can change this at any time via the 'Customization Level' button!"), tr("Sounds good!"), this)) {
if (FrogPilotConfirmationDialog::toggleAlert(tr("Since you're experienced with openpilot, the 'Standard' toggle preset has been applied, but you can change this at any time via the 'Customization Level' button!"), tr("Sounds good!"), this, true)) {
params.putBoolNonBlocking("CustomizationLevelConfirmed", true);
params.putIntNonBlocking("CustomizationLevel", 1);
}
} else {
if (FrogPilotConfirmationDialog::toggleAlert(tr("Since you're experienced with FrogPilot, the 'Standard' toggle preset has been applied, but you can change this at any time via the 'Customization Level' button!"), tr("Sounds good!"), this)) {
if (FrogPilotConfirmationDialog::toggleAlert(tr("Since you're experienced with FrogPilot, the 'Standard' toggle preset has been applied, but you can change this at any time via the 'Customization Level' button!"), tr("Sounds good!"), this, true)) {
params.putBoolNonBlocking("CustomizationLevelConfirmed", true);
params.putIntNonBlocking("CustomizationLevel", 1);
}
}
} else if (frogpilotHours >= 100) {
if (FrogPilotConfirmationDialog::toggleAlert(tr("Since you're very experienced with FrogPilot, the 'Advanced' toggle preset has been applied, but you can change this at any time via the 'Customization Level' button!"), tr("Sounds good!"), this)) {
if (FrogPilotConfirmationDialog::toggleAlert(tr("Since you're very experienced with FrogPilot, the 'Advanced' toggle preset has been applied, but you can change this at any time via the 'Customization Level' button!"), tr("Sounds good!"), this, true)) {
params.putBoolNonBlocking("CustomizationLevelConfirmed", true);
params.putIntNonBlocking("CustomizationLevel", 2);
}

View File

@ -91,7 +91,7 @@ SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) {
auto uninstallBtn = new ButtonControl(tr("Uninstall %1").arg(getBrand()), tr("UNINSTALL"));
connect(uninstallBtn, &ButtonControl::clicked, [&]() {
if (ConfirmationDialog::confirm(tr("Are you sure you want to uninstall?"), tr("Uninstall"), this)) {
if (FrogPilotConfirmationDialog::yesorno(tr("Do you want to permanently delete any additional FrogPilot assets? This is 100% unrecoverable and includes backups, downloaded models, themes, and long-term storage toggle settings for easy reinstalls."), this)) {
if (FrogPilotConfirmationDialog::yesorno(tr("Do you want to permanently delete any additional FrogPilot assets? This is 100% unrecoverable and includes backups, models, and long-term storage toggle settings for easy reinstalls."), this, true)) {
std::system("rm -rf /data/backups");
std::system("rm -rf /data/crashes");
std::system("rm -rf /data/media/screen_recordings");

View File

@ -206,7 +206,7 @@ void InputDialog::updateMaxLengthSublabel(const QString &text) {
// ConfirmationDialog
ConfirmationDialog::ConfirmationDialog(const QString &prompt_text, const QString &confirm_text, const QString &cancel_text,
const bool rich, QWidget *parent) : DialogBase(parent) {
const bool rich, QWidget *parent, const bool isLong) : DialogBase(parent) {
QFrame *container = new QFrame(this);
container->setStyleSheet(R"(
QFrame { background-color: #1B1B1B; color: #C9C9C9; }
@ -214,7 +214,7 @@ ConfirmationDialog::ConfirmationDialog(const QString &prompt_text, const QString
#confirm_btn:pressed { background-color: #3049F4; }
)");
QVBoxLayout *main_layout = new QVBoxLayout(container);
main_layout->setContentsMargins(32, 32, 32, 32);
main_layout->setContentsMargins(32, rich || isLong ? 32 : 120, 32, 32);
QLabel *prompt = new QLabel(prompt_text, this);
prompt->setWordWrap(true);

View File

@ -65,7 +65,7 @@ class ConfirmationDialog : public DialogBase {
public:
explicit ConfirmationDialog(const QString &prompt_text, const QString &confirm_text,
const QString &cancel_text, const bool rich, QWidget* parent);
const QString &cancel_text, const bool rich, QWidget* parent, const bool isLong=false);
static bool alert(const QString &prompt_text, QWidget *parent);
static bool confirm(const QString &prompt_text, const QString &confirm_text, QWidget *parent);
static bool rich(const QString &prompt_text, QWidget *parent);

View File

@ -6,6 +6,8 @@ import sys
import threading
import traceback
from types import SimpleNamespace
from cereal import log
import cereal.messaging as messaging
import openpilot.system.sentry as sentry
@ -22,9 +24,8 @@ from openpilot.system.athena.registration import register, UNREGISTERED_DONGLE_I
from openpilot.common.swaglog import cloudlog, add_file_handler
from openpilot.system.version import get_build_metadata, terms_version, training_version
from openpilot.selfdrive.frogpilot.assets.model_manager import DEFAULT_MODEL, DEFAULT_MODEL_NAME
from openpilot.selfdrive.frogpilot.frogpilot_functions import convert_params, frogpilot_boot_functions, setup_frogpilot, uninstall_frogpilot
from openpilot.selfdrive.frogpilot.frogpilot_variables import frogpilot_default_params, get_frogpilot_toggles
from openpilot.selfdrive.frogpilot.frogpilot_variables import FrogPilotVariables, frogpilot_default_params, get_frogpilot_toggles
def manager_init() -> None:
@ -169,17 +170,14 @@ def manager_thread() -> None:
pm = messaging.PubMaster(['managerState'])
write_onroad_params(False, params)
ensure_running(managed_processes.values(), False, params=params, CP=sm['carParams'], not_run=ignore, classic_model=False)
ensure_running(managed_processes.values(), False, params=params, CP=sm['carParams'], not_run=ignore, classic_model=False, frogpilot_toggles=SimpleNamespace())
started_prev = False
# FrogPilot variables
FrogPilotVariables().update(False)
frogpilot_toggles = get_frogpilot_toggles(True)
classic_model = getattr(frogpilot_toggles, 'classic_model', False)
error_log = os.path.join(sentry.CRASHES_DIR, 'error.txt')
if os.path.isfile(error_log):
os.remove(error_log)
classic_model = frogpilot_toggles.classic_model
while True:
sm.update(1000)
@ -189,9 +187,6 @@ def manager_thread() -> None:
if started and not started_prev:
params.clear_all(ParamKeyType.CLEAR_ON_ONROAD_TRANSITION)
if os.path.isfile(error_log):
os.remove(error_log)
# FrogPilot variables
classic_model = frogpilot_toggles.classic_model
@ -205,7 +200,7 @@ def manager_thread() -> None:
started_prev = started
ensure_running(managed_processes.values(), started, params=params, CP=sm['carParams'], not_run=ignore, classic_model=classic_model)
ensure_running(managed_processes.values(), started, params=params, CP=sm['carParams'], not_run=ignore, classic_model=classic_model, frogpilot_toggles=frogpilot_toggles)
running = ' '.join("{}{}\u001b[0m".format("\u001b[32m" if p.proc.is_alive() else "\u001b[31m", p.name)
for p in managed_processes.values() if p.proc)

View File

@ -9,6 +9,7 @@ from abc import ABC, abstractmethod
from multiprocessing import Process
from setproctitle import setproctitle
from types import SimpleNamespace
from cereal import car, log
import cereal.messaging as messaging
@ -245,7 +246,7 @@ class DaemonProcess(ManagerProcess):
self.params = None
@staticmethod
def should_run(started, params, CP, classic_model):
def should_run(started, params, CP, classic_model, frogpilot_toggles):
return True
def prepare(self) -> None:
@ -281,13 +282,13 @@ class DaemonProcess(ManagerProcess):
def ensure_running(procs: ValuesView[ManagerProcess], started: bool, params=None, CP: car.CarParams=None,
not_run: list[str] | None=None, classic_model=False) -> list[ManagerProcess]:
not_run: list[str] | None=None, classic_model=False, frogpilot_toggles=SimpleNamespace()) -> list[ManagerProcess]:
if not_run is None:
not_run = []
running = []
for p in procs:
if p.enabled and p.name not in not_run and p.should_run(started, params, CP, classic_model):
if p.enabled and p.name not in not_run and p.should_run(started, params, CP, classic_model, frogpilot_toggles):
running.append(p)
else:
p.stop(block=False)

View File

@ -7,53 +7,51 @@ from openpilot.system.manager.process import PythonProcess, NativeProcess, Daemo
WEBCAM = os.getenv("USE_WEBCAM") is not None
def driverview(started: bool, params: Params, CP: car.CarParams, classic_model) -> bool:
def driverview(started: bool, params: Params, CP: car.CarParams, classic_model, frogpilot_toggles) -> bool:
return started or params.get_bool("IsDriverViewEnabled")
def notcar(started: bool, params: Params, CP: car.CarParams, classic_model) -> bool:
def notcar(started: bool, params: Params, CP: car.CarParams, classic_model, frogpilot_toggles) -> bool:
return started and CP.notCar
def iscar(started: bool, params: Params, CP: car.CarParams, classic_model) -> bool:
def iscar(started: bool, params: Params, CP: car.CarParams, classic_model, frogpilot_toggles) -> bool:
return started and not CP.notCar
def logging(started, params, CP: car.CarParams, classic_model) -> bool:
def logging(started, params, CP: car.CarParams, classic_model, frogpilot_toggles) -> bool:
run = (not CP.notCar) or not params.get_bool("DisableLogging")
return started and run
def ublox_available() -> bool:
return os.path.exists('/dev/ttyHS0') and not os.path.exists('/persist/comma/use-quectel-gps')
def ublox(started, params, CP: car.CarParams, classic_model) -> bool:
def ublox(started, params, CP: car.CarParams, classic_model, frogpilot_toggles) -> bool:
use_ublox = ublox_available()
if use_ublox != params.get_bool("UbloxAvailable"):
params.put_bool("UbloxAvailable", use_ublox)
return started and use_ublox
def qcomgps(started, params, CP: car.CarParams, classic_model) -> bool:
def qcomgps(started, params, CP: car.CarParams, classic_model, frogpilot_toggles) -> bool:
return started and not ublox_available()
def always_run(started, params, CP: car.CarParams, classic_model) -> bool:
def always_run(started, params, CP: car.CarParams, classic_model, frogpilot_toggles) -> bool:
return True
def only_onroad(started: bool, params, CP: car.CarParams, classic_model) -> bool:
def only_onroad(started: bool, params, CP: car.CarParams, classic_model, frogpilot_toggles) -> bool:
return started
def only_offroad(started, params, CP: car.CarParams, classic_model) -> bool:
def only_offroad(started, params, CP: car.CarParams, classic_model, frogpilot_toggles) -> bool:
return not started
# FrogPilot functions
def allow_logging(started, params, CP: car.CarParams, classic_model) -> bool:
allow_logging = not (params.get_bool("DeviceManagement") and params.get_bool("NoLogging"))
return allow_logging and logging(started, params, CP, classic_model)
def allow_logging(started, params, CP: car.CarParams, classic_model, frogpilot_toggles) -> bool:
return not getattr(frogpilot_toggles, 'no_logging', False) and logging(started, params, CP, classic_model, frogpilot_toggles)
def allow_uploads(started, params, CP: car.CarParams, classic_model) -> bool:
allow_uploads = not (params.get_bool("DeviceManagement") and params.get_bool("NoUploads") and not params.get_bool("DisableOnroadUploads"))
return allow_uploads
def allow_uploads(started, params, CP: car.CarParams, classic_model, frogpilot_toggles) -> bool:
return not getattr(frogpilot_toggles, 'no_uploads', False)
def run_classic_modeld(started, params, CP: car.CarParams, classic_model) -> bool:
def run_classic_modeld(started, params, CP: car.CarParams, classic_model, frogpilot_toggles) -> bool:
return started and classic_model
def run_new_modeld(started, params, CP: car.CarParams, classic_model) -> bool:
def run_new_modeld(started, params, CP: car.CarParams, classic_model, frogpilot_toggles) -> bool:
return started and not classic_model
procs = [

View File

@ -9,7 +9,7 @@ from sentry_sdk.integrations.threading import ThreadingIntegration
from openpilot.common.params import Params, ParamKeyType
from openpilot.system.athena.registration import is_registered_device
from openpilot.system.hardware import HARDWARE, PC
from openpilot.system.hardware import PC
from openpilot.common.swaglog import cloudlog
from openpilot.system.version import get_build_metadata, get_version
@ -87,7 +87,8 @@ def capture_fingerprint(candidate, params, blocked=False):
matched_params[label] = {k: int(v) if isinstance(v, float) and v.is_integer() else v for k, v in sorted(key_values.items())}
with sentry_sdk.configure_scope() as scope:
scope.fingerprint = [HARDWARE.get_serial()]
scope.fingerprint = [params.get("DongleId", encoding='utf-8')]
for label, key_values in matched_params.items():
scope.set_extra(label, "\n".join(f"{k}: {v}" for k, v in key_values.items()))
@ -158,6 +159,8 @@ def init(project: SentryProject) -> bool:
else:
env = short_branch
dongle_id = params.get("DongleId", encoding='utf-8')
integrations = []
if project == SentryProject.SELFDRIVE:
integrations.append(ThreadingIntegration(propagate_hub=True))
@ -170,7 +173,7 @@ def init(project: SentryProject) -> bool:
max_value_length=8192,
environment=env)
sentry_sdk.set_user({"id": HARDWARE.get_serial()})
sentry_sdk.set_user({"id": dongle_id})
sentry_sdk.set_tag("origin", build_metadata.openpilot.git_origin)
sentry_sdk.set_tag("branch", short_branch)
sentry_sdk.set_tag("commit", build_metadata.openpilot.git_commit)