Compare commits

...

19 Commits

Author SHA1 Message Date
Jason Wen
14bceeb172 rename 2024-09-29 14:02:09 -04:00
Jason Wen
124d1bb12f revert 2024-09-29 13:44:09 -04:00
Kumar
8ee80deb96 maybe>? 2024-09-28 15:01:41 -07:00
Jason Wen
d4b79ff36a Revert "temp: build tf"
This reverts commit 0570833ad3.
2024-09-28 13:38:58 -04:00
Jason Wen
7ea4096155 Revert "tf"
This reverts commit 5cda10e74a.
2024-09-28 13:38:58 -04:00
Jason Wen
5cda10e74a tf 2024-09-28 13:31:57 -04:00
Jason Wen
0570833ad3 temp: build tf 2024-09-28 13:31:48 -04:00
Jason Wen
bbbeb93cc2 Make sure it updates 2024-09-28 13:25:18 -04:00
Jason Wen
32ce8e58e9 Flipped 2024-09-28 13:08:28 -04:00
Jason Wen
0084010d55 get DMS version 2024-09-28 12:40:34 -04:00
Jason Wen
8f173083c2 gen7 model 2024-09-28 12:33:00 -04:00
Jason Wen
524a5f2f24 long planner: use temporalPose for v_model_error calibration 2024-09-28 11:31:30 -04:00
Harald Schäfer
44349a829a Safe exp in parsing (#33640)
(cherry picked from commit deb6b72091)
2024-09-28 11:21:41 -04:00
Harald Schäfer
8c04dcde59 Clip sigmoid overlfow (#33635)
* No more C sigmoid

* Clipping

* Need to cast to float

* Update ref

* Clip

* Model refg

(cherry picked from commit 251e2e9400)
2024-09-28 11:21:30 -04:00
ZwX1616
d7ec35a986 onnxmodel fp16_to_fp32: misc improvements (#33615)
(cherry picked from commit b2976631d2)
2024-09-28 11:20:57 -04:00
Kacper Rączy
e26a805476 Add modelExecutionTime to DrivingModelData (#33606)
* Add model execution time to DrivingModelData

* Update model replay ref commit

* Update ref commit again

* Ignore this field in model replay

* Back to original ref commit

* Bring back

---------

Co-authored-by: Comma Device <device@comma.ai>
(cherry picked from commit 48938098e0)
2024-09-28 11:19:39 -04:00
Mitchell Goff
51d862921b Add gas/brake press probs to ModelDataV2 (#33382)
* Add gas/brake press probs to ModelDataV2

* Updated model_replay_ref_commit
old-commit-hash: 40fb90a8a2

(cherry picked from commit 6bb9e72c64)
2024-09-28 11:18:30 -04:00
Jason Wen
8e8463a996 Tomb Raider 2024-09-28 10:02:23 -04:00
Jason Wen
306df5935a new infra 2024-09-28 09:19:19 -04:00
23 changed files with 153 additions and 61 deletions

View File

@@ -32,6 +32,8 @@ enum ModelGeneration {
three @3;
four @4;
five @5;
six @6;
seven @7;
}
struct ControlsStateSP @0x81c2f05a394cf4af {

View File

@@ -871,6 +871,7 @@ struct DrivingModelData {
frameId @0 :UInt32;
frameIdExtra @1 :UInt32;
frameDropPerc @6 :Float32;
modelExecutionTime @7 :Float32;
action @2 :ModelDataV2.Action;
@@ -1010,6 +1011,8 @@ struct ModelDataV2 {
brake3MetersPerSecondSquaredProbs @4 :List(Float32);
brake4MetersPerSecondSquaredProbs @5 :List(Float32);
brake5MetersPerSecondSquaredProbs @6 :List(Float32);
gasPressProbs @7 :List(Float32);
brakePressProbs @8 :List(Float32);
}
struct Pose {

View File

@@ -239,6 +239,7 @@ std::unordered_map<std::string, uint32_t> keys = {
{"DrivingModelGeneration", PERSISTENT},
{"DrivingModelMetadataText", PERSISTENT},
{"DrivingModelName", PERSISTENT},
{"DrivingModelSelectorVersion", CLEAR_ON_MANAGER_START},
{"DrivingModelText", PERSISTENT},
{"DrivingModelUrl", PERSISTENT},
{"DynamicExperimentalControl", PERSISTENT | BACKUP},

View File

@@ -255,8 +255,8 @@ class RadarD:
self.radar_state.radarErrors = list(radar_errors)
self.radar_state.carStateMonoTime = sm.logMonoTime['carState']
if len(sm['modelV2'].temporalPose.trans):
model_v_ego = sm['modelV2'].temporalPose.trans[0]
if len(sm['modelV2'].velocity.x):
model_v_ego = sm['modelV2'].velocity.x[0]
else:
model_v_ego = self.v_ego
leads_v3 = sm['modelV2'].leadsV3

View File

@@ -76,13 +76,14 @@ class Plan:
class Meta:
ENGAGED = slice(0, 1)
# next 2, 4, 6, 8, 10 seconds
GAS_DISENGAGE = slice(1, 36, 7)
BRAKE_DISENGAGE = slice(2, 36, 7)
STEER_OVERRIDE = slice(3, 36, 7)
HARD_BRAKE_3 = slice(4, 36, 7)
HARD_BRAKE_4 = slice(5, 36, 7)
HARD_BRAKE_5 = slice(6, 36, 7)
GAS_PRESS = slice(7, 36, 7)
GAS_DISENGAGE = slice(1, 31, 6)
BRAKE_DISENGAGE = slice(2, 31, 6)
STEER_OVERRIDE = slice(3, 31, 6)
HARD_BRAKE_3 = slice(4, 31, 6)
HARD_BRAKE_4 = slice(5, 31, 6)
HARD_BRAKE_5 = slice(6, 31, 6)
# next 0, 2, 4, 6, 8, 10 seconds
LEFT_BLINKER = slice(36, 48, 2)
RIGHT_BLINKER = slice(37, 48, 2)
GAS_PRESS = slice(31, 55, 4)
BRAKE_PRESS = slice(32, 55, 4)
LEFT_BLINKER = slice(33, 55, 4)
RIGHT_BLINKER = slice(34, 55, 4)

View File

@@ -1,9 +1,10 @@
from enum import IntFlag
import os
import os, sys
from cereal import custom
from openpilot.common.params import Params
DRIVING_MODEL_SELECTOR_VERSION = 6
SIMULATION = "SIMULATION" in os.environ
ModelGeneration = custom.ModelGeneration
@@ -33,6 +34,10 @@ class ModelCapabilities(IntFlag):
In V2, 'prev_desired_curv' (no plural) is used as the input for the same 'desired_curvature' output.
"""
PlanVelocity = 2 ** 5
ModelOutputSlicesV1 = 2 ** 6
class CustomModelMetadata:
def __init__(self, params=None, init_only=False) -> None:
@@ -45,13 +50,19 @@ class CustomModelMetadata:
self.capabilities: ModelCapabilities = self.get_model_capabilities()
self.valid: bool = self.params.get_bool("CustomDrivingModel") and not SIMULATION and \
self.capabilities != ModelCapabilities.Default
self.initialized = False
def read_model_generation_param(self) -> ModelGeneration:
return int(self.params.get('DrivingModelGeneration') or ModelGeneration.default)
def get_model_capabilities(self) -> ModelCapabilities:
"""Returns the model capabilities for a given generation."""
if self.generation == ModelGeneration.five:
if self.generation == ModelGeneration.seven:
return ModelCapabilities.DesiredCurvatureV2 | ModelCapabilities.PlanVelocity | \
ModelCapabilities.ModelOutputSlicesV1
elif self.generation == ModelGeneration.six:
return ModelCapabilities.DesiredCurvatureV2 | ModelCapabilities.PlanVelocity
elif self.generation == ModelGeneration.five:
return ModelCapabilities.DesiredCurvatureV2
elif self.generation == ModelGeneration.four:
return ModelCapabilities.DesiredCurvatureV2
@@ -64,3 +75,29 @@ class CustomModelMetadata:
else:
# Default model is meant to represent the capabilities of the prebuilt model
return ModelCapabilities.Default
def custom_meta(self):
if not self.initialized:
if self.capabilities & ModelCapabilities.ModelOutputSlicesV1:
class Meta:
ENGAGED = slice(0, 1)
# next 2, 4, 6, 8, 10 seconds
GAS_DISENGAGE = slice(1, 41, 8)
BRAKE_DISENGAGE = slice(2, 41, 8)
STEER_OVERRIDE = slice(3, 41, 8)
HARD_BRAKE_3 = slice(4, 41, 8)
HARD_BRAKE_4 = slice(5, 41, 8)
HARD_BRAKE_5 = slice(6, 41, 8)
GAS_PRESS = slice(7, 41, 8)
BRAKE_PRESS = slice(8, 41, 8)
# next 0, 2, 4, 6, 8, 10 seconds
LEFT_BLINKER = slice(41, 53, 2)
RIGHT_BLINKER = slice(42, 53, 2)
module = 'openpilot.selfdrive.modeld.constants'
if module in sys.modules:
sys.modules[module].Meta = Meta
else:
raise ImportError(f"The module '{module}' is not imported yet or does not exist.")
self.initialized = True

View File

@@ -14,7 +14,7 @@ from openpilot.common.swaglog import cloudlog
from openpilot.common.params import Params
from openpilot.common.realtime import set_realtime_priority
from openpilot.selfdrive.modeld.runners import ModelRunner, Runtime
from openpilot.selfdrive.modeld.models.commonmodel_pyx import sigmoid
from openpilot.selfdrive.modeld.parse_model_outputs import sigmoid
CALIB_LEN = 3
REG_SCALE = 0.25
@@ -88,15 +88,15 @@ def fill_driver_state(msg, ds_result: DriverStateResult):
msg.faceOrientationStd = [math.exp(x) for x in ds_result.face_orientation_std]
msg.facePosition = [x * REG_SCALE for x in ds_result.face_position[:2]]
msg.facePositionStd = [math.exp(x) for x in ds_result.face_position_std[:2]]
msg.faceProb = sigmoid(ds_result.face_prob)
msg.leftEyeProb = sigmoid(ds_result.left_eye_prob)
msg.rightEyeProb = sigmoid(ds_result.right_eye_prob)
msg.leftBlinkProb = sigmoid(ds_result.left_blink_prob)
msg.rightBlinkProb = sigmoid(ds_result.right_blink_prob)
msg.sunglassesProb = sigmoid(ds_result.sunglasses_prob)
msg.occludedProb = sigmoid(ds_result.occluded_prob)
msg.readyProb = [sigmoid(x) for x in ds_result.ready_prob]
msg.notReadyProb = [sigmoid(x) for x in ds_result.not_ready_prob]
msg.faceProb = float(sigmoid(ds_result.face_prob))
msg.leftEyeProb = float(sigmoid(ds_result.left_eye_prob))
msg.rightEyeProb = float(sigmoid(ds_result.right_eye_prob))
msg.leftBlinkProb = float(sigmoid(ds_result.left_blink_prob))
msg.rightBlinkProb = float(sigmoid(ds_result.right_blink_prob))
msg.sunglassesProb = float(sigmoid(ds_result.sunglasses_prob))
msg.occludedProb = float(sigmoid(ds_result.occluded_prob))
msg.readyProb = [float(sigmoid(x)) for x in ds_result.ready_prob]
msg.notReadyProb = [float(sigmoid(x)) for x in ds_result.not_ready_prob]
def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts: int, execution_time: float, dsp_execution_time: float):
model_result = ctypes.cast(model_output.ctypes.data, ctypes.POINTER(DMonitoringModelResult)).contents
@@ -105,8 +105,8 @@ def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts:
ds.frameId = frame_id
ds.modelExecutionTime = execution_time
ds.dspExecutionTime = dsp_execution_time
ds.poorVisionProb = sigmoid(model_result.poor_vision_prob)
ds.wheelOnRightProb = sigmoid(model_result.wheel_on_right_prob)
ds.poorVisionProb = float(sigmoid(model_result.poor_vision_prob))
ds.wheelOnRightProb = float(sigmoid(model_result.wheel_on_right_prob))
ds.rawPredictions = model_output.tobytes() if SEND_RAW_PRED else b''
fill_driver_state(ds.leftDriverData, model_result.driver_state_lhd)
fill_driver_state(ds.rightDriverData, model_result.driver_state_rhd)

View File

@@ -3,7 +3,7 @@ import capnp
import numpy as np
from cereal import log
from openpilot.selfdrive.modeld.constants import ModelConstants, Plan, Meta
from openpilot.selfdrive.modeld.custom_model_metadata import ModelCapabilities
from openpilot.selfdrive.modeld.custom_model_metadata import CustomModelMetadata, ModelCapabilities
SEND_RAW_PRED = os.getenv('SEND_RAW_PRED')
@@ -55,7 +55,8 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D
vipc_frame_id: int, vipc_frame_id_extra: int, frame_id: int, frame_drop: float,
timestamp_eof: int, timestamp_llk: int, model_execution_time: float,
nav_enabled: bool, valid: bool,
custom_model_valid: bool, custom_model_capabilities: ModelCapabilities) -> None:
custom_model: CustomModelMetadata) -> None:
custom_model.custom_meta()
frame_age = frame_id - vipc_frame_id if frame_id > vipc_frame_id else 0
frame_drop_perc = frame_drop * 100
extended_msg.valid = valid
@@ -66,9 +67,10 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D
driving_model_data.frameId = vipc_frame_id
driving_model_data.frameIdExtra = vipc_frame_id_extra
driving_model_data.frameDropPerc = frame_drop_perc
driving_model_data.modelExecutionTime = model_execution_time
action = driving_model_data.action
model_use_lateral_planner = custom_model_valid and custom_model_capabilities & ModelCapabilities.LateralPlannerSolution
model_use_lateral_planner = custom_model.valid and custom_model.capabilities & ModelCapabilities.LateralPlannerSolution
if not model_use_lateral_planner:
action.desiredCurvature = float(net_output_data['desired_curvature'][0,0])
@@ -78,7 +80,7 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D
modelV2.frameAge = frame_age
modelV2.frameDropPerc = frame_drop_perc
modelV2.timestampEof = timestamp_eof
model_use_nav = custom_model_valid and custom_model_capabilities & ModelCapabilities.NoO
model_use_nav = custom_model.valid and custom_model.capabilities & ModelCapabilities.NoO
if model_use_nav:
modelV2.locationMonoTimeDEPRECATED = timestamp_llk
modelV2.modelExecutionTime = model_execution_time
@@ -172,6 +174,8 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D
disengage_predictions.brake3MetersPerSecondSquaredProbs = net_output_data['meta'][0,Meta.HARD_BRAKE_3].tolist()
disengage_predictions.brake4MetersPerSecondSquaredProbs = net_output_data['meta'][0,Meta.HARD_BRAKE_4].tolist()
disengage_predictions.brake5MetersPerSecondSquaredProbs = net_output_data['meta'][0,Meta.HARD_BRAKE_5].tolist()
disengage_predictions.gasPressProbs = net_output_data['meta'][0,Meta.GAS_PRESS].tolist()
disengage_predictions.brakePressProbs = net_output_data['meta'][0,Meta.BRAKE_PRESS].tolist()
publish_state.prev_brake_5ms2_probs[:-1] = publish_state.prev_brake_5ms2_probs[1:]
publish_state.prev_brake_5ms2_probs[-1] = net_output_data['meta'][0,Meta.HARD_BRAKE_5][0]
@@ -183,10 +187,22 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D
# temporal pose
temporal_pose = modelV2.temporalPose
temporal_pose.trans = net_output_data['sim_pose'][0,:3].tolist()
temporal_pose.transStd = net_output_data['sim_pose_stds'][0,:3].tolist()
temporal_pose.rot = net_output_data['sim_pose'][0,3:].tolist()
temporal_pose.rotStd = net_output_data['sim_pose_stds'][0,3:].tolist()
if custom_model.valid:
if custom_model.capabilities & ModelCapabilities.PlanVelocity:
temporal_pose.trans = net_output_data['plan'][0,0,Plan.VELOCITY].tolist()
temporal_pose.transStd = net_output_data['plan_stds'][0,0,Plan.VELOCITY].tolist()
temporal_pose.rot = net_output_data['plan'][0,0,Plan.ORIENTATION_RATE].tolist()
temporal_pose.rotStd = net_output_data['plan_stds'][0,0,Plan.ORIENTATION_RATE].tolist()
else:
temporal_pose.trans = net_output_data['sim_pose'][0,:3].tolist()
temporal_pose.transStd = net_output_data['sim_pose_stds'][0,:3].tolist()
temporal_pose.rot = net_output_data['sim_pose'][0,3:].tolist()
temporal_pose.rotStd = net_output_data['sim_pose_stds'][0,3:].tolist()
else:
temporal_pose.trans = net_output_data['plan'][0,0,Plan.VELOCITY].tolist()
temporal_pose.transStd = net_output_data['plan_stds'][0,0,Plan.VELOCITY].tolist()
temporal_pose.rot = net_output_data['plan'][0,0,Plan.ORIENTATION_RATE].tolist()
temporal_pose.rotStd = net_output_data['plan_stds'][0,0,Plan.ORIENTATION_RATE].tolist()
# confidence
if vipc_frame_id % (2*ModelConstants.MODEL_FREQ) == 0:

View File

@@ -377,7 +377,7 @@ def main(demo=False):
posenet_send = messaging.new_message('cameraOdometry')
fill_model_msg(drivingdata_send, modelv2_send, model_output, publish_state, meta_main.frame_id, meta_extra.frame_id, frame_id,
frame_drop_ratio, meta_main.timestamp_eof, timestamp_llk, model_execution_time, nav_enabled, live_calib_seen,
custom_model_metadata.valid, custom_model_metadata.capabilities)
custom_model_metadata)
if not (custom_model_metadata.valid and custom_model_metadata.capabilities & ModelCapabilities.LateralPlannerSolution):
desire_state = modelv2_send.modelV2.meta.desireState

View File

@@ -47,8 +47,4 @@ ModelFrame::~ModelFrame() {
CL_CHECK(clReleaseMemObject(u_cl));
CL_CHECK(clReleaseMemObject(y_cl));
CL_CHECK(clReleaseCommandQueue(q));
}
float sigmoid(float input) {
return 1 / (1 + expf(-input));
}
}

View File

@@ -16,8 +16,6 @@
#include "selfdrive/modeld/transforms/loadyuv.h"
#include "selfdrive/modeld/transforms/transform.h"
float sigmoid(float input);
class ModelFrame {
public:
ModelFrame(cl_device_id device_id, cl_context context);

View File

@@ -12,8 +12,6 @@ cdef extern from "common/clutil.h":
cl_context cl_create_context(cl_device_id)
cdef extern from "selfdrive/modeld/models/commonmodel.h":
float sigmoid(float)
cppclass ModelFrame:
int buf_size
ModelFrame(cl_device_id, cl_context)

View File

@@ -8,10 +8,8 @@ from libc.string cimport memcpy
from msgq.visionipc.visionipc cimport cl_mem
from msgq.visionipc.visionipc_pyx cimport VisionBuf, CLContext as BaseCLContext
from .commonmodel cimport CL_DEVICE_TYPE_DEFAULT, cl_get_device_id, cl_create_context
from .commonmodel cimport mat3, sigmoid as cppSigmoid, ModelFrame as cppModelFrame
from .commonmodel cimport mat3, ModelFrame as cppModelFrame
def sigmoid(x):
return cppSigmoid(x)
cdef class CLContext(BaseCLContext):
def __cinit__(self):

Binary file not shown.

View File

@@ -1,15 +1,19 @@
import numpy as np
from openpilot.selfdrive.modeld.constants import ModelConstants
def safe_exp(x, out=None):
# -11 is around 10**14, more causes float16 overflow
return np.exp(np.clip(x, -np.inf, 11), out=out)
def sigmoid(x):
return 1. / (1. + np.exp(-x))
return 1. / (1. + safe_exp(-x))
def softmax(x, axis=-1):
x -= np.max(x, axis=axis, keepdims=True)
if x.dtype == np.float32 or x.dtype == np.float64:
np.exp(x, out=x)
safe_exp(x, out=x)
else:
x = np.exp(x)
x = safe_exp(x)
x /= np.sum(x, axis=axis, keepdims=True)
return x
@@ -44,7 +48,7 @@ class Parser:
n_values = (raw.shape[2] - out_N)//2
pred_mu = raw[:,:,:n_values]
pred_std = np.exp(raw[:,:,n_values: 2*n_values])
pred_std = safe_exp(raw[:,:,n_values: 2*n_values])
if in_N > 1:
weights = np.zeros((raw.shape[0], in_N, out_N), dtype=raw.dtype)
@@ -87,7 +91,8 @@ class Parser:
self.parse_mdn('road_edges', outs, in_N=0, out_N=0, out_shape=(ModelConstants.NUM_ROAD_EDGES,ModelConstants.IDX_N,ModelConstants.LANE_LINES_WIDTH))
self.parse_mdn('pose', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,))
self.parse_mdn('road_transform', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,))
self.parse_mdn('sim_pose', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,))
if 'sim_pose' in outs:
self.parse_mdn('sim_pose', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,))
self.parse_mdn('wide_from_device_euler', outs, in_N=0, out_N=0, out_shape=(ModelConstants.WIDE_FROM_DEVICE_WIDTH,))
self.parse_mdn('lead', outs, in_N=ModelConstants.LEAD_MHP_N, out_N=ModelConstants.LEAD_MHP_SELECTION,
out_shape=(ModelConstants.LEAD_TRAJ_LEN,ModelConstants.LEAD_WIDTH))

View File

@@ -14,8 +14,12 @@ def attributeproto_fp16_to_fp32(attr):
attr.data_type = 1
attr.raw_data = float32_list.astype(np.float32).tobytes()
def convert_fp16_to_fp32(path):
model = onnx.load(path)
def convert_fp16_to_fp32(onnx_path_or_bytes):
if isinstance(onnx_path_or_bytes, bytes):
model = onnx.load_from_string(onnx_path_or_bytes)
elif isinstance(onnx_path_or_bytes, str):
model = onnx.load(onnx_path_or_bytes)
for i in model.graph.initializer:
if i.data_type == 10:
attributeproto_fp16_to_fp32(i)
@@ -23,6 +27,8 @@ def convert_fp16_to_fp32(path):
if i.type.tensor_type.elem_type == 10:
i.type.tensor_type.elem_type = 1
for i in model.graph.node:
if i.op_type == 'Cast' and i.attribute[0].i == 10:
i.attribute[0].i = 1
for a in i.attribute:
if hasattr(a, 't'):
if a.t.data_type == 10:

View File

@@ -130,6 +130,7 @@ if __name__ == "__main__":
ignore = [
'logMonoTime',
'drivingModelData.frameDropPerc',
'drivingModelData.modelExecutionTime',
'modelV2.frameDropPerc',
'modelV2.modelExecutionTime',
'driverStateV2.modelExecutionTime',

View File

@@ -1 +1 @@
01e8432830805165527d1dbadd5f009d19430b39
9d4d653d8cc361fe2ba53f74fd8fcfe1f1d559ed

View File

@@ -566,7 +566,7 @@ CONFIGS = [
proc_name="modeld",
pubs=["deviceState", "roadCameraState", "wideRoadCameraState", "liveCalibration", "driverMonitoringState"],
subs=["modelV2", "drivingModelData", "cameraOdometry"],
ignore=["logMonoTime", "modelV2.frameDropPerc", "modelV2.modelExecutionTime"],
ignore=["logMonoTime", "modelV2.frameDropPerc", "modelV2.modelExecutionTime", "drivingModelData.frameDropPerc", "drivingModelData.modelExecutionTime"],
should_recv_callback=ModeldCameraSyncRcvCallback(),
tolerance=NUMPY_TOLERANCE,
processing_time=0.020,

View File

@@ -177,5 +177,18 @@ std::vector<Model> ModelsFetcher::getModelsFromURL(const QString&url) {
}
std::vector<Model> ModelsFetcher::getModelsFromURL() {
return getModelsFromURL("https://docs.sunnypilot.ai/models_v5.json");
return getModelsFromURL("https://docs.sunnypilot.ai/driving_models.json");
}
std::vector<Model> ModelsFetcher::getCompatibleModels(const QString &selector_version) {
std::vector<Model> allModels = getModelsFromURL();
std::vector<Model> compatibleModels;
for (const auto &model : allModels) {
if (model.isCompatible(selector_version)) {
compatibleModels.push_back(model);
}
}
return compatibleModels;
}

View File

@@ -34,6 +34,7 @@ Last updated: July 29, 2024
#include <QDir>
#include <QJsonObject>
#include <QTimer>
#include <QVersionNumber>
#include "common/swaglog.h"
#include "common/util.h"
@@ -86,6 +87,8 @@ public:
index = json["index"].toString();
environment = json["environment"].toString();
generation = json["generation"].toString();
minDrivingModelSelectorVersion = json["minimum_selector_version"].toString();
}
// Method to convert model back to QJsonObject, if needed
@@ -117,6 +120,9 @@ public:
json["index"] = index;
json["environment"] = environment;
json["generation"] = generation;
json["minimum_selector_version"] = minDrivingModelSelectorVersion;
return json;
}
@@ -134,6 +140,13 @@ public:
QString index;
QString environment;
QString generation;
QString minDrivingModelSelectorVersion;
bool isCompatible(const QString &selector_version) const {
return QVersionNumber::fromString(selector_version) >=
QVersionNumber::fromString(minDrivingModelSelectorVersion);
}
};
class ModelsFetcher : public QObject {
@@ -145,6 +158,7 @@ public:
static std::vector<Model> getModelsFromURL(const QUrl&url);
static std::vector<Model> getModelsFromURL(const QString&url);
static std::vector<Model> getModelsFromURL();
static std::vector<Model> getCompatibleModels(const QString &selector_version);
signals:
void downloadProgress(double percentage);

View File

@@ -210,12 +210,13 @@ void SoftwarePanelSP::handleCurrentModelLblBtnClicked() {
checkNetwork();
const auto currentModelName = QString::fromStdString(params.get("DrivingModelName"));
const bool is_release_sp = params.getBool("IsReleaseSPBranch");
const auto models = ModelsFetcher::getModelsFromURL();
const QString selector_version = QString::fromStdString(params.get("DrivingModelSelectorVersion"));
const auto compatible_models = ModelsFetcher::getCompatibleModels(selector_version);
QMap<QString, QString> index_to_model;
// Collecting indices with display names
for (const auto &model : models) {
for (const auto &model : compatible_models) {
if ((is_release_sp && model.environment == "release") || !is_release_sp) {
index_to_model.insert(model.index, model.displayName);
}
@@ -243,7 +244,7 @@ void SoftwarePanelSP::handleCurrentModelLblBtnClicked() {
}
// Finding and setting the selected model
for (auto &model : models) {
for (auto &model : compatible_models) {
if (model.displayName == selectedModelName) {
selectedModelToDownload = model;
selectedNavModelToDownload = model;

View File

@@ -11,6 +11,7 @@ import openpilot.system.sentry as sentry
from openpilot.common.api.sunnylink import UNREGISTERED_SUNNYLINK_DONGLE_ID
from openpilot.common.params import Params, ParamKeyType
from openpilot.common.text_window import TextWindow
from openpilot.selfdrive.modeld.custom_model_metadata import DRIVING_MODEL_SELECTOR_VERSION
from openpilot.system.hardware import HARDWARE, PC
from openpilot.system.manager.helpers import unblock_stdout, write_onroad_params, save_bootlog
from openpilot.system.manager.mapd_installer import VERSION
@@ -64,6 +65,7 @@ def manager_init() -> None:
("DisableOnroadUploads", "0"),
("DisengageLateralOnBrake", "0"),
("DrivingModelGeneration", "0"),
("DrivingModelSelectorVersion", str(DRIVING_MODEL_SELECTOR_VERSION)),
("DynamicLaneProfile", "1"),
("DynamicPersonality", "0"),
("EnableMads", "1"),