From 66bc246210b4471e0a5fa3ab792c4d9fe0316406 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 10 Jun 2022 15:23:42 -0700 Subject: [PATCH 001/302] count events: add simple camera debugging --- selfdrive/debug/count_events.py | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/selfdrive/debug/count_events.py b/selfdrive/debug/count_events.py index 8b32ce9d21..c3870e0f9e 100755 --- a/selfdrive/debug/count_events.py +++ b/selfdrive/debug/count_events.py @@ -4,6 +4,7 @@ from collections import Counter from pprint import pprint from tqdm import tqdm +from cereal.services import service_list from tools.lib.route import Route from tools.lib.logreader import LogReader @@ -13,6 +14,9 @@ if __name__ == "__main__": cnt_valid: Counter = Counter() cnt_events: Counter = Counter() + cams = [s for s in service_list if s.endswith('CameraState')] + cnt_cameras = dict.fromkeys(cams, 0) + for q in tqdm(r.qlog_paths()): if q is None: continue @@ -21,12 +25,21 @@ if __name__ == "__main__": if msg.which() == 'carEvents': for e in msg.carEvents: cnt_events[e.name] += 1 + elif msg.which() in cams: + cnt_cameras[msg.which()] += 1 + if not msg.valid: cnt_valid[msg.which()] += 1 + print("Events") pprint(cnt_events) - print("\n\n") + print("\n") print("Not valid") pprint(cnt_valid) + + print("\n") + print("Cameras") + for k, v in cnt_cameras.items(): + print(" ", k.ljust(20), v) From c646eeee0ac54925db5afc51b95c5d869d6dba68 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Fri, 10 Jun 2022 16:16:46 -0700 Subject: [PATCH 002/302] Revert fullframe DM model (#24812) * Revert "fullframe DM: flip RHD yaw to use matching thresholds" This reverts commit 2ac693100359d9df34d5b2b450a0058f2dd6b7c4. * Revert "fullframe DM model (#24762)" This reverts commit d6c07a6b158595c1ab10256dc6eee4fbdf902379. * revert cereal --- cereal | 2 +- common/modeldata.h | 6 + selfdrive/camerad/cameras/camera_common.cc | 2 +- selfdrive/camerad/cameras/camera_qcom2.cc | 2 +- selfdrive/hardware/tici/test_power_draw.py | 2 +- selfdrive/modeld/dmonitoringmodeld.cc | 6 +- selfdrive/modeld/models/dmonitoring.cc | 234 ++++++++++++------ selfdrive/modeld/models/dmonitoring.h | 33 +-- .../modeld/models/dmonitoring_model.current | 4 +- .../modeld/models/dmonitoring_model.onnx | 4 +- .../modeld/models/dmonitoring_model_q.dlc | 4 +- selfdrive/modeld/runners/onnx_runner.py | 21 +- selfdrive/modeld/runners/onnxmodel.cc | 6 +- selfdrive/modeld/runners/onnxmodel.h | 3 +- selfdrive/modeld/runners/snpemodel.cc | 12 +- selfdrive/modeld/runners/snpemodel.h | 3 +- selfdrive/monitoring/dmonitoringd.py | 7 +- selfdrive/monitoring/driver_monitor.py | 90 ++++--- selfdrive/monitoring/test_monitoring.py | 24 +- selfdrive/test/process_replay/model_replay.py | 8 +- .../process_replay/model_replay_ref_commit | 2 +- .../test/process_replay/process_replay.py | 2 +- selfdrive/test/test_onroad.py | 6 +- selfdrive/ui/qt/offroad/driverview.cc | 43 ++-- selfdrive/ui/qt/widgets/cameraview.cc | 9 +- 25 files changed, 308 insertions(+), 227 deletions(-) diff --git a/cereal b/cereal index 96cbed052a..e9d3597d23 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 96cbed052ab1d69ea15da94dc2b882d59a786347 +Subproject commit e9d3597d23311a3e33a2def74ceec839e5ff4bf5 diff --git a/common/modeldata.h b/common/modeldata.h index 410a69ea65..06d9398031 100644 --- a/common/modeldata.h +++ b/common/modeldata.h @@ -24,6 +24,12 @@ constexpr auto T_IDXS_FLOAT = build_idxs(10.0); constexpr auto X_IDXS = build_idxs(192.0); constexpr auto X_IDXS_FLOAT = build_idxs(192.0); +namespace tici_dm_crop { + const int x_offset = -72; + const int y_offset = -144; + const int width = 954; +}; + const mat3 fcam_intrinsic_matrix = (mat3){{2648.0, 0.0, 1928.0 / 2, 0.0, 2648.0, 1208.0 / 2, 0.0, 0.0, 1.0}}; diff --git a/selfdrive/camerad/cameras/camera_common.cc b/selfdrive/camerad/cameras/camera_common.cc index 21e225d538..049324f085 100644 --- a/selfdrive/camerad/cameras/camera_common.cc +++ b/selfdrive/camerad/cameras/camera_common.cc @@ -239,7 +239,7 @@ static kj::Array yuv420_to_jpeg(const CameraBuf *b, int thumbnail_w int in_stride = b->cur_yuv_buf->stride; // make the buffer big enough. jpeg_write_raw_data requires 16-pixels aligned height to be used. - std::unique_ptr buf(new uint8_t[(thumbnail_width * ((thumbnail_height + 15) & ~15) * 3) / 2]); + std::unique_ptr buf(new uint8_t[(thumbnail_width * ((thumbnail_height + 15) & ~15) * 3) / 2]); uint8_t *y_plane = buf.get(); uint8_t *u_plane = y_plane + thumbnail_width * thumbnail_height; uint8_t *v_plane = u_plane + (thumbnail_width * thumbnail_height) / 4; diff --git a/selfdrive/camerad/cameras/camera_qcom2.cc b/selfdrive/camerad/cameras/camera_qcom2.cc index b949dfb80f..d43beb0921 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.cc +++ b/selfdrive/camerad/cameras/camera_qcom2.cc @@ -837,7 +837,7 @@ void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_i s->road_cam.camera_init(s, v, CAMERA_ID_AR0231, 1, 20, device_id, ctx, VISION_STREAM_RGB_ROAD, VISION_STREAM_ROAD, !env_disable_road); s->wide_road_cam.camera_init(s, v, CAMERA_ID_AR0231, 0, 20, device_id, ctx, VISION_STREAM_RGB_WIDE_ROAD, VISION_STREAM_WIDE_ROAD, !env_disable_wide_road); - s->sm = new SubMaster({"driverStateV2"}); + s->sm = new SubMaster({"driverState"}); s->pm = new PubMaster({"roadCameraState", "driverCameraState", "wideRoadCameraState", "thumbnail"}); } diff --git a/selfdrive/hardware/tici/test_power_draw.py b/selfdrive/hardware/tici/test_power_draw.py index 5eb84514e5..ab2d691a09 100755 --- a/selfdrive/hardware/tici/test_power_draw.py +++ b/selfdrive/hardware/tici/test_power_draw.py @@ -21,7 +21,7 @@ class Proc: PROCS = [ Proc('camerad', 2.15), Proc('modeld', 1.0), - Proc('dmonitoringmodeld', 0.35), + Proc('dmonitoringmodeld', 0.25), Proc('encoderd', 0.23), ] diff --git a/selfdrive/modeld/dmonitoringmodeld.cc b/selfdrive/modeld/dmonitoringmodeld.cc index cde13a9bee..68c49572e6 100644 --- a/selfdrive/modeld/dmonitoringmodeld.cc +++ b/selfdrive/modeld/dmonitoringmodeld.cc @@ -12,7 +12,7 @@ ExitHandler do_exit; void run_model(DMonitoringModelState &model, VisionIpcClient &vipc_client) { - PubMaster pm({"driverStateV2"}); + PubMaster pm({"driverState"}); SubMaster sm({"liveCalibration"}); float calib[CALIB_LEN] = {0}; double last = 0; @@ -31,11 +31,11 @@ void run_model(DMonitoringModelState &model, VisionIpcClient &vipc_client) { } double t1 = millis_since_boot(); - DMonitoringModelResult model_res = dmonitoring_eval_frame(&model, buf->addr, buf->width, buf->height, buf->stride, buf->uv_offset, calib); + DMonitoringResult res = dmonitoring_eval_frame(&model, buf->addr, buf->width, buf->height, buf->stride, buf->uv_offset, calib); double t2 = millis_since_boot(); // send dm packet - dmonitoring_publish(pm, extra.frame_id, model_res, (t2 - t1) / 1000.0, model.output); + dmonitoring_publish(pm, extra.frame_id, res, (t2 - t1) / 1000.0, model.output); //printf("dmonitoring process: %.2fms, from last %.2fms\n", t2 - t1, t1 - last); last = t1; diff --git a/selfdrive/modeld/models/dmonitoring.cc b/selfdrive/modeld/models/dmonitoring.cc index 20294c3f3c..e134ad3a5a 100644 --- a/selfdrive/modeld/models/dmonitoring.cc +++ b/selfdrive/modeld/models/dmonitoring.cc @@ -10,8 +10,8 @@ #include "selfdrive/modeld/models/dmonitoring.h" -constexpr int MODEL_WIDTH = 1440; -constexpr int MODEL_HEIGHT = 960; +constexpr int MODEL_WIDTH = 320; +constexpr int MODEL_HEIGHT = 640; template static inline T *get_buffer(std::vector &buf, const size_t size) { @@ -19,115 +19,199 @@ static inline T *get_buffer(std::vector &buf, const size_t size) { return buf.data(); } +static inline void init_yuv_buf(std::vector &buf, const int width, int height) { + uint8_t *y = get_buffer(buf, width * height * 3 / 2); + uint8_t *u = y + width * height; + uint8_t *v = u + (width / 2) * (height / 2); + + // needed on comma two to make the padded border black + // equivalent to RGB(0,0,0) in YUV space + memset(y, 16, width * height); + memset(u, 128, (width / 2) * (height / 2)); + memset(v, 128, (width / 2) * (height / 2)); +} + void dmonitoring_init(DMonitoringModelState* s) { s->is_rhd = Params().getBool("IsRHD"); + for (int x = 0; x < std::size(s->tensor); ++x) { + s->tensor[x] = (x - 128.f) * 0.0078125f; + } + init_yuv_buf(s->resized_buf, MODEL_WIDTH, MODEL_HEIGHT); #ifdef USE_ONNX_MODEL - s->m = new ONNXModel("models/dmonitoring_model.onnx", &s->output[0], OUTPUT_SIZE, USE_DSP_RUNTIME, false, true); + s->m = new ONNXModel("models/dmonitoring_model.onnx", &s->output[0], OUTPUT_SIZE, USE_DSP_RUNTIME); #else - s->m = new SNPEModel("models/dmonitoring_model_q.dlc", &s->output[0], OUTPUT_SIZE, USE_DSP_RUNTIME, false, true); + s->m = new SNPEModel("models/dmonitoring_model_q.dlc", &s->output[0], OUTPUT_SIZE, USE_DSP_RUNTIME); #endif s->m->addCalib(s->calib, CALIB_LEN); } -void parse_driver_data(DriverStateResult &ds_res, const DMonitoringModelState* s, int out_idx_offset) { - for (int i = 0; i < 3; ++i) { - ds_res.face_orientation[i] = s->output[out_idx_offset+i] * REG_SCALE; - ds_res.face_orientation_std[i] = exp(s->output[out_idx_offset+6+i]); - } - for (int i = 0; i < 2; ++i) { - ds_res.face_position[i] = s->output[out_idx_offset+3+i] * REG_SCALE; - ds_res.face_position_std[i] = exp(s->output[out_idx_offset+9+i]); - } - for (int i = 0; i < 4; ++i) { - ds_res.ready_prob[i] = sigmoid(s->output[out_idx_offset+35+i]); - } - for (int i = 0; i < 2; ++i) { - ds_res.not_ready_prob[i] = sigmoid(s->output[out_idx_offset+39+i]); - } - ds_res.face_prob = sigmoid(s->output[out_idx_offset+12]); - ds_res.left_eye_prob = sigmoid(s->output[out_idx_offset+21]); - ds_res.right_eye_prob = sigmoid(s->output[out_idx_offset+30]); - ds_res.left_blink_prob = sigmoid(s->output[out_idx_offset+31]); - ds_res.right_blink_prob = sigmoid(s->output[out_idx_offset+32]); - ds_res.sunglasses_prob = sigmoid(s->output[out_idx_offset+33]); - ds_res.occluded_prob = sigmoid(s->output[out_idx_offset+34]); +static inline auto get_yuv_buf(std::vector &buf, const int width, int height) { + uint8_t *y = get_buffer(buf, width * height * 3 / 2); + uint8_t *u = y + width * height; + uint8_t *v = u + (width /2) * (height / 2); + return std::make_tuple(y, u, v); } -void fill_driver_data(cereal::DriverStateV2::DriverData::Builder ddata, const DriverStateResult &ds_res) { - ddata.setFaceOrientation(ds_res.face_orientation); - ddata.setFaceOrientationStd(ds_res.face_orientation_std); - ddata.setFacePosition(ds_res.face_position); - ddata.setFacePositionStd(ds_res.face_position_std); - ddata.setFaceProb(ds_res.face_prob); - ddata.setLeftEyeProb(ds_res.left_eye_prob); - ddata.setRightEyeProb(ds_res.right_eye_prob); - ddata.setLeftBlinkProb(ds_res.left_blink_prob); - ddata.setRightBlinkProb(ds_res.right_blink_prob); - ddata.setSunglassesProb(ds_res.sunglasses_prob); - ddata.setOccludedProb(ds_res.occluded_prob); - ddata.setReadyProb(ds_res.ready_prob); - ddata.setNotReadyProb(ds_res.not_ready_prob); +struct Rect {int x, y, w, h;}; +void crop_nv12_to_yuv(uint8_t *raw, int stride, int uv_offset, uint8_t *y, uint8_t *u, uint8_t *v, const Rect &rect) { + uint8_t *raw_y = raw; + uint8_t *raw_uv = raw_y + uv_offset; + for (int r = 0; r < rect.h / 2; r++) { + memcpy(y + 2 * r * rect.w, raw_y + (2 * r + rect.y) * stride + rect.x, rect.w); + memcpy(y + (2 * r + 1) * rect.w, raw_y + (2 * r + rect.y + 1) * stride + rect.x, rect.w); + for (int h = 0; h < rect.w / 2; h++) { + u[r * rect.w/2 + h] = raw_uv[(r + (rect.y/2)) * stride + (rect.x/2 + h)*2]; + v[r * rect.w/2 + h] = raw_uv[(r + (rect.y/2)) * stride + (rect.x/2 + h)*2 + 1]; + } + } } -DMonitoringModelResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_buf, int width, int height, int stride, int uv_offset, float *calib) { - int v_off = height - MODEL_HEIGHT; - int h_off = (width - MODEL_WIDTH) / 2; - int yuv_buf_len = MODEL_WIDTH * MODEL_HEIGHT; - - uint8_t *raw_buf = (uint8_t *) stream_buf; - // vertical crop free - uint8_t *raw_y_start = raw_buf + stride * v_off; +DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_buf, int width, int height, int stride, int uv_offset, float *calib) { + const int cropped_height = tici_dm_crop::width / 1.33; + Rect crop_rect = {width / 2 - tici_dm_crop::width / 2 + tici_dm_crop::x_offset, + height / 2 - cropped_height / 2 + tici_dm_crop::y_offset, + cropped_height / 2, + cropped_height}; + if (!s->is_rhd) { + crop_rect.x += tici_dm_crop::width - crop_rect.w; + } - uint8_t *net_input_buf = get_buffer(s->net_input_buf, yuv_buf_len); + int resized_width = MODEL_WIDTH; + int resized_height = MODEL_HEIGHT; + + auto [cropped_y, cropped_u, cropped_v] = get_yuv_buf(s->cropped_buf, crop_rect.w, crop_rect.h); + if (!s->is_rhd) { + crop_nv12_to_yuv((uint8_t *)stream_buf, stride, uv_offset, cropped_y, cropped_u, cropped_v, crop_rect); + } else { + auto [mirror_y, mirror_u, mirror_v] = get_yuv_buf(s->premirror_cropped_buf, crop_rect.w, crop_rect.h); + crop_nv12_to_yuv((uint8_t *)stream_buf, stride, uv_offset, mirror_y, mirror_u, mirror_v, crop_rect); + libyuv::I420Mirror(mirror_y, crop_rect.w, + mirror_u, crop_rect.w / 2, + mirror_v, crop_rect.w / 2, + cropped_y, crop_rect.w, + cropped_u, crop_rect.w / 2, + cropped_v, crop_rect.w / 2, + crop_rect.w, crop_rect.h); + } - // here makes a uint8 copy - for (int r = 0; r < MODEL_HEIGHT; ++r) { - memcpy(net_input_buf + r * MODEL_WIDTH, raw_y_start + r * stride + h_off, MODEL_WIDTH); + auto [resized_buf, resized_u, resized_v] = get_yuv_buf(s->resized_buf, resized_width, resized_height); + uint8_t *resized_y = resized_buf; + libyuv::FilterMode mode = libyuv::FilterModeEnum::kFilterBilinear; + libyuv::I420Scale(cropped_y, crop_rect.w, + cropped_u, crop_rect.w / 2, + cropped_v, crop_rect.w / 2, + crop_rect.w, crop_rect.h, + resized_y, resized_width, + resized_u, resized_width / 2, + resized_v, resized_width / 2, + resized_width, resized_height, + mode); + + + int yuv_buf_len = (MODEL_WIDTH/2) * (MODEL_HEIGHT/2) * 6; // Y|u|v -> y|y|y|y|u|v + float *net_input_buf = get_buffer(s->net_input_buf, yuv_buf_len); + // one shot conversion, O(n) anyway + // yuvframe2tensor, normalize + for (int r = 0; r < MODEL_HEIGHT/2; r++) { + for (int c = 0; c < MODEL_WIDTH/2; c++) { + // Y_ul + net_input_buf[(r*MODEL_WIDTH/2) + c + (0*(MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = s->tensor[resized_y[(2*r)*resized_width + 2*c]]; + // Y_dl + net_input_buf[(r*MODEL_WIDTH/2) + c + (1*(MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = s->tensor[resized_y[(2*r+1)*resized_width + 2*c]]; + // Y_ur + net_input_buf[(r*MODEL_WIDTH/2) + c + (2*(MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = s->tensor[resized_y[(2*r)*resized_width + 2*c+1]]; + // Y_dr + net_input_buf[(r*MODEL_WIDTH/2) + c + (3*(MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = s->tensor[resized_y[(2*r+1)*resized_width + 2*c+1]]; + // U + net_input_buf[(r*MODEL_WIDTH/2) + c + (4*(MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = s->tensor[resized_u[r*resized_width/2 + c]]; + // V + net_input_buf[(r*MODEL_WIDTH/2) + c + (5*(MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = s->tensor[resized_v[r*resized_width/2 + c]]; + } } - // printf("preprocess completed. %d \n", yuv_buf_len); - // FILE *dump_yuv_file = fopen("/tmp/rawdump.yuv", "wb"); - // fwrite(net_input_buf, yuv_buf_len, sizeof(uint8_t), dump_yuv_file); - // fclose(dump_yuv_file); + //printf("preprocess completed. %d \n", yuv_buf_len); + //FILE *dump_yuv_file = fopen("/tmp/rawdump.yuv", "wb"); + //fwrite(resized_buf, yuv_buf_len, sizeof(uint8_t), dump_yuv_file); + //fclose(dump_yuv_file); + + // *** testing *** + // idat = np.frombuffer(open("/tmp/inputdump.yuv", "rb").read(), np.float32).reshape(6, 160, 320) + // imshow(cv2.cvtColor(tensor_to_frames(idat[None]/0.0078125+128)[0], cv2.COLOR_YUV2RGB_I420)) + + //FILE *dump_yuv_file2 = fopen("/tmp/inputdump.yuv", "wb"); + //fwrite(net_input_buf, MODEL_HEIGHT*MODEL_WIDTH*3/2, sizeof(float), dump_yuv_file2); + //fclose(dump_yuv_file2); double t1 = millis_since_boot(); - s->m->addImage((float*)net_input_buf, yuv_buf_len / 4); + s->m->addImage(net_input_buf, yuv_buf_len); for (int i = 0; i < CALIB_LEN; i++) { s->calib[i] = calib[i]; } s->m->execute(); double t2 = millis_since_boot(); - DMonitoringModelResult model_res = {0}; - parse_driver_data(model_res.driver_state_lhd, s, 0); - parse_driver_data(model_res.driver_state_rhd, s, 41); - model_res.poor_vision_prob = sigmoid(s->output[82]); - model_res.wheel_on_right_prob = sigmoid(s->output[83]); - model_res.dsp_execution_time = (t2 - t1) / 1000.; - - return model_res; + DMonitoringResult ret = {0}; + for (int i = 0; i < 3; ++i) { + ret.face_orientation[i] = s->output[i] * REG_SCALE; + ret.face_orientation_meta[i] = exp(s->output[6 + i]); + } + for (int i = 0; i < 2; ++i) { + ret.face_position[i] = s->output[3 + i] * REG_SCALE; + ret.face_position_meta[i] = exp(s->output[9 + i]); + } + for (int i = 0; i < 4; ++i) { + ret.ready_prob[i] = sigmoid(s->output[39 + i]); + } + for (int i = 0; i < 2; ++i) { + ret.not_ready_prob[i] = sigmoid(s->output[43 + i]); + } + ret.face_prob = sigmoid(s->output[12]); + ret.left_eye_prob = sigmoid(s->output[21]); + ret.right_eye_prob = sigmoid(s->output[30]); + ret.left_blink_prob = sigmoid(s->output[31]); + ret.right_blink_prob = sigmoid(s->output[32]); + ret.sg_prob = sigmoid(s->output[33]); + ret.poor_vision = sigmoid(s->output[34]); + ret.partial_face = sigmoid(s->output[35]); + ret.distracted_pose = sigmoid(s->output[36]); + ret.distracted_eyes = sigmoid(s->output[37]); + ret.occluded_prob = sigmoid(s->output[38]); + ret.dsp_execution_time = (t2 - t1) / 1000.; + return ret; } -void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringModelResult &model_res, float execution_time, kj::ArrayPtr raw_pred) { +void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResult &res, float execution_time, kj::ArrayPtr raw_pred) { // make msg MessageBuilder msg; - auto framed = msg.initEvent().initDriverStateV2(); + auto framed = msg.initEvent().initDriverState(); framed.setFrameId(frame_id); framed.setModelExecutionTime(execution_time); - framed.setDspExecutionTime(model_res.dsp_execution_time); - - framed.setPoorVisionProb(model_res.poor_vision_prob); - framed.setWheelOnRightProb(model_res.wheel_on_right_prob); - fill_driver_data(framed.initLeftDriverData(), model_res.driver_state_lhd); - fill_driver_data(framed.initRightDriverData(), model_res.driver_state_rhd); - + framed.setDspExecutionTime(res.dsp_execution_time); + + framed.setFaceOrientation(res.face_orientation); + framed.setFaceOrientationStd(res.face_orientation_meta); + framed.setFacePosition(res.face_position); + framed.setFacePositionStd(res.face_position_meta); + framed.setFaceProb(res.face_prob); + framed.setLeftEyeProb(res.left_eye_prob); + framed.setRightEyeProb(res.right_eye_prob); + framed.setLeftBlinkProb(res.left_blink_prob); + framed.setRightBlinkProb(res.right_blink_prob); + framed.setSunglassesProb(res.sg_prob); + framed.setPoorVision(res.poor_vision); + framed.setPartialFace(res.partial_face); + framed.setDistractedPose(res.distracted_pose); + framed.setDistractedEyes(res.distracted_eyes); + framed.setOccludedProb(res.occluded_prob); + framed.setReadyProb(res.ready_prob); + framed.setNotReadyProb(res.not_ready_prob); if (send_raw_pred) { framed.setRawPredictions(raw_pred.asBytes()); } - pm.send("driverStateV2", msg); + pm.send("driverState", msg); } void dmonitoring_free(DMonitoringModelState* s) { diff --git a/selfdrive/modeld/models/dmonitoring.h b/selfdrive/modeld/models/dmonitoring.h index 874722cd93..a1be91e3bb 100644 --- a/selfdrive/modeld/models/dmonitoring.h +++ b/selfdrive/modeld/models/dmonitoring.h @@ -9,43 +9,44 @@ #define CALIB_LEN 3 -#define OUTPUT_SIZE 84 +#define OUTPUT_SIZE 45 #define REG_SCALE 0.25f -typedef struct DriverStateResult { +typedef struct DMonitoringResult { float face_orientation[3]; - float face_orientation_std[3]; + float face_orientation_meta[3]; float face_position[2]; - float face_position_std[2]; + float face_position_meta[2]; float face_prob; float left_eye_prob; float right_eye_prob; float left_blink_prob; float right_blink_prob; - float sunglasses_prob; + float sg_prob; + float poor_vision; + float partial_face; + float distracted_pose; + float distracted_eyes; float occluded_prob; float ready_prob[4]; float not_ready_prob[2]; -} DriverStateResult; - -typedef struct DMonitoringModelResult { - DriverStateResult driver_state_lhd; - DriverStateResult driver_state_rhd; - float poor_vision_prob; - float wheel_on_right_prob; float dsp_execution_time; -} DMonitoringModelResult; +} DMonitoringResult; typedef struct DMonitoringModelState { RunModel *m; bool is_rhd; float output[OUTPUT_SIZE]; - std::vector net_input_buf; + std::vector resized_buf; + std::vector cropped_buf; + std::vector premirror_cropped_buf; + std::vector net_input_buf; float calib[CALIB_LEN]; + float tensor[UINT8_MAX + 1]; } DMonitoringModelState; void dmonitoring_init(DMonitoringModelState* s); -DMonitoringModelResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_buf, int width, int height, int stride, int uv_offset, float *calib); -void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringModelResult &model_res, float execution_time, kj::ArrayPtr raw_pred); +DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_buf, int width, int height, int stride, int uv_offset, float *calib); +void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResult &res, float execution_time, kj::ArrayPtr raw_pred); void dmonitoring_free(DMonitoringModelState* s); diff --git a/selfdrive/modeld/models/dmonitoring_model.current b/selfdrive/modeld/models/dmonitoring_model.current index ba2865429e..74bcfe17a4 100644 --- a/selfdrive/modeld/models/dmonitoring_model.current +++ b/selfdrive/modeld/models/dmonitoring_model.current @@ -1,2 +1,2 @@ -5b02cff5-2b29-431d-b186-372e9c6fd0c7 -bf33cc569076984626ac7e027f927aa593261fa7 \ No newline at end of file +a8236e30-5bee-4689-8ea0-fc102e2770e5 +d508c79bae1c1c451f3af3e2bc231ce33678cb43 \ No newline at end of file diff --git a/selfdrive/modeld/models/dmonitoring_model.onnx b/selfdrive/modeld/models/dmonitoring_model.onnx index 1fca1317d5..51b0d1ed76 100644 --- a/selfdrive/modeld/models/dmonitoring_model.onnx +++ b/selfdrive/modeld/models/dmonitoring_model.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:aca1dd411b5f488bea605dc360656e631fc4301968a589ea072e2220c8092600 -size 9157561 +oid sha256:00731ebd06fcff7e5837607b91bc56cad3bed5d7ee89052c911c981e8f665308 +size 3679940 diff --git a/selfdrive/modeld/models/dmonitoring_model_q.dlc b/selfdrive/modeld/models/dmonitoring_model_q.dlc index c1cba15176..2e54f7ee4b 100644 --- a/selfdrive/modeld/models/dmonitoring_model_q.dlc +++ b/selfdrive/modeld/models/dmonitoring_model_q.dlc @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:d146b1d1fd9d40d57d058e51d285f83676866e26d9e5aff9fa27623ce343b58a -size 2636941 +oid sha256:667df5e925570a0f6a33dfb890e186a1f13f101885b46db47ec45305737dffb6 +size 1145921 diff --git a/selfdrive/modeld/runners/onnx_runner.py b/selfdrive/modeld/runners/onnx_runner.py index ac7cc68814..e282a66b66 100755 --- a/selfdrive/modeld/runners/onnx_runner.py +++ b/selfdrive/modeld/runners/onnx_runner.py @@ -9,24 +9,20 @@ os.environ["OMP_WAIT_POLICY"] = "PASSIVE" import onnxruntime as ort # pylint: disable=import-error -def read(sz, tf8=False): +def read(sz): dd = [] gt = 0 - szof = 1 if tf8 else 4 - while gt < sz * szof: - st = os.read(0, sz * szof - gt) + while gt < sz * 4: + st = os.read(0, sz * 4 - gt) assert(len(st) > 0) dd.append(st) gt += len(st) - r = np.frombuffer(b''.join(dd), dtype=np.uint8 if tf8 else np.float32).astype(np.float32) - if tf8: - r = r / 255. - return r + return np.frombuffer(b''.join(dd), dtype=np.float32) def write(d): os.write(1, d.tobytes()) -def run_loop(m, tf8_input=False): +def run_loop(m): ishapes = [[1]+ii.shape[1:] for ii in m.get_inputs()] keys = [x.name for x in m.get_inputs()] @@ -37,10 +33,10 @@ def run_loop(m, tf8_input=False): print("ready to run onnx model", keys, ishapes, file=sys.stderr) while 1: inputs = [] - for k, shp in zip(keys, ishapes): + for shp in ishapes: ts = np.product(shp) #print("reshaping %s with offset %d" % (str(shp), offset), file=sys.stderr) - inputs.append(read(ts, (k=='input_img' and tf8_input)).reshape(shp)) + inputs.append(read(ts).reshape(shp)) ret = m.run(None, dict(zip(keys, inputs))) #print(ret, file=sys.stderr) for r in ret: @@ -48,7 +44,6 @@ def run_loop(m, tf8_input=False): if __name__ == "__main__": - print(sys.argv, file=sys.stderr) print("Onnx available providers: ", ort.get_available_providers(), file=sys.stderr) options = ort.SessionOptions() options.graph_optimization_level = ort.GraphOptimizationLevel.ORT_DISABLE_ALL @@ -68,6 +63,6 @@ if __name__ == "__main__": print("Onnx selected provider: ", [provider], file=sys.stderr) ort_session = ort.InferenceSession(sys.argv[1], options, providers=[provider]) print("Onnx using ", ort_session.get_providers(), file=sys.stderr) - run_loop(ort_session, tf8_input=("--use_tf8" in sys.argv)) + run_loop(ort_session) except KeyboardInterrupt: pass diff --git a/selfdrive/modeld/runners/onnxmodel.cc b/selfdrive/modeld/runners/onnxmodel.cc index 1f9f551abc..9b4d6fd015 100644 --- a/selfdrive/modeld/runners/onnxmodel.cc +++ b/selfdrive/modeld/runners/onnxmodel.cc @@ -14,13 +14,12 @@ #include "common/swaglog.h" #include "common/util.h" -ONNXModel::ONNXModel(const char *path, float *_output, size_t _output_size, int runtime, bool _use_extra, bool _use_tf8) { +ONNXModel::ONNXModel(const char *path, float *_output, size_t _output_size, int runtime, bool _use_extra) { LOGD("loading model %s", path); output = _output; output_size = _output_size; use_extra = _use_extra; - use_tf8 = _use_tf8; int err = pipe(pipein); assert(err == 0); @@ -29,12 +28,11 @@ ONNXModel::ONNXModel(const char *path, float *_output, size_t _output_size, int std::string exe_dir = util::dir_name(util::readlink("/proc/self/exe")); std::string onnx_runner = exe_dir + "/runners/onnx_runner.py"; - std::string tf8_arg = use_tf8 ? "--use_tf8" : ""; proc_pid = fork(); if (proc_pid == 0) { LOGD("spawning onnx process %s", onnx_runner.c_str()); - char *argv[] = {(char*)onnx_runner.c_str(), (char*)path, (char*)tf8_arg.c_str(), nullptr}; + char *argv[] = {(char*)onnx_runner.c_str(), (char*)path, nullptr}; dup2(pipein[0], 0); dup2(pipeout[1], 1); close(pipein[0]); diff --git a/selfdrive/modeld/runners/onnxmodel.h b/selfdrive/modeld/runners/onnxmodel.h index 4ac599e2af..567d81d29e 100644 --- a/selfdrive/modeld/runners/onnxmodel.h +++ b/selfdrive/modeld/runners/onnxmodel.h @@ -6,7 +6,7 @@ class ONNXModel : public RunModel { public: - ONNXModel(const char *path, float *output, size_t output_size, int runtime, bool use_extra = false, bool _use_tf8 = false); + ONNXModel(const char *path, float *output, size_t output_size, int runtime, bool use_extra = false); ~ONNXModel(); void addRecurrent(float *state, int state_size); void addDesire(float *state, int state_size); @@ -31,7 +31,6 @@ private: int calib_size; float *image_input_buf = NULL; int image_buf_size; - bool use_tf8; float *extra_input_buf = NULL; int extra_buf_size; bool use_extra; diff --git a/selfdrive/modeld/runners/snpemodel.cc b/selfdrive/modeld/runners/snpemodel.cc index 4d6917e894..1861494d59 100644 --- a/selfdrive/modeld/runners/snpemodel.cc +++ b/selfdrive/modeld/runners/snpemodel.cc @@ -14,11 +14,10 @@ void PrintErrorStringAndExit() { std::exit(EXIT_FAILURE); } -SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra, bool luse_tf8) { +SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra) { output = loutput; output_size = loutput_size; use_extra = luse_extra; - use_tf8 = luse_tf8; #ifdef QCOM2 if (runtime==USE_GPU_RUNTIME) { Runtime = zdl::DlSystem::Runtime_t::GPU; @@ -71,16 +70,14 @@ SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int printf("model: %s -> %s\n", input_tensor_name, output_tensor_name); zdl::DlSystem::UserBufferEncodingFloat userBufferEncodingFloat; - zdl::DlSystem::UserBufferEncodingTf8 userBufferEncodingTf8(0, 1./255); // network takes 0-1 zdl::DlSystem::IUserBufferFactory& ubFactory = zdl::SNPE::SNPEFactory::getUserBufferFactory(); - size_t size_of_input = use_tf8 ? sizeof(uint8_t) : sizeof(float); // create input buffer { const auto &inputDims_opt = snpe->getInputDimensions(input_tensor_name); const zdl::DlSystem::TensorShape& bufferShape = *inputDims_opt; std::vector strides(bufferShape.rank()); - strides[strides.size() - 1] = size_of_input; + strides[strides.size() - 1] = sizeof(float); size_t product = 1; for (size_t i = 0; i < bufferShape.rank(); i++) product *= bufferShape[i]; size_t stride = strides[strides.size() - 1]; @@ -89,10 +86,7 @@ SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int strides[i-1] = stride; } printf("input product is %lu\n", product); - inputBuffer = ubFactory.createUserBuffer(NULL, - product*size_of_input, - strides, - use_tf8 ? (zdl::DlSystem::UserBufferEncoding*)&userBufferEncodingTf8 : (zdl::DlSystem::UserBufferEncoding*)&userBufferEncodingFloat); + inputBuffer = ubFactory.createUserBuffer(NULL, product*sizeof(float), strides, &userBufferEncodingFloat); inputMap.add(input_tensor_name, inputBuffer.get()); } diff --git a/selfdrive/modeld/runners/snpemodel.h b/selfdrive/modeld/runners/snpemodel.h index ed9d58d1e1..ba51fdced0 100644 --- a/selfdrive/modeld/runners/snpemodel.h +++ b/selfdrive/modeld/runners/snpemodel.h @@ -23,7 +23,7 @@ class SNPEModel : public RunModel { public: - SNPEModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra = false, bool use_tf8 = false); + SNPEModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra = false); void addRecurrent(float *state, int state_size); void addTrafficConvention(float *state, int state_size); void addCalib(float *state, int state_size); @@ -52,7 +52,6 @@ private: std::unique_ptr inputBuffer; float *input; size_t input_size; - bool use_tf8; // snpe output stuff zdl::DlSystem::UserBufferMap outputMap; diff --git a/selfdrive/monitoring/dmonitoringd.py b/selfdrive/monitoring/dmonitoringd.py index c31e9da43b..9a3196030b 100755 --- a/selfdrive/monitoring/dmonitoringd.py +++ b/selfdrive/monitoring/dmonitoringd.py @@ -18,7 +18,7 @@ def dmonitoringd_thread(sm=None, pm=None): pm = messaging.PubMaster(['driverMonitoringState']) if sm is None: - sm = messaging.SubMaster(['driverStateV2', 'liveCalibration', 'carState', 'controlsState', 'modelV2'], poll=['driverStateV2']) + sm = messaging.SubMaster(['driverState', 'liveCalibration', 'carState', 'controlsState', 'modelV2'], poll=['driverState']) driver_status = DriverStatus(rhd=Params().get_bool("IsRHD")) @@ -34,7 +34,7 @@ def dmonitoringd_thread(sm=None, pm=None): while True: sm.update() - if not sm.updated['driverStateV2']: + if not sm.updated['driverState']: continue # Get interaction @@ -51,7 +51,7 @@ def dmonitoringd_thread(sm=None, pm=None): # Get data from dmonitoringmodeld events = Events() - driver_status.update_states(sm['driverStateV2'], sm['liveCalibration'].rpyCalib, sm['carState'].vEgo, sm['controlsState'].enabled) + driver_status.update_states(sm['driverState'], sm['liveCalibration'].rpyCalib, sm['carState'].vEgo, sm['controlsState'].enabled) # Block engaging after max number of distrations if driver_status.terminal_alert_cnt >= driver_status.settings._MAX_TERMINAL_ALERTS or \ @@ -79,7 +79,6 @@ def dmonitoringd_thread(sm=None, pm=None): "isLowStd": driver_status.pose.low_std, "hiStdCount": driver_status.hi_stds, "isActiveMode": driver_status.active_monitoring_mode, - "isRHD": driver_status.wheel_on_right, } pm.send('driverMonitoringState', dat) diff --git a/selfdrive/monitoring/driver_monitor.py b/selfdrive/monitoring/driver_monitor.py index e7ed175846..662e0d76ce 100644 --- a/selfdrive/monitoring/driver_monitor.py +++ b/selfdrive/monitoring/driver_monitor.py @@ -5,7 +5,6 @@ from common.numpy_fast import interp from common.realtime import DT_DMON from common.filter_simple import FirstOrderFilter from common.stat_live import RunningStatFilter -from common.transformations.camera import tici_d_frame_size EventName = car.CarEvent.EventName @@ -27,29 +26,32 @@ class DRIVER_MONITOR_SETTINGS(): self._DISTRACTED_PROMPT_TIME_TILL_TERMINAL = 6. self._FACE_THRESHOLD = 0.5 + self._PARTIAL_FACE_THRESHOLD = 0.8 self._EYE_THRESHOLD = 0.65 self._SG_THRESHOLD = 0.925 - self._BLINK_THRESHOLD = 0.861 + self._BLINK_THRESHOLD = 0.8 + self._BLINK_THRESHOLD_SLACK = 0.9 + self._BLINK_THRESHOLD_STRICT = self._BLINK_THRESHOLD self._EE_THRESH11 = 0.75 self._EE_THRESH12 = 3.25 self._EE_THRESH21 = 0.01 self._EE_THRESH22 = 0.35 - self._POSE_PITCH_THRESHOLD = 0.3133 - self._POSE_PITCH_THRESHOLD_SLACK = 0.3237 + self._POSE_PITCH_THRESHOLD = 0.3237 + self._POSE_PITCH_THRESHOLD_SLACK = 0.3657 self._POSE_PITCH_THRESHOLD_STRICT = self._POSE_PITCH_THRESHOLD - self._POSE_YAW_THRESHOLD = 0.4020 - self._POSE_YAW_THRESHOLD_SLACK = 0.5042 + self._POSE_YAW_THRESHOLD = 0.3109 + self._POSE_YAW_THRESHOLD_SLACK = 0.4294 self._POSE_YAW_THRESHOLD_STRICT = self._POSE_YAW_THRESHOLD - self._PITCH_NATURAL_OFFSET = 0.029 # initial value before offset is learned - self._YAW_NATURAL_OFFSET = 0.097 # initial value before offset is learned + self._PITCH_NATURAL_OFFSET = 0.057 # initial value before offset is learned + self._YAW_NATURAL_OFFSET = 0.11 # initial value before offset is learned self._PITCH_MAX_OFFSET = 0.124 self._PITCH_MIN_OFFSET = -0.0881 self._YAW_MAX_OFFSET = 0.289 self._YAW_MIN_OFFSET = -0.0246 - self._POSESTD_THRESHOLD = 0.3 + self._POSESTD_THRESHOLD = 0.315 self._HI_STD_FALLBACK_TIME = int(10 / self._DT_DMON) # fall back to wheel touch if model is uncertain for 10s self._DISTRACTED_FILTER_TS = 0.25 # 0.6Hz @@ -57,9 +59,6 @@ class DRIVER_MONITOR_SETTINGS(): self._POSE_OFFSET_MIN_COUNT = int(60 / self._DT_DMON) # valid data counts before calibration completes, 1min cumulative self._POSE_OFFSET_MAX_COUNT = int(360 / self._DT_DMON) # stop deweighting new data after 6 min, aka "short term memory" - self._WHEELPOS_THRESHOLD = 0.5 - self._WHEELPOS_FILTER_MIN_COUNT = int(5 / self._DT_DMON) - self._RECOVERY_FACTOR_MAX = 5. # relative to minus step change self._RECOVERY_FACTOR_MIN = 1.25 # relative to minus step change @@ -67,9 +66,9 @@ class DRIVER_MONITOR_SETTINGS(): self._MAX_TERMINAL_DURATION = int(30 / self._DT_DMON) # not allowed to engage after 30s of terminal alerts -# model output refers to center of undistorted+leveled image -EFL = 598.0 # focal length in K -W, H = tici_d_frame_size # corrected image has same size as raw +# model output refers to center of cropped image, so need to apply the x displacement offset +RESIZED_FOCAL = 320.0 +H, W, FULL_W = 320, 160, 426 class DistractedType: NOT_DISTRACTED = 0 @@ -77,22 +76,22 @@ class DistractedType: DISTRACTED_BLINK = 2 DISTRACTED_E2E = 4 -def face_orientation_from_net(angles_desc, pos_desc, rpy_calib): +def face_orientation_from_net(angles_desc, pos_desc, rpy_calib, is_rhd): # the output of these angles are in device frame # so from driver's perspective, pitch is up and yaw is right pitch_net, yaw_net, roll_net = angles_desc - face_pixel_position = ((pos_desc[0]+0.5)*W, (pos_desc[1]+0.5)*H) - yaw_focal_angle = atan2(face_pixel_position[0] - W//2, EFL) - pitch_focal_angle = atan2(face_pixel_position[1] - H//2, EFL) + face_pixel_position = ((pos_desc[0] + .5)*W - W + FULL_W, (pos_desc[1]+.5)*H) + yaw_focal_angle = atan2(face_pixel_position[0] - FULL_W//2, RESIZED_FOCAL) + pitch_focal_angle = atan2(face_pixel_position[1] - H//2, RESIZED_FOCAL) pitch = pitch_net + pitch_focal_angle yaw = -yaw_net + yaw_focal_angle # no calib for roll pitch -= rpy_calib[1] - yaw -= rpy_calib[2] + yaw -= rpy_calib[2] * (1 - 2 * int(is_rhd)) # lhd -> -=, rhd -> += return roll_net, pitch, yaw class DriverPose(): @@ -113,6 +112,7 @@ class DriverBlink(): def __init__(self): self.left_blink = 0. self.right_blink = 0. + self.cfactor = 1. class DriverStatus(): def __init__(self, rhd=False, settings=DRIVER_MONITOR_SETTINGS()): @@ -120,7 +120,7 @@ class DriverStatus(): self.settings = settings # init driver status - # self.wheelpos_learner = RunningStatFilter() + self.is_rhd_region = rhd self.pose = DriverPose(self.settings._POSE_OFFSET_MAX_COUNT) self.pose_calibrated = False self.blink = DriverBlink() @@ -137,8 +137,8 @@ class DriverStatus(): self.distracted_types = [] self.driver_distracted = False self.driver_distraction_filter = FirstOrderFilter(0., self.settings._DISTRACTED_FILTER_TS, self.settings._DT_DMON) - self.wheel_on_right = rhd self.face_detected = False + self.face_partial = False self.terminal_alert_cnt = 0 self.terminal_time = 0 self.step_change = 0. @@ -197,7 +197,7 @@ class DriverStatus(): yaw_error > self.settings._POSE_YAW_THRESHOLD*self.pose.cfactor_yaw: distracted_types.append(DistractedType.DISTRACTED_POSE) - if (self.blink.left_blink + self.blink.right_blink)*0.5 > self.settings._BLINK_THRESHOLD: + if (self.blink.left_blink + self.blink.right_blink)*0.5 > self.settings._BLINK_THRESHOLD*self.blink.cfactor: distracted_types.append(DistractedType.DISTRACTED_BLINK) if self.ee1_calibrated: @@ -214,7 +214,13 @@ class DriverStatus(): return distracted_types def set_policy(self, model_data, car_speed): + ep = min(model_data.meta.engagedProb, 0.8) / 0.8 # engaged prob bp = model_data.meta.disengagePredictions.brakeDisengageProbs[0] # brake disengage prob in next 2s + # TODO: retune adaptive blink + self.blink.cfactor = interp(ep, [0, 0.5, 1], + [self.settings._BLINK_THRESHOLD_STRICT, + self.settings._BLINK_THRESHOLD, + self.settings._BLINK_THRESHOLD_SLACK]) / self.settings._BLINK_THRESHOLD k1 = max(-0.00156*((car_speed-16)**2)+0.6, 0.2) bp_normal = max(min(bp / k1, 0.5),0) self.pose.cfactor_pitch = interp(bp_normal, [0, 0.5], @@ -225,36 +231,28 @@ class DriverStatus(): self.settings._POSE_YAW_THRESHOLD_STRICT]) / self.settings._POSE_YAW_THRESHOLD def update_states(self, driver_state, cal_rpy, car_speed, op_engaged): - # rhd_pred = driver_state.wheelOnRightProb - # if car_speed > 0.01: - # self.wheelpos_learner.push_and_update(rhd_pred) - # if self.wheelpos_learner.filtered_stat.n > self.settings._WHEELPOS_FILTER_MIN_COUNT: - # self.wheel_on_right = self.wheelpos_learner.filtered_stat.M > self.settings._WHEELPOS_THRESHOLD - # else: - # self.wheel_on_right = rhd_pred > self.settings._WHEELPOS_THRESHOLD - driver_data = driver_state.rightDriverData if self.wheel_on_right else driver_state.leftDriverData - if not all(len(x) > 0 for x in (driver_data.faceOrientation, driver_data.facePosition, - driver_data.faceOrientationStd, driver_data.facePositionStd, - driver_data.readyProb, driver_data.notReadyProb)): + if not all(len(x) > 0 for x in (driver_state.faceOrientation, driver_state.facePosition, + driver_state.faceOrientationStd, driver_state.facePositionStd, + driver_state.readyProb, driver_state.notReadyProb)): return - self.face_detected = driver_data.faceProb > self.settings._FACE_THRESHOLD - self.pose.roll, self.pose.pitch, self.pose.yaw = face_orientation_from_net(driver_data.faceOrientation, driver_data.facePosition, cal_rpy) - if self.wheel_on_right: - self.pose.yaw *= -1 - self.pose.pitch_std = driver_data.faceOrientationStd[0] - self.pose.yaw_std = driver_data.faceOrientationStd[1] + self.face_partial = driver_state.partialFace > self.settings._PARTIAL_FACE_THRESHOLD + self.face_detected = driver_state.faceProb > self.settings._FACE_THRESHOLD or self.face_partial + self.pose.roll, self.pose.pitch, self.pose.yaw = face_orientation_from_net(driver_state.faceOrientation, driver_state.facePosition, cal_rpy, self.is_rhd_region) + self.pose.pitch_std = driver_state.faceOrientationStd[0] + self.pose.yaw_std = driver_state.faceOrientationStd[1] + # self.pose.roll_std = driver_state.faceOrientationStd[2] model_std_max = max(self.pose.pitch_std, self.pose.yaw_std) - self.pose.low_std = model_std_max < self.settings._POSESTD_THRESHOLD - self.blink.left_blink = driver_data.leftBlinkProb * (driver_data.leftEyeProb > self.settings._EYE_THRESHOLD) * (driver_data.sunglassesProb < self.settings._SG_THRESHOLD) - self.blink.right_blink = driver_data.rightBlinkProb * (driver_data.rightEyeProb > self.settings._EYE_THRESHOLD) * (driver_data.sunglassesProb < self.settings._SG_THRESHOLD) - self.eev1 = driver_data.notReadyProb[1] - self.eev2 = driver_data.readyProb[0] + self.pose.low_std = model_std_max < self.settings._POSESTD_THRESHOLD and not self.face_partial + self.blink.left_blink = driver_state.leftBlinkProb * (driver_state.leftEyeProb > self.settings._EYE_THRESHOLD) * (driver_state.sunglassesProb < self.settings._SG_THRESHOLD) + self.blink.right_blink = driver_state.rightBlinkProb * (driver_state.rightEyeProb > self.settings._EYE_THRESHOLD) * (driver_state.sunglassesProb < self.settings._SG_THRESHOLD) + self.eev1 = driver_state.notReadyProb[1] + self.eev2 = driver_state.readyProb[0] self.distracted_types = self._get_distracted_types() self.driver_distracted = (DistractedType.DISTRACTED_POSE in self.distracted_types or DistractedType.DISTRACTED_BLINK in self.distracted_types) and \ - driver_data.faceProb > self.settings._FACE_THRESHOLD and self.pose.low_std + driver_state.faceProb > self.settings._FACE_THRESHOLD and self.pose.low_std self.driver_distraction_filter.update(self.driver_distracted) # update offseter diff --git a/selfdrive/monitoring/test_monitoring.py b/selfdrive/monitoring/test_monitoring.py index 43b5e7747e..a84ed242ba 100755 --- a/selfdrive/monitoring/test_monitoring.py +++ b/selfdrive/monitoring/test_monitoring.py @@ -17,19 +17,19 @@ INVISIBLE_SECONDS_TO_ORANGE = dm_settings._AWARENESS_TIME - dm_settings._AWARENE INVISIBLE_SECONDS_TO_RED = dm_settings._AWARENESS_TIME + 1 def make_msg(face_detected, distracted=False, model_uncertain=False): - ds = log.DriverStateV2.new_message() - ds.leftDriverData.faceOrientation = [0., 0., 0.] - ds.leftDriverData.facePosition = [0., 0.] - ds.leftDriverData.faceProb = 1. * face_detected - ds.leftDriverData.leftEyeProb = 1. - ds.leftDriverData.rightEyeProb = 1. - ds.leftDriverData.leftBlinkProb = 1. * distracted - ds.leftDriverData.rightBlinkProb = 1. * distracted - ds.leftDriverData.faceOrientationStd = [1.*model_uncertain, 1.*model_uncertain, 1.*model_uncertain] - ds.leftDriverData.facePositionStd = [1.*model_uncertain, 1.*model_uncertain] + ds = log.DriverState.new_message() + ds.faceOrientation = [0., 0., 0.] + ds.facePosition = [0., 0.] + ds.faceProb = 1. * face_detected + ds.leftEyeProb = 1. + ds.rightEyeProb = 1. + ds.leftBlinkProb = 1. * distracted + ds.rightBlinkProb = 1. * distracted + ds.faceOrientationStd = [1.*model_uncertain, 1.*model_uncertain, 1.*model_uncertain] + ds.facePositionStd = [1.*model_uncertain, 1.*model_uncertain] # TODO: test both separately when e2e is used - ds.leftDriverData.readyProb = [0., 0., 0., 0.] - ds.leftDriverData.notReadyProb = [0., 0.] + ds.readyProb = [0., 0., 0., 0.] + ds.notReadyProb = [0., 0.] return ds diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index 032b504879..b83629c76a 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -52,7 +52,7 @@ def model_replay(lr, frs): vipc_server.create_buffers(VisionStreamType.VISION_STREAM_WIDE_ROAD, 40, False, *(tici_f_frame_size)) vipc_server.start_listener() - sm = messaging.SubMaster(['modelV2', 'driverStateV2']) + sm = messaging.SubMaster(['modelV2', 'driverState']) pm = messaging.PubMaster(['roadCameraState', 'wideRoadCameraState', 'driverCameraState', 'liveCalibration', 'lateralPlan']) try: @@ -112,7 +112,7 @@ def model_replay(lr, frs): if min(frame_idxs['roadCameraState'], frame_idxs['wideRoadCameraState']) > recv_cnt['modelV2']: recv = "modelV2" elif msg.which() == 'driverCameraState': - recv = "driverStateV2" + recv = "driverState" # wait for a response with Timeout(15, f"timed out waiting for {recv}"): @@ -170,8 +170,8 @@ if __name__ == "__main__": 'logMonoTime', 'modelV2.frameDropPerc', 'modelV2.modelExecutionTime', - 'driverStateV2.modelExecutionTime', - 'driverStateV2.dspExecutionTime' + 'driverState.modelExecutionTime', + 'driverState.dspExecutionTime' ] # TODO this tolerence is absurdly large tolerance = 5e-1 if PC else None diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 626d54a8f0..90520f2619 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -1d0979ca59dbc89bc5890656e9501e83f0556d50 +f74ab97371be93fdc28333e5ea12bbb78c3a32d0 diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 89885ef397..1eda9bc7f5 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -293,7 +293,7 @@ CONFIGS = [ ProcessConfig( proc_name="dmonitoringd", pub_sub={ - "driverStateV2": ["driverMonitoringState"], + "driverState": ["driverMonitoringState"], "liveCalibration": [], "carState": [], "modelV2": [], "controlsState": [], }, ignore=["logMonoTime", "valid"], diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 3beeaff3b2..6cf53a046e 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -33,7 +33,7 @@ PROCS = { "selfdrive.controls.radard": 4.5, "./_modeld": 4.48, "./boardd": 3.63, - "./_dmonitoringmodeld": 5.0, + "./_dmonitoringmodeld": 10.0, "selfdrive.thermald.thermald": 3.87, "selfdrive.locationd.calibrationd": 2.0, "./_soundd": 1.0, @@ -60,7 +60,7 @@ TIMINGS = { "roadCameraState": [2.5, 0.35], "driverCameraState": [2.5, 0.35], "modelV2": [2.5, 0.35], - "driverStateV2": [2.5, 0.40], + "driverState": [2.5, 0.40], "liveLocationKalman": [2.5, 0.35], "wideRoadCameraState": [1.5, 0.35], } @@ -221,7 +221,7 @@ class TestOnroad(unittest.TestCase): # TODO: this went up when plannerd cpu usage increased, why? cfgs = [ ("modelV2", 0.050, 0.036), - ("driverStateV2", 0.050, 0.026), + ("driverState", 0.050, 0.026), ] for (s, instant_max, avg_max) in cfgs: ts = [getattr(getattr(m, s), "modelExecutionTime") for m in self.lr if m.which() == s] diff --git a/selfdrive/ui/qt/offroad/driverview.cc b/selfdrive/ui/qt/offroad/driverview.cc index 868a97f604..06578b455a 100644 --- a/selfdrive/ui/qt/offroad/driverview.cc +++ b/selfdrive/ui/qt/offroad/driverview.cc @@ -25,7 +25,7 @@ void DriverViewWindow::mouseReleaseEvent(QMouseEvent* e) { emit done(); } -DriverViewScene::DriverViewScene(QWidget* parent) : sm({"driverStateV2"}), QWidget(parent) { +DriverViewScene::DriverViewScene(QWidget* parent) : sm({"driverState"}), QWidget(parent) { face_img = loadPixmap("../assets/img_driver_face.png", {FACE_IMG_SIZE, FACE_IMG_SIZE}); } @@ -57,36 +57,43 @@ void DriverViewScene::paintEvent(QPaintEvent* event) { return; } - cereal::DriverStateV2::Reader driver_state = sm["driverStateV2"].getDriverStateV2(); - cereal::DriverStateV2::DriverData::Reader driver_data; + const int width = 4 * height() / 3; + const QRect rect2 = {rect().center().x() - width / 2, rect().top(), width, rect().height()}; + const QRect valid_rect = {is_rhd ? rect2.right() - rect2.height() / 2 : rect2.left(), rect2.top(), rect2.height() / 2, rect2.height()}; - // is_rhd = driver_state.getWheelOnRightProb() > 0.5; - driver_data = is_rhd ? driver_state.getRightDriverData() : driver_state.getLeftDriverData(); + // blackout + const QColor bg(0, 0, 0, 140); + const QRect& blackout_rect = rect(); + p.fillRect(blackout_rect.adjusted(0, 0, valid_rect.left() - blackout_rect.right(), 0), bg); + p.fillRect(blackout_rect.adjusted(valid_rect.right() - blackout_rect.left(), 0, 0, 0), bg); + p.fillRect(blackout_rect.adjusted(valid_rect.left()-blackout_rect.left()+1, 0, valid_rect.right()-blackout_rect.right()-1, -valid_rect.height()*7/10), bg); // top dz - bool face_detected = driver_data.getFaceProb() > 0.5; + // face bounding box + cereal::DriverState::Reader driver_state = sm["driverState"].getDriverState(); + bool face_detected = driver_state.getFaceProb() > 0.5; if (face_detected) { - auto fxy_list = driver_data.getFacePosition(); - auto std_list = driver_data.getFaceOrientationStd(); + auto fxy_list = driver_state.getFacePosition(); + auto std_list = driver_state.getFaceOrientationStd(); float face_x = fxy_list[0]; float face_y = fxy_list[1]; float face_std = std::max(std_list[0], std_list[1]); float alpha = 0.7; - if (face_std > 0.15) { - alpha = std::max(0.7 - (face_std-0.15)*3.5, 0.0); + if (face_std > 0.08) { + alpha = std::max(0.7 - (face_std-0.08)*7, 0.0); } - const int box_size = 220; - // use approx instead of distort_points - int fbox_x = 1080.0 - 1714.0 * face_x; - int fbox_y = -135.0 + (504.0 + std::abs(face_x)*112.0) + (1205.0 - std::abs(face_x)*724.0) * face_y; + const int box_size = 0.6 * rect2.height() / 2; + const float rhd_offset = 0.05; // lhd is shifted, so rhd is not mirrored + int fbox_x = valid_rect.center().x() + (is_rhd ? (face_x + rhd_offset) : -face_x) * valid_rect.width(); + int fbox_y = valid_rect.center().y() + face_y * valid_rect.height(); p.setPen(QPen(QColor(255, 255, 255, alpha * 255), 10)); p.drawRoundedRect(fbox_x - box_size / 2, fbox_y - box_size / 2, box_size, box_size, 35.0, 35.0); } // icon - const int img_offset = 60; - const int img_x = rect().left() + img_offset; - const int img_y = rect().bottom() - FACE_IMG_SIZE - img_offset; - p.setOpacity(face_detected ? 1.0 : 0.2); + const int img_offset = 30; + const int img_x = is_rhd ? rect2.right() - FACE_IMG_SIZE - img_offset : rect2.left() + img_offset; + const int img_y = rect2.bottom() - FACE_IMG_SIZE - img_offset; + p.setOpacity(face_detected ? 1.0 : 0.3); p.drawPixmap(img_x, img_y, face_img); } diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 0a3b9762e5..f16e8e4e0d 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -54,15 +54,16 @@ const mat4 device_transform = {{ }}; mat4 get_driver_view_transform(int screen_width, int screen_height, int stream_width, int stream_height) { - const float driver_view_ratio = 2.0; - const float yscale = stream_height * driver_view_ratio / stream_width; + const float driver_view_ratio = 1.333; + const float yscale = stream_height * driver_view_ratio / tici_dm_crop::width; const float xscale = yscale*screen_height/screen_width*stream_width/stream_height; mat4 transform = (mat4){{ - xscale, 0.0, 0.0, 0.0, - 0.0, yscale, 0.0, 0.0, + xscale, 0.0, 0.0, xscale*tici_dm_crop::x_offset/stream_width*2, + 0.0, yscale, 0.0, yscale*tici_dm_crop::y_offset/stream_height*2, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, }}; + return transform; } From 6618d2bebee9a1fc5a0ee5d5a9b2764403865281 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 10 Jun 2022 16:18:31 -0700 Subject: [PATCH 003/302] Add missing fw versions for 2019 Sonata (#24814) --- selfdrive/car/hyundai/values.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 7d3ab93cde..4ca81fdb40 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -501,6 +501,7 @@ FW_VERSIONS = { ], (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00LFF LKAS AT USA LHD 1.00 1.01 95740-C1000 E51', + b'\xf1\x00LFF LKAS AT USA LHD 1.01 1.02 95740-C1000 E52', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x006T6H0_C2\x00\x006T6B4051\x00\x00TLF0G24NL1\xb0\x9f\xee\xf5', @@ -509,6 +510,7 @@ FW_VERSIONS = { b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6B4051\x00\x00\xf1\x006T6H0_C2\x00\x006T6B4051\x00\x00TLF0G24SL2n\x8d\xbe\xd8', b'\xf1\x87LAHSGN012918KF10\x98\x88x\x87\x88\x88x\x87\x88\x88\x98\x88\x87w\x88w\x88\x88\x98\x886o\xf6\xff\x98w\x7f\xff3\x00\xf1\x816W3B1051\x00\x00\xf1\x006W351_C2\x00\x006W3B1051\x00\x00TLF0T20NL2\x00\x00\x00\x00', b'\xf1\x87LAHSGN012918KF10\x98\x88x\x87\x88\x88x\x87\x88\x88\x98\x88\x87w\x88w\x88\x88\x98\x886o\xf6\xff\x98w\x7f\xff3\x00\xf1\x816W3B1051\x00\x00\xf1\x006W351_C2\x00\x006W3B1051\x00\x00TLF0T20NL2H\r\xbdm', + b'\xf1\x87LAJSG49645724HF0\x87x\x87\x88\x87www\x88\x99\xa8\x89\x88\x99\xa8\x89\x88\x99\xa8\x89S_\xfb\xff\x87f\x7f\xff^2\xf1\x816W3B1051\x00\x00\xf1\x006W351_C2\x00\x006W3B1051\x00\x00TLF0T20NL2H\r\xbdm', ], }, CAR.TUCSON: { From a8ccd8f838aff958a60546de04bf42220567b288 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Fri, 10 Jun 2022 16:26:06 -0700 Subject: [PATCH 004/302] put cereal on master --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index e9d3597d23..ff49c8e126 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit e9d3597d23311a3e33a2def74ceec839e5ff4bf5 +Subproject commit ff49c8e126ea04889af13d690ceaf520ce7084d2 From 3066ad81a8b2f89a22ddfc86a879395c573ce0f5 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Fri, 10 Jun 2022 17:57:23 -0700 Subject: [PATCH 005/302] Car interface: set max lateral torque from table (#24789) * json * better naem * Read from table * formatting and default to nan * Generate docs * Read from table * this should be the same * Prius v is full * test we always set the tunes correctly add to release files * Set for all cars Set for all cars * Revert tuning changes Revert tuning changes * remove that * fixes * update ref commit for new maxLateralAccels Co-authored-by: Shane Smiskol --- docs/CARS.md | 68 +++++++++++----------- release/files_common | 1 + selfdrive/car/chrysler/interface.py | 8 --- selfdrive/car/docs_definitions.py | 2 +- selfdrive/car/gm/interface.py | 2 - selfdrive/car/honda/interface.py | 11 ---- selfdrive/car/hyundai/interface.py | 8 --- selfdrive/car/interfaces.py | 10 +++- selfdrive/car/subaru/interface.py | 2 - selfdrive/car/tests/test_car_interfaces.py | 5 +- selfdrive/car/tests/test_docs.py | 6 ++ selfdrive/car/torque_data.json | 1 + selfdrive/car/toyota/interface.py | 12 ---- selfdrive/car/volkswagen/interface.py | 6 -- selfdrive/test/process_replay/ref_commit | 2 +- 15 files changed, 57 insertions(+), 87 deletions(-) create mode 100644 selfdrive/car/torque_data.json diff --git a/docs/CARS.md b/docs/CARS.md index e9b9e947f3..479c519dab 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -35,7 +35,7 @@ How We Rate The Cars **All supported cars can move between the tiers as support changes.** -# Gold - 29 cars +# Gold - 28 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -52,10 +52,9 @@ How We Rate The Cars |Lexus|ES 2019-21|All|||||| |Lexus|ES Hybrid 2019-22|All|||||| |Lexus|NX 2020|All|||||| -|Lexus|NX Hybrid 2020|All|||||| +|Lexus|RX 2020-22|All|||||| |Lexus|UX Hybrid 2019-21|All|||||| |Toyota|Avalon 2022|All|||||| -|Toyota|Avalon Hybrid 2022|All|||||| |Toyota|Camry 2021-22|All||[4](#footnotes)|||| |Toyota|Camry Hybrid 2021-22|All|||||| |Toyota|Corolla 2020-22|All|||||| @@ -69,14 +68,13 @@ How We Rate The Cars |Toyota|RAV4 2019-21|All|||||| |Toyota|RAV4 Hybrid 2019-21|All|||||| -# Silver - 78 cars +# Silver - 75 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| |Audi|A3 2014-19|ACC + Lane Assist|||||| |Audi|A3 Sportback e-tron 2017-18|ACC + Lane Assist|||||| |Audi|Q2 2018|ACC + Lane Assist|||||| -|Audi|Q3 2020-21|ACC + Lane Assist|||||| |Audi|RS3 2018|ACC + Lane Assist|||||| |Audi|S3 2015-17|ACC + Lane Assist|||||| |Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise|||||| @@ -93,7 +91,6 @@ How We Rate The Cars |Hyundai|Santa Fe 2021-22|All|||||| |Hyundai|Santa Fe Hybrid 2022|All|||||| |Hyundai|Santa Fe Plug-in Hybrid 2022|All|||||| -|Hyundai|Sonata 2018-19|SCC + LKAS|||||| |Hyundai|Tucson Diesel 2019|SCC + LKAS|||||| |Kia|Ceed 2019|SCC + LKAS|||||| |Kia|Forte 2018|SCC + LKAS|||||| @@ -106,15 +103,16 @@ How We Rate The Cars |Kia|Sorento 2018|SCC + LKAS|||||| |Kia|Sorento 2019|SCC + LKAS|||||| |Kia|Stinger 2018|SCC + LKAS|||||| -|Lexus|ES Hybrid 2017-18|LSS|[3](#footnotes)||||| |Lexus|NX 2018-19|All|[3](#footnotes)||||| |Lexus|NX Hybrid 2018-19|All|[3](#footnotes)||||| -|Lexus|RX 2020-22|All|||||| +|Lexus|NX Hybrid 2020|All|||||| |Lexus|RX Hybrid 2020-21|All|||||| |Mazda|CX-5 2022|All|||||| |SEAT|Ateca 2018|Driver Assistance|||||| |SEAT|Leon 2014-20|Driver Assistance|||||| +|Subaru|Crosstrek 2020-21|EyeSight|||||| |Subaru|Forester 2019-21|All|||||| +|Subaru|Impreza 2020-21|EyeSight|||||| |Škoda|Kamiq 2021[5](#footnotes)|Driver Assistance|||||| |Škoda|Karoq 2019|Driver Assistance|||||| |Škoda|Kodiaq 2018-19|Driver Assistance|||||| @@ -125,18 +123,17 @@ How We Rate The Cars |Toyota|Alphard 2019-20|All|||||| |Toyota|Alphard Hybrid 2021|All|||||| |Toyota|Avalon 2019-21|TSS-P|[3](#footnotes)||||| -|Toyota|Avalon Hybrid 2019-21|TSS-P|[3](#footnotes)||||| +|Toyota|Avalon Hybrid 2022|All|||||| |Toyota|Camry 2018-20|All||[4](#footnotes)|||| |Toyota|Camry Hybrid 2018-20|All||[4](#footnotes)|||| |Toyota|Highlander 2017-19|All|[3](#footnotes)||||| |Toyota|Highlander Hybrid 2017-19|All|[3](#footnotes)||||| |Toyota|Prius 2016-20|TSS-P|[3](#footnotes)||||| |Toyota|Prius Prime 2017-20|All|[3](#footnotes)||||| -|Toyota|RAV4 2022|All|||||| |Toyota|RAV4 Hybrid 2016-18|TSS-P|[3](#footnotes)||||| |Toyota|RAV4 Hybrid 2022|All|||||| |Toyota|Sienna 2018-20|All|[3](#footnotes)||||| -|Volkswagen|Arteon 2018, 2021[7](#footnotes)|Driver Assistance|||||| +|Volkswagen|Atlas 2018-19, 2022[7](#footnotes)|Driver Assistance|||||| |Volkswagen|e-Golf 2014, 2018-20|Driver Assistance|||||| |Volkswagen|Golf 2015-20|Driver Assistance|||||| |Volkswagen|Golf Alltrack 2017-18|Driver Assistance|||||| @@ -145,57 +142,59 @@ How We Rate The Cars |Volkswagen|Golf R 2016-19|Driver Assistance|||||| |Volkswagen|Golf SportsVan 2016|Driver Assistance|||||| |Volkswagen|Golf SportWagen 2015|Driver Assistance|||||| -|Volkswagen|Passat 2015-19[6](#footnotes)|Driver Assistance|||||| |Volkswagen|Polo 2020|Driver Assistance|||||| |Volkswagen|T-Cross 2021[7](#footnotes)|Driver Assistance|||||| |Volkswagen|T-Roc 2021[7](#footnotes)|Driver Assistance|||||| |Volkswagen|Taos 2022[7](#footnotes)|Driver Assistance|||||| |Volkswagen|Touran 2017|Driver Assistance|||||| -# Bronze - 66 cars +# Bronze - 70 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| |Acura|ILX 2016-19|AcuraWatch Plus|||||| |Acura|RDX 2016-18|AcuraWatch Plus|||||| -|Acura|RDX 2019-21|All|||||| +|Acura|RDX 2019-21|All|||||| +|Audi|Q3 2020-21|ACC + Lane Assist|||||| |Cadillac|Escalade ESV 2016[1](#footnotes)|ACC + LKAS|||||| -|Chrysler|Pacifica 2017-18|Adaptive Cruise|||||| -|Chrysler|Pacifica 2020|Adaptive Cruise|||||| +|Chrysler|Pacifica 2017-18|Adaptive Cruise|||||| +|Chrysler|Pacifica 2020|Adaptive Cruise|||||| |Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise|||||| -|Chrysler|Pacifica Hybrid 2019-21|Adaptive Cruise|||||| +|Chrysler|Pacifica Hybrid 2019-21|Adaptive Cruise|||||| |Genesis|G90 2018|All|||||| |GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise|||||| -|Honda|Accord 2018-21|All|||||| -|Honda|Accord Hybrid 2018-21|All|||||| +|Honda|Accord 2018-21|All|||||| +|Honda|Accord Hybrid 2018-21|All|||||| |Honda|Civic 2016-18|Honda Sensing|||||| -|Honda|Civic 2019-20|All|||[2](#footnotes)||| -|Honda|Civic Hatchback 2017-21|Honda Sensing|||||| +|Honda|Civic 2019-20|All|||[2](#footnotes)||| +|Honda|Civic Hatchback 2017-21|Honda Sensing|||||| |Honda|CR-V 2015-16|Touring|||||| -|Honda|CR-V 2017-21|Honda Sensing|||||| +|Honda|CR-V 2017-21|Honda Sensing|||||| |Honda|CR-V Hybrid 2017-19|Honda Sensing|||||| |Honda|e 2020|All|||||| -|Honda|Fit 2018-19|Honda Sensing|||||| +|Honda|Fit 2018-19|Honda Sensing|||||| |Honda|Freed 2020|Honda Sensing|||||| |Honda|HR-V 2019-20|Honda Sensing|||||| -|Honda|Insight 2019-21|All|||||| -|Honda|Inspire 2018|All|||||| +|Honda|Insight 2019-21|All|||||| +|Honda|Inspire 2018|All|||||| |Honda|Odyssey 2018-20|Honda Sensing|||||| -|Honda|Passport 2019-21|All|||||| -|Honda|Pilot 2016-21|Honda Sensing|||||| -|Honda|Ridgeline 2017-22|Honda Sensing|||||| +|Honda|Passport 2019-21|All|||||| +|Honda|Pilot 2016-21|Honda Sensing|||||| +|Honda|Ridgeline 2017-22|Honda Sensing|||||| |Hyundai|Elantra 2017-19|SCC + LKAS|||||| |Hyundai|Genesis 2015-16|SCC + LKAS|||||| |Hyundai|Ioniq Electric 2019|SCC + LKAS|||||| |Hyundai|Ioniq Hybrid 2017-19|SCC + LKAS|||||| |Hyundai|Ioniq Plug-in Hybrid 2019|SCC + LKAS|||||| +|Hyundai|Sonata 2018-19|SCC + LKAS|||||| |Hyundai|Tucson 2021|SCC + LKAS|||||| |Hyundai|Veloster 2019-20|SCC + LKAS|||||| |Jeep|Grand Cherokee 2016-18|Adaptive Cruise|||||| -|Jeep|Grand Cherokee 2019-20|Adaptive Cruise|||||| +|Jeep|Grand Cherokee 2019-20|Adaptive Cruise|||||| |Kia|Niro Plug-in Hybrid 2019|SCC + LKAS|||||| |Kia|Optima 2017|SCC + LKAS|||||| |Lexus|CT Hybrid 2017-18|LSS|[3](#footnotes)||||| +|Lexus|ES Hybrid 2017-18|LSS|[3](#footnotes)||||| |Lexus|IS 2017-19|All|||||| |Lexus|RC 2020|All|||||| |Lexus|RX 2016-18|All|[3](#footnotes)||||| @@ -207,20 +206,21 @@ How We Rate The Cars |Nissan|X-Trail 2017|ProPILOT|||||| |Subaru|Ascent 2019-20|All|||||| |Subaru|Crosstrek 2018-19|EyeSight|||||| -|Subaru|Crosstrek 2020-21|EyeSight|||||| |Subaru|Impreza 2017-19|EyeSight|||||| -|Subaru|Impreza 2020-21|EyeSight|||||| -|Toyota|Avalon 2016-18|TSS-P|[3](#footnotes)||||| +|Toyota|Avalon 2016-18|TSS-P|[3](#footnotes)||||| +|Toyota|Avalon Hybrid 2019-21|TSS-P|[3](#footnotes)||||| |Toyota|C-HR 2017-21|All|||||| -|Toyota|C-HR Hybrid 2017-19|All|||||| +|Toyota|C-HR Hybrid 2017-19|All|||||| |Toyota|Corolla 2017-19|All|[3](#footnotes)||||| |Toyota|Prius v 2017|TSS-P|[3](#footnotes)||||| |Toyota|RAV4 2016-18|TSS-P|[3](#footnotes)||||| -|Volkswagen|Atlas 2018-19, 2022[7](#footnotes)|Driver Assistance|||||| +|Toyota|RAV4 2022|All|||||| +|Volkswagen|Arteon 2018, 2021[7](#footnotes)|Driver Assistance|||||| |Volkswagen|California 2021[7](#footnotes)|Driver Assistance|||||| |Volkswagen|Caravelle 2020[7](#footnotes)|Driver Assistance|||||| |Volkswagen|Jetta 2018-21|Driver Assistance|||||| |Volkswagen|Jetta GLI 2021|Driver Assistance|||||| +|Volkswagen|Passat 2015-19[6](#footnotes)|Driver Assistance|||||| |Volkswagen|Tiguan 2019-22[7](#footnotes)|Driver Assistance|||||| diff --git a/release/files_common b/release/files_common index ceb0110606..5230511ddd 100644 --- a/release/files_common +++ b/release/files_common @@ -104,6 +104,7 @@ selfdrive/car/fw_versions.py selfdrive/car/isotp_parallel_query.py selfdrive/car/tests/__init__.py selfdrive/car/tests/test_car_interfaces.py +selfdrive/car/torque_data.json selfdrive/car/body/*.py selfdrive/car/chrysler/*.py diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index e47b085533..55672dd4ab 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -23,14 +23,6 @@ class CarInterface(CarInterfaceBase): ret.steerRateCost = 0.7 ret.steerLimitTimer = 0.4 - # set max lateral acceleration - if candidate in (CAR.PACIFICA_2018, CAR.PACIFICA_2019_HYBRID, CAR.JEEP_CHEROKEE, CAR.JEEP_CHEROKEE_2019): - ret.maxLateralAccel = 1.6 - if candidate in (CAR.PACIFICA_2018_HYBRID,): - ret.maxLateralAccel = 1.4 - if candidate in (CAR.PACIFICA_2017_HYBRID,): - ret.maxLateralAccel = 1.2 - if candidate in (CAR.JEEP_CHEROKEE, CAR.JEEP_CHEROKEE_2019): ret.wheelbase = 2.91 # in meters ret.steerRatio = 12.7 diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index e3b46c29e4..3700a24835 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -7,7 +7,7 @@ from enum import Enum from typing import Dict, List, Optional, Union, no_type_check TACO_TORQUE_THRESHOLD = 2.5 # m/s^2 -GREAT_TORQUE_THRESHOLD = 1.5 # m/s^2 +GREAT_TORQUE_THRESHOLD = 1.4 # m/s^2 GOOD_TORQUE_THRESHOLD = 1.0 # m/s^2 diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index bc43086586..498f4b3347 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -83,7 +83,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 17.7 # Stock 15.7, LiveParameters tire_stiffness_factor = 0.469 # Stock Michelin Energy Saver A/S, LiveParameters ret.centerToFront = ret.wheelbase * 0.45 # Volt Gen 1, TODO corner weigh - ret.maxLateralAccel = 1.6 ret.lateralTuning.pid.kpBP = [0., 40.] ret.lateralTuning.pid.kpV = [0., 0.17] @@ -111,7 +110,6 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.86 ret.steerRatio = 14.4 # end to end is 13.46 ret.centerToFront = ret.wheelbase * 0.4 - ret.maxLateralAccel = 1.4 ret.lateralTuning.pid.kf = 1. # get_steer_feedforward_acadia() elif candidate == CAR.BUICK_REGAL: diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index de5db98ea6..ea7deab5d7 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -100,7 +100,6 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560, 8000], [0, 2560, 3840]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.1]] else: - ret.maxLateralAccel = 0.4 ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560], [0, 2560]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[1.1], [0.33]] tire_stiffness_factor = 1. @@ -113,7 +112,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 15.38 # 10.93 is end-to-end spec ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 1. - ret.maxLateralAccel = 1.6 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] elif candidate in (CAR.ACCORD, CAR.ACCORDH): @@ -128,7 +126,6 @@ class CarInterface(CarInterfaceBase): if eps_modified: ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.09]] else: - ret.maxLateralAccel = 1.6 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] elif candidate == CAR.ACURA_ILX: @@ -165,7 +162,6 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560, 10000], [0, 2560, 3840]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.21], [0.07]] else: - ret.maxLateralAccel = 1.7 ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.64], [0.192]] tire_stiffness_factor = 0.677 @@ -190,7 +186,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.06 ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.75 - ret.maxLateralAccel = 1.7 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] elif candidate == CAR.FREED: @@ -222,7 +217,6 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.38 ret.steerRatio = 15.0 # as spec tire_stiffness_factor = 0.444 - ret.maxLateralAccel = 0.9 ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] @@ -232,7 +226,6 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.75 ret.centerToFront = ret.wheelbase * 0.41 ret.steerRatio = 11.95 # as spec - ret.maxLateralAccel = 1.2 ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.06]] tire_stiffness_factor = 0.677 @@ -245,7 +238,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.35 # as spec ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.82 - ret.maxLateralAccel = 0.8 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] elif candidate == CAR.ODYSSEY_CHN: @@ -266,7 +258,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 17.25 # as spec ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.444 - ret.maxLateralAccel = 1.5 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] elif candidate == CAR.RIDGELINE: @@ -277,7 +268,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 15.59 # as spec ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.444 - ret.maxLateralAccel = 1.3 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] elif candidate == CAR.INSIGHT: @@ -288,7 +278,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 15.0 # 12.58 is spec end-to-end ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.82 - ret.maxLateralAccel = 1.4 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] elif candidate == CAR.HONDA_E: diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 831b318d55..08af654996 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -63,7 +63,6 @@ class CarInterface(CarInterfaceBase): # Values from optimizer ret.steerRatio = 16.55 # 13.8 is spec end-to-end tire_stiffness_factor = 0.82 - ret.maxLateralAccel = 3.2 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[9., 22.], [9., 22.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.35], [0.05, 0.09]] elif candidate in (CAR.SONATA, CAR.SONATA_HYBRID): @@ -72,7 +71,6 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.84 ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable tire_stiffness_factor = 0.65 - ret.maxLateralAccel = 2.5 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.SONATA_LF: @@ -80,7 +78,6 @@ class CarInterface(CarInterfaceBase): ret.mass = 4497. * CV.LB_TO_KG ret.wheelbase = 2.804 ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable - ret.maxLateralAccel = 1.8 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.PALISADE: @@ -89,7 +86,6 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.90 ret.steerRatio = 15.6 * 1.15 tire_stiffness_factor = 0.63 - ret.maxLateralAccel = 2.5 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.05]] elif candidate in (CAR.ELANTRA, CAR.ELANTRA_GT_I30): @@ -146,7 +142,6 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.7 ret.steerRatio = 13.73 # Spec tire_stiffness_factor = 0.385 - ret.maxLateralAccel = 3.0 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] if candidate not in (CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.IONIQ_HEV_2022): @@ -196,7 +191,6 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.7 ret.steerRatio = 13.9 if CAR.KIA_NIRO_HEV_2021 else 13.73 # Spec tire_stiffness_factor = 0.385 - ret.maxLateralAccel = 2.9 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] if candidate == CAR.KIA_NIRO_HEV: @@ -228,7 +222,6 @@ class CarInterface(CarInterfaceBase): ret.mass = 1825. + STD_CARGO_KG ret.wheelbase = 2.78 ret.steerRatio = 14.4 * 1.15 # 15% higher at the center seems reasonable - ret.maxLateralAccel = 2.4 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.KIA_FORTE: @@ -254,7 +247,6 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.85 ret.steerRatio = 13.27 # 2021 Kia K5 Steering Ratio (all trims) tire_stiffness_factor = 0.5 - ret.maxLateralAccel = 2.1 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.KIA_EV6: diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index a2c11bf023..9220aee522 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -1,3 +1,4 @@ +import json import os import time from abc import abstractmethod, ABC @@ -19,6 +20,7 @@ EventName = car.CarEvent.EventName MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS ACCEL_MAX = 2.0 ACCEL_MIN = -3.5 +TORQUE_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data.json') # generic car and radar interfaces @@ -81,7 +83,7 @@ class CarInterfaceBase(ABC): ret.steerControlType = car.CarParams.SteerControlType.torque ret.minSteerSpeed = 0. ret.wheelSpeedFactor = 1.0 - ret.maxLateralAccel = float('nan') + ret.maxLateralAccel = CarInterfaceBase.get_torque_params(candidate)['MAX_LAT_ACCEL_MEASURED'] ret.pcmCruise = True # openpilot's state is tied to the PCM's cruise state on most cars ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this @@ -105,6 +107,12 @@ class CarInterfaceBase(ABC): ret.steerLimitTimer = 1.0 return ret + @staticmethod + def get_torque_params(candidate, default=float('NaN')): + with open(TORQUE_PARAMS_PATH) as f: + data = json.load(f) + return {key: data[key].get(candidate, default) for key in data} + @abstractmethod def _update(self, c: car.CarControl) -> car.CarState: pass diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index edd26a4449..d0d8e91ce1 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -51,7 +51,6 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.5 ret.steerRatio = 17 # learned, 14 stock ret.steerActuatorDelay = 0.1 - ret.maxLateralAccel = 1.3 ret.lateralTuning.pid.kf = 0.00005 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.045, 0.042, 0.20], [0.04, 0.035, 0.045]] @@ -62,7 +61,6 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.5 ret.steerRatio = 17 # learned, 14 stock ret.steerActuatorDelay = 0.1 - ret.maxLateralAccel = 3.2 ret.lateralTuning.pid.kf = 0.000038 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01, 0.065, 0.2], [0.001, 0.015, 0.025]] diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index 92024ab0c2..52c89440c7 100755 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +import math import unittest import importlib from parameterized import parameterized @@ -39,7 +40,9 @@ class TestCarInterfaces(unittest.TestCase): if tuning == 'pid': self.assertTrue(len(car_params.lateralTuning.pid.kpV)) elif tuning == 'torque': - self.assertTrue(car_params.lateralTuning.torque.kf > 0) + kf = car_params.lateralTuning.torque.kf + self.assertTrue(not math.isnan(kf) and kf > 0) + self.assertTrue(not math.isnan(car_params.lateralTuning.torque.friction)) elif tuning == 'indi': self.assertTrue(len(car_params.lateralTuning.indi.outerLoopGainV)) diff --git a/selfdrive/car/tests/test_docs.py b/selfdrive/car/tests/test_docs.py index fed6989d40..b4bc14ef00 100755 --- a/selfdrive/car/tests/test_docs.py +++ b/selfdrive/car/tests/test_docs.py @@ -3,6 +3,7 @@ import unittest from selfdrive.car.car_helpers import interfaces, get_interface_attr from selfdrive.car.docs import CARS_MD_OUT, CARS_MD_TEMPLATE, generate_cars_md, get_all_car_info +from selfdrive.car.docs_definitions import Column, Star class TestCarDocs(unittest.TestCase): @@ -37,6 +38,11 @@ class TestCarDocs(unittest.TestCase): if "rav4" in tokens: self.assertIn("RAV4", car.model, "Use correct capitalization") + def test_torque_star(self): + for car in self.all_cars: + if car.car_name == "honda": + self.assertTrue(car.row[Column.STEERING_TORQUE] in (Star.EMPTY, Star.HALF), f"{car.name} has full torque star") + if __name__ == "__main__": unittest.main() diff --git a/selfdrive/car/torque_data.json b/selfdrive/car/torque_data.json new file mode 100644 index 0000000000..63ee0e9bcd --- /dev/null +++ b/selfdrive/car/torque_data.json @@ -0,0 +1 @@ +{"LAT_ACCEL_FACTOR": {"HONDA PILOT 2017": 1.682289482065265, "HONDA CIVIC 2016": 1.5248128495527884, "TOYOTA CAMRY 2018": 2.1115709806216447, "TOYOTA COROLLA HYBRID TSS2 2019": 2.3250600977240077, "TOYOTA RAV4 2019": 2.625504029066767, "HYUNDAI PALISADE 2020": 2.5250855675875634, "TOYOTA SIENNA 2018": 1.8254254785341577, "ACURA RDX 2020": 1.3998101622214894, "TOYOTA RAV4 2017": 1.948190869577896, "HONDA RIDGELINE 2017": 1.4158181862793415, "TOYOTA PRIUS 2017": 1.9142926195557595, "TOYOTA HIGHLANDER HYBRID 2020": 2.1097056247344392, "HYUNDAI SONATA 2020": 3.2488989629905944, "KIA STINGER GT2 2018": 2.7592622336517834, "TOYOTA HIGHLANDER 2020": 2.0408544157877055, "HONDA ACCORD 2018": 1.6374118241564064, "TOYOTA PRIUS TSS2 2021": 2.3207270770298365, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 1.46050785084946, "LEXUS NX 2020": 2.29533657249232, "TOYOTA RAV4 HYBRID 2019": 2.4003012079562085, "HONDA CIVIC (BOSCH) 2019": 1.6523031416671652, "KIA NIRO HYBRID 2021": 2.743464625803003, "HONDA ACCORD HYBRID 2018": 1.5904016830979033, "LEXUS NX HYBRID 2018": 2.398678119681945, "TOYOTA COROLLA TSS2 2019": 2.3859244449846466, "VOLKSWAGEN ARTEON 1ST GEN": 1.4249208219414902, "TOYOTA CAMRY HYBRID 2021": 2.5434553806317055, "VOLKSWAGEN JETTA 7TH GEN": 1.2228130240634283, "HONDA INSIGHT 2019": 1.468352089969897, "SUBARU FORESTER 2019": 3.6185035528523546, "HYUNDAI ELANTRA 2021": 3.5294999663335185, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 2.2179616966432905, "HYUNDAI KONA HYBRID 2020": 4.493208192966529, "HONDA ODYSSEY 2018": 1.8838175399087222, "LEXUS RX 2016": 1.3912132245094184, "TOYOTA COROLLA 2017": 3.0143547548384735, "LEXUS ES 2019": 2.012201253045193, "HYUNDAI SANTA FE 2019": 3.039728566484244, "TOYOTA AVALON 2022": 2.4619858654670885, "JEEP GRAND CHEROKEE V6 2018": 1.8411674990629987, "CHEVROLET VOLT PREMIER 2017": 1.5943438675127841, "TOYOTA RAV4 HYBRID 2017": 1.9803053616868995, "LEXUS RX 2020": 1.664616846377383, "TOYOTA HIGHLANDER HYBRID 2018": 1.8866764457400844, "TOYOTA CAMRY HYBRID 2018": 2.014213351947917, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 1.4428896585442685, "TOYOTA MIRAI 2021": 2.7217623852898853, "LEXUS IS 2018": 3.5624668608596837, "TOYOTA HIGHLANDER 2017": 1.9199133105823853, "HYUNDAI SONATA HYBRID 2021": 2.7313907441569554, "VOLKSWAGEN ATLAS 1ST GEN": 1.4483948408160645, "LEXUS ES HYBRID 2019": 2.4138026617523547, "HYUNDAI GENESIS 2015-2016": 1.7636839808044658, "JEEP GRAND CHEROKEE 2019": 1.787264083939164, "SUBARU ASCENT LIMITED 2019": 3.0494069339774565, "HONDA CR-V 2017": 1.9828470679233807, "HONDA FIT 2018": 1.594940026552055, "TOYOTA CAMRY 2021": 2.5057990840460342, "AUDI Q3 2ND GEN": 1.4558300885316715, "AUDI A3 3RD GEN": 1.5304173783542625, "LEXUS RX HYBRID 2017": 1.577216425446677, "HONDA CIVIC 2022": 2.69252285552613, "GENESIS G70 2018": 3.866842361627636, "CHRYSLER PACIFICA HYBRID 2018": 1.5771851419640903, "VOLKSWAGEN PASSAT 8TH GEN": 1.2985597059739313, "HONDA CR-V 2016": 0.7745984062630755, "HYUNDAI IONIQ PHEV 2020": 2.5696218908589383, "GMC ACADIA DENALI 2018": 1.3310088601868082, "HYUNDAI SONATA 2019": 1.9736552675022665, "TOYOTA AVALON 2019": 1.7245149905226294, "TOYOTA C-HR 2018": 1.5895016960662856, "HONDA CR-V HYBRID 2019": 2.0687746810729193, "CHRYSLER PACIFICA 2020": 1.40536880000744, "HYUNDAI IONIQ ELECTRIC 2020": 3.3220838625838667, "VOLKSWAGEN TIGUAN 2ND GEN": NaN, "LEXUS NX 2018": 1.7753192756242595, "KIA OPTIMA SX 2019 & 2016": 3.12625562280304, "TOYOTA AVALON HYBRID 2019": 1.7681286449373381, "TOYOTA RAV4 HYBRID 2022": 2.5518187542231816, "HONDA PASSPORT 2021": 1.5174924139130355, "KIA K5 2021": 2.482916204106975, "ACURA ILX 2016": 1.5237423964720282, "HYUNDAI IONIQ HYBRID 2017-2019": 2.3723887901632645, "KIA NIRO EV 2020": 2.924651969180446, "SUBARU IMPREZA SPORT 2020": 2.5317689549587694, "CHRYSLER PACIFICA HYBRID 2017": 1.167126725149114, "HYUNDAI KONA ELECTRIC 2019": 4.201092987427836, "HYUNDAI ELANTRA HYBRID 2021": 3.7153193626001926, "HYUNDAI SANTA FE HYBRID 2022": 3.3049230586030545, "CHRYSLER PACIFICA 2018": 1.524867383058782, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": 2.5970979517766213, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 1.5460982690267173, "MAZDA CX-9 2021": 1.9514800984278198, "HYUNDAI SANTA FE 2022": 3.5354982200434524, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 1.8902492836532216, "HONDA HRV 2019": 2.1262957371020352, "TOYOTA AVALON HYBRID 2022": 2.4142150048378683, "SUBARU IMPREZA LIMITED 2019": 1.2203463907025918, "GENESIS G80 2017": 2.4086794443413906, "VOLKSWAGEN TAOS 1ST GEN": 2.0031666974545947, "KIA FORTE E 2018 & GT 2021": 2.022553820222557, "CADILLAC ESCALADE ESV 2016": 1.5522339636408988, "TOYOTA C-HR 2021": 1.6519334844316687, "TOYOTA C-HR HYBRID 2018": 1.3193315010905482}, "MAX_LAT_ACCEL_MEASURED": {"HONDA PILOT 2017": 0.9069354290994807, "HONDA CIVIC 2016": 0.4030275472529351, "TOYOTA CAMRY 2018": 1.686123168195758, "TOYOTA COROLLA HYBRID TSS2 2019": 1.9139332621491167, "TOYOTA RAV4 2019": 2.234047196286479, "HYUNDAI PALISADE 2020": 1.8303582523301922, "TOYOTA SIENNA 2018": 1.4752503435300715, "ACURA RDX 2020": 0.40911581320000334, "TOYOTA RAV4 2017": 1.6622227720995595, "HONDA RIDGELINE 2017": 0.8224685813281227, "TOYOTA PRIUS 2017": 1.4548827870876067, "TOYOTA HIGHLANDER HYBRID 2020": 2.0649784271823037, "HYUNDAI SONATA 2020": 2.243989856570093, "KIA STINGER GT2 2018": 1.9531287107084392, "TOYOTA HIGHLANDER 2020": 1.659381392090836, "HONDA ACCORD 2018": 0.40486739531686267, "TOYOTA PRIUS TSS2 2021": 1.861541601048098, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 1.1930739374812243, "LEXUS NX 2020": 1.565268724838564, "TOYOTA RAV4 HYBRID 2019": 2.0915384047218426, "HONDA CIVIC (BOSCH) 2019": 0.4062886118517984, "KIA NIRO HYBRID 2021": NaN, "HONDA ACCORD HYBRID 2018": 0.35128914564548286, "LEXUS NX HYBRID 2018": 1.81821359787186, "TOYOTA COROLLA TSS2 2019": 1.911280958056631, "VOLKSWAGEN ARTEON 1ST GEN": 1.2587939472578302, "TOYOTA CAMRY HYBRID 2021": 2.312510643730013, "VOLKSWAGEN JETTA 7TH GEN": 1.232161945396623, "HONDA INSIGHT 2019": 0.5174836462945298, "SUBARU FORESTER 2019": 2.29255993930968, "HYUNDAI ELANTRA 2021": NaN, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 2.133978602602408, "HYUNDAI KONA HYBRID 2020": NaN, "HONDA ODYSSEY 2018": 0.8254773781363679, "LEXUS RX 2016": 1.0954776820595344, "TOYOTA COROLLA 2017": 2.2012870528168964, "LEXUS ES 2019": 2.069508805495439, "HYUNDAI SANTA FE 2019": 2.3763720477660253, "TOYOTA AVALON 2022": 2.531962323786023, "JEEP GRAND CHEROKEE V6 2018": 1.4193323242487865, "CHEVROLET VOLT PREMIER 2017": 1.8576430337666092, "TOYOTA RAV4 HYBRID 2017": 1.7425797219020926, "LEXUS RX 2020": 1.5118835180227874, "TOYOTA HIGHLANDER HYBRID 2018": 1.6872527654528833, "TOYOTA CAMRY HYBRID 2018": 1.6793468378089895, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 1.5614447712441282, "TOYOTA MIRAI 2021": 2.271146483563897, "LEXUS IS 2018": NaN, "TOYOTA HIGHLANDER 2017": 1.6573774863189379, "HYUNDAI SONATA HYBRID 2021": 1.9464120717803253, "VOLKSWAGEN ATLAS 1ST GEN": 1.6867005451451638, "LEXUS ES HYBRID 2019": 1.956450687999482, "HYUNDAI GENESIS 2015-2016": 1.5359761378898085, "JEEP GRAND CHEROKEE 2019": 1.2418961305308847, "SUBARU ASCENT LIMITED 2019": NaN, "HONDA CR-V 2017": 0.2642062271814174, "HONDA FIT 2018": 0.5896345937094754, "TOYOTA CAMRY 2021": 2.1783533980215166, "AUDI Q3 2ND GEN": 1.1582239457022647, "AUDI A3 3RD GEN": 1.598699116126939, "LEXUS RX HYBRID 2017": 1.319771127672888, "HONDA CIVIC 2022": 1.1806949852580793, "GENESIS G70 2018": 2.2496820850331134, "CHRYSLER PACIFICA HYBRID 2018": 1.294798200968084, "VOLKSWAGEN PASSAT 8TH GEN": 1.247540921731637, "HONDA CR-V 2016": 0.6991119250342539, "HYUNDAI IONIQ PHEV 2020": 1.9062392690595655, "GMC ACADIA DENALI 2018": 1.2986994230652662, "HYUNDAI SONATA 2019": 1.257445187146704, "TOYOTA AVALON 2019": 1.664577368475227, "TOYOTA C-HR 2018": 1.308490445144888, "HONDA CR-V HYBRID 2019": 0.4693072746041504, "CHRYSLER PACIFICA 2020": 1.1712413003138664, "HYUNDAI IONIQ ELECTRIC 2020": NaN, "VOLKSWAGEN TIGUAN 2ND GEN": 1.1573057001955744, "LEXUS NX 2018": 1.9457312007432144, "KIA OPTIMA SX 2019 & 2016": 2.0928228595938845, "TOYOTA AVALON HYBRID 2019": NaN, "TOYOTA RAV4 HYBRID 2022": 1.7647290773049569, "HONDA PASSPORT 2021": 0.8248357750132685, "KIA K5 2021": 1.4628018983720577, "ACURA ILX 2016": 0.6330753921140401, "HYUNDAI IONIQ HYBRID 2017-2019": NaN, "KIA NIRO EV 2020": 2.020186575503497, "SUBARU IMPREZA SPORT 2020": 2.136786720514988, "CHRYSLER PACIFICA HYBRID 2017": 1.0642918033307907, "HYUNDAI KONA ELECTRIC 2019": NaN, "HYUNDAI ELANTRA HYBRID 2021": NaN, "HYUNDAI SANTA FE HYBRID 2022": NaN, "CHRYSLER PACIFICA 2018": 1.3654603720349934, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": NaN, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 1.255230465866663, "MAZDA CX-9 2021": NaN, "HYUNDAI SANTA FE 2022": 3.3823387508235827, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 1.544104124172169, "HONDA HRV 2019": 0.7492792210307291, "TOYOTA AVALON HYBRID 2022": NaN, "SUBARU IMPREZA LIMITED 2019": 0.8127509604734238, "GENESIS G80 2017": NaN, "VOLKSWAGEN TAOS 1ST GEN": 1.6590543949912684, "KIA FORTE E 2018 & GT 2021": 2.3970573789339786, "CADILLAC ESCALADE ESV 2016": NaN, "TOYOTA C-HR 2021": 1.3559230155096402, "TOYOTA C-HR HYBRID 2018": 0.8910235787356033}, "FRICTION": {"HONDA PILOT 2017": 0.2168217463499328, "HONDA CIVIC 2016": 0.28406761310944795, "TOYOTA CAMRY 2018": 0.1327947477896041, "TOYOTA COROLLA HYBRID TSS2 2019": 0.21792021497538405, "TOYOTA RAV4 2019": 0.12757022360707945, "HYUNDAI PALISADE 2020": 0.13391574986922777, "TOYOTA SIENNA 2018": 0.1853443239485906, "ACURA RDX 2020": 0.18058553315570297, "TOYOTA RAV4 2017": 0.14319170324556796, "HONDA RIDGELINE 2017": 0.2380553573913589, "TOYOTA PRIUS 2017": 0.2079869382946584, "TOYOTA HIGHLANDER HYBRID 2020": 0.14038812589302646, "HYUNDAI SONATA 2020": 0.08266051305053168, "KIA STINGER GT2 2018": 0.11909534626930472, "TOYOTA HIGHLANDER 2020": 0.14658637853444048, "HONDA ACCORD 2018": 0.21616610462729247, "TOYOTA PRIUS TSS2 2021": 0.20613763260512002, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 0.16250373743651828, "LEXUS NX 2020": 0.14404022591302845, "TOYOTA RAV4 HYBRID 2019": 0.1319247989758836, "HONDA CIVIC (BOSCH) 2019": 0.2575217845562353, "KIA NIRO HYBRID 2021": 0.14468633728800306, "HONDA ACCORD HYBRID 2018": 0.21150723931119184, "LEXUS NX HYBRID 2018": 0.16117151597250162, "TOYOTA COROLLA TSS2 2019": 0.21045927995242877, "VOLKSWAGEN ARTEON 1ST GEN": 0.17828895368353925, "TOYOTA CAMRY HYBRID 2021": 0.16283734136957057, "VOLKSWAGEN JETTA 7TH GEN": 0.19508489725001105, "HONDA INSIGHT 2019": 0.25750800088299297, "SUBARU FORESTER 2019": 0.11783702069698135, "HYUNDAI ELANTRA 2021": 0.09377564130711125, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 0.14740189509875762, "HYUNDAI KONA HYBRID 2020": 0.0863709736632968, "HONDA ODYSSEY 2018": 0.2125595696498247, "LEXUS RX 2016": 0.21475140622981923, "TOYOTA COROLLA 2017": 0.12325064090161544, "LEXUS ES 2019": 0.12757526660498053, "HYUNDAI SANTA FE 2019": 0.12230125806479573, "TOYOTA AVALON 2022": 0.11030226705639488, "JEEP GRAND CHEROKEE V6 2018": 0.12871972792344108, "CHEVROLET VOLT PREMIER 2017": 0.16697256960295873, "TOYOTA RAV4 HYBRID 2017": 0.14074453855329072, "LEXUS RX 2020": 0.2249895411716623, "TOYOTA HIGHLANDER HYBRID 2018": 0.16692807938039034, "TOYOTA CAMRY HYBRID 2018": 0.13418904852016877, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 0.19324413131475543, "TOYOTA MIRAI 2021": 0.20035237756713503, "LEXUS IS 2018": 0.073103111226694, "TOYOTA HIGHLANDER 2017": 0.17502689439420385, "HYUNDAI SONATA HYBRID 2021": 0.09518615688045734, "VOLKSWAGEN ATLAS 1ST GEN": 0.12761803335799474, "LEXUS ES HYBRID 2019": 0.1682771025433274, "HYUNDAI GENESIS 2015-2016": 0.10254237048034251, "JEEP GRAND CHEROKEE 2019": 0.15702739382013717, "SUBARU ASCENT LIMITED 2019": 0.12936982863095342, "HONDA CR-V 2017": 0.22518506713451308, "HONDA FIT 2018": 0.10803295063463647, "TOYOTA CAMRY 2021": 0.15512845523424743, "AUDI Q3 2ND GEN": 0.14083949977629878, "AUDI A3 3RD GEN": 0.1611945965384188, "LEXUS RX HYBRID 2017": 0.19322020114452776, "HONDA CIVIC 2022": 0.24279247053469405, "GENESIS G70 2018": 0.06869638264150804, "CHRYSLER PACIFICA HYBRID 2018": 0.13887505891474383, "VOLKSWAGEN PASSAT 8TH GEN": 0.21714039653367842, "HONDA CR-V 2016": 0.41726236462791455, "HYUNDAI IONIQ PHEV 2020": 0.13800461817330806, "GMC ACADIA DENALI 2018": 0.3447163106452739, "HYUNDAI SONATA 2019": 0.15371520337813344, "TOYOTA AVALON 2019": 0.10392921606262978, "TOYOTA C-HR 2018": 0.2015190716953846, "HONDA CR-V HYBRID 2019": 0.19595630321202379, "CHRYSLER PACIFICA 2020": 0.14337114313208268, "HYUNDAI IONIQ ELECTRIC 2020": 0.08104502306679212, "VOLKSWAGEN TIGUAN 2ND GEN": NaN, "LEXUS NX 2018": 0.1471001686544422, "KIA OPTIMA SX 2019 & 2016": 0.11703652166984638, "TOYOTA AVALON HYBRID 2019": 0.10863628402866225, "TOYOTA RAV4 HYBRID 2022": 0.14334213238415072, "HONDA PASSPORT 2021": 0.19826160782809032, "KIA K5 2021": 0.1027179720106188, "ACURA ILX 2016": 0.35663988815912573, "HYUNDAI IONIQ HYBRID 2017-2019": 0.12332151728479951, "KIA NIRO EV 2020": 0.0892074288578785, "SUBARU IMPREZA SPORT 2020": 0.15841234487251604, "CHRYSLER PACIFICA HYBRID 2017": 0.1345638758810282, "HYUNDAI KONA ELECTRIC 2019": 0.08503096350356723, "HYUNDAI ELANTRA HYBRID 2021": 0.09887804390243872, "HYUNDAI SANTA FE HYBRID 2022": 0.11171499761140577, "CHRYSLER PACIFICA 2018": 0.13611561752951415, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": 0.10502695501512567, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 0.21818156330777305, "MAZDA CX-9 2021": 0.1793735649504697, "HYUNDAI SANTA FE 2022": 0.09184808719698756, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 0.14050744688135813, "HONDA HRV 2019": 0.17840321248608593, "TOYOTA AVALON HYBRID 2022": 0.16159049452515487, "SUBARU IMPREZA LIMITED 2019": 0.20322553080306893, "GENESIS G80 2017": 0.07934444681782107, "VOLKSWAGEN TAOS 1ST GEN": 0.18276122764341485, "KIA FORTE E 2018 & GT 2021": 0.11406160665068436, "CADILLAC ESCALADE ESV 2016": 0.15063766975884627, "TOYOTA C-HR 2021": 0.22798633346500694, "TOYOTA C-HR HYBRID 2018": 0.2036375866375624}, "ERROR_RATIO": {"HONDA PILOT 2017": 0.6158457247286419, "HONDA CIVIC 2016": 2.0785618623350928, "TOYOTA CAMRY 2018": 0.17356565057429169, "TOYOTA COROLLA HYBRID TSS2 2019": 0.10094741777075293, "TOYOTA RAV4 2019": 0.11812042718338775, "HYUNDAI PALISADE 2020": 0.30639442561268304, "TOYOTA SIENNA 2018": 0.1117307389748361, "ACURA RDX 2020": 1.9801454495960717, "TOYOTA RAV4 2017": 0.08589486116378196, "HONDA RIDGELINE 2017": 0.4319851914417577, "TOYOTA PRIUS 2017": 0.17281316158588575, "TOYOTA HIGHLANDER HYBRID 2020": 0.046325388721577, "HYUNDAI SONATA 2020": 0.4109860794021653, "KIA STINGER GT2 2018": 0.3517628781488943, "TOYOTA HIGHLANDER 2020": 0.14155072865224166, "HONDA ACCORD 2018": 2.510398061115294, "TOYOTA PRIUS TSS2 2021": 0.13593456264106363, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 0.08794943266738546, "LEXUS NX 2020": 0.3743942573190866, "TOYOTA RAV4 HYBRID 2019": 0.0845492503791727, "HONDA CIVIC (BOSCH) 2019": 2.4329816697390063, "KIA NIRO HYBRID 2021": NaN, "HONDA ACCORD HYBRID 2018": 2.9252406767451804, "LEXUS NX HYBRID 2018": 0.23060712246809048, "TOYOTA COROLLA TSS2 2019": 0.13822363784977285, "VOLKSWAGEN ARTEON 1ST GEN": 0.009661691674299285, "TOYOTA CAMRY HYBRID 2021": 0.029451711159377333, "VOLKSWAGEN JETTA 7TH GEN": 0.16591473170144055, "HONDA INSIGHT 2019": 1.3398692842898896, "SUBARU FORESTER 2019": 0.5269683780697442, "HYUNDAI ELANTRA 2021": NaN, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 0.02971857401969039, "HYUNDAI KONA HYBRID 2020": NaN, "HONDA ODYSSEY 2018": 1.0245957242729038, "LEXUS RX 2016": 0.07392586589971588, "TOYOTA COROLLA 2017": 0.31336988069649124, "LEXUS ES 2019": 0.08933657038050916, "HYUNDAI SANTA FE 2019": 0.2276812089092099, "TOYOTA AVALON 2022": 0.07120118798045925, "JEEP GRAND CHEROKEE V6 2018": 0.2065164316228118, "CHEVROLET VOLT PREMIER 2017": 0.2316223989408518, "TOYOTA RAV4 HYBRID 2017": 0.055653752888652736, "LEXUS RX 2020": 0.047792182371008345, "TOYOTA HIGHLANDER HYBRID 2018": 0.019259474082467202, "TOYOTA CAMRY HYBRID 2018": 0.11949733140330816, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 0.1996863736436734, "TOYOTA MIRAI 2021": 0.11019259478417197, "LEXUS IS 2018": NaN, "TOYOTA HIGHLANDER 2017": 0.05279963713251727, "HYUNDAI SONATA HYBRID 2021": 0.3543918194389536, "VOLKSWAGEN ATLAS 1ST GEN": 0.21694647502209782, "LEXUS ES HYBRID 2019": 0.14775474433507507, "HYUNDAI GENESIS 2015-2016": 0.0814892037361157, "JEEP GRAND CHEROKEE 2019": 0.3126997097753535, "SUBARU ASCENT LIMITED 2019": NaN, "HONDA CR-V 2017": 5.652613829506629, "HONDA FIT 2018": 1.5217432826711779, "TOYOTA CAMRY 2021": 0.07910435053686729, "AUDI Q3 2ND GEN": 0.13535089102138698, "AUDI A3 3RD GEN": 0.14353941401245793, "LEXUS RX HYBRID 2017": 0.048663813961824696, "HONDA CIVIC 2022": 1.0748206908458815, "GENESIS G70 2018": 0.688303429295532, "CHRYSLER PACIFICA HYBRID 2018": 0.11083725786301112, "VOLKSWAGEN PASSAT 8TH GEN": 0.13315924904555493, "HONDA CR-V 2016": 0.488871482749128, "HYUNDAI IONIQ PHEV 2020": 0.2756096845519595, "GMC ACADIA DENALI 2018": 0.24055364003040136, "HYUNDAI SONATA 2019": 0.4473315280277132, "TOYOTA AVALON 2019": 0.026428086100632363, "TOYOTA C-HR 2018": 0.06075105822970755, "HONDA CR-V HYBRID 2019": 2.9906016360828276, "CHRYSLER PACIFICA 2020": 0.07748732608487266, "HYUNDAI IONIQ ELECTRIC 2020": NaN, "VOLKSWAGEN TIGUAN 2ND GEN": NaN, "LEXUS NX 2018": 0.16318394527060903, "KIA OPTIMA SX 2019 & 2016": 0.4378756841929454, "TOYOTA AVALON HYBRID 2019": NaN, "TOYOTA RAV4 HYBRID 2022": 0.36478548056633514, "HONDA PASSPORT 2021": 0.5993860184637646, "KIA K5 2021": 0.6271500841947655, "ACURA ILX 2016": 0.8435442647921855, "HYUNDAI IONIQ HYBRID 2017-2019": NaN, "KIA NIRO EV 2020": 0.40355577782011604, "SUBARU IMPREZA SPORT 2020": 0.11071291640854522, "CHRYSLER PACIFICA HYBRID 2017": 0.029812269495458284, "HYUNDAI KONA ELECTRIC 2019": NaN, "HYUNDAI ELANTRA HYBRID 2021": NaN, "HYUNDAI SANTA FE HYBRID 2022": NaN, "CHRYSLER PACIFICA 2018": 0.01705753895996445, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": NaN, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 0.05790668871480552, "MAZDA CX-9 2021": NaN, "HYUNDAI SANTA FE 2022": 0.018126919430513307, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 0.1331760659016062, "HONDA HRV 2019": 1.599688433820939, "TOYOTA AVALON HYBRID 2022": NaN, "SUBARU IMPREZA LIMITED 2019": 0.2514545160390271, "GENESIS G80 2017": NaN, "VOLKSWAGEN TAOS 1ST GEN": 0.09725484306423876, "KIA FORTE E 2018 & GT 2021": 0.20381871942480628, "CADILLAC ESCALADE ESV 2016": NaN, "TOYOTA C-HR 2021": 0.05016813984196128, "TOYOTA C-HR HYBRID 2018": 0.2521485862766935}} \ No newline at end of file diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 9440c73f5d..e737b4d2e7 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -74,7 +74,6 @@ class CarInterface(CarInterfaceBase): ret.wheelSpeedFactor = 1.035 tire_stiffness_factor = 0.5533 ret.mass = 4481. * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max - ret.maxLateralAccel = 1.4 set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate in (CAR.CHR, CAR.CHRH): @@ -83,7 +82,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.6 tire_stiffness_factor = 0.7933 ret.mass = 3300. * CV.LB_TO_KG + STD_CARGO_KG - ret.maxLateralAccel = 1.3 set_lat_tune(ret.lateralTuning, LatTunes.PID_F) elif candidate in (CAR.CAMRY, CAR.CAMRYH, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2): @@ -96,7 +94,6 @@ class CarInterface(CarInterfaceBase): ret.maxLateralAccel = 2.4 set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=ret.maxLateralAccel, FRICTION=0.05) else: - ret.maxLateralAccel = 2.0 set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate in (CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2): @@ -105,7 +102,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.0 tire_stiffness_factor = 0.8 ret.mass = 4700. * CV.LB_TO_KG + STD_CARGO_KG # 4260 + 4-5 people - ret.maxLateralAccel = 2.0 set_lat_tune(ret.lateralTuning, LatTunes.PID_G) elif candidate in (CAR.HIGHLANDER, CAR.HIGHLANDERH): @@ -114,7 +110,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.0 tire_stiffness_factor = 0.8 ret.mass = 4607. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid limited - ret.maxLateralAccel = 1.8 set_lat_tune(ret.lateralTuning, LatTunes.PID_G) elif candidate in (CAR.AVALON, CAR.AVALON_2019, CAR.AVALONH_2019, CAR.AVALON_TSS2, CAR.AVALONH_TSS2): @@ -125,7 +120,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.8 # Found at https://pressroom.toyota.com/releases/2016+avalon+product+specs.download tire_stiffness_factor = 0.7983 ret.mass = 3505. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid - ret.maxLateralAccel = 1.6 set_lat_tune(ret.lateralTuning, LatTunes.PID_H) elif candidate in (CAR.RAV4_TSS2, CAR.RAV4_TSS2_2022, CAR.RAV4H_TSS2, CAR.RAV4H_TSS2_2022): @@ -134,7 +128,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.3 tire_stiffness_factor = 0.7933 ret.mass = 3585. * CV.LB_TO_KG + STD_CARGO_KG # Average between ICE and Hybrid - ret.maxLateralAccel = 2.5 set_lat_tune(ret.lateralTuning, LatTunes.PID_D) # 2019+ RAV4 TSS2 uses two different steering racks and specific tuning seems to be necessary. @@ -159,7 +152,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.0 # not optimized tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 3677. * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max - ret.maxLateralAccel = 2.2 set_lat_tune(ret.lateralTuning, LatTunes.PID_D) elif candidate == CAR.SIENNA: @@ -168,7 +160,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 15.5 tire_stiffness_factor = 0.444 ret.mass = 4590. * CV.LB_TO_KG + STD_CARGO_KG - ret.maxLateralAccel = 1.6 set_lat_tune(ret.lateralTuning, LatTunes.PID_J) elif candidate in (CAR.LEXUS_IS, CAR.LEXUS_RC): @@ -192,7 +183,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.7 tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 4070 * CV.LB_TO_KG + STD_CARGO_KG - ret.maxLateralAccel = 2.0 set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate == CAR.PRIUS_TSS2: @@ -201,7 +191,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.4 # True steerRatio from older prius tire_stiffness_factor = 0.6371 # hand-tune ret.mass = 3115. * CV.LB_TO_KG + STD_CARGO_KG - ret.maxLateralAccel = 2.0 set_lat_tune(ret.lateralTuning, LatTunes.PID_N) elif candidate == CAR.MIRAI: @@ -210,7 +199,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.8 tire_stiffness_factor = 0.8 ret.mass = 4300. * CV.LB_TO_KG + STD_CARGO_KG - ret.maxLateralAccel = 2.4 set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate in (CAR.ALPHARD_TSS2, CAR.ALPHARDH_TSS2): diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 90bbd6d889..3a0d7c8ce8 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -64,17 +64,14 @@ class CarInterface(CarInterfaceBase): elif candidate == CAR.ATLAS_MK1: ret.mass = 2011 + STD_CARGO_KG ret.wheelbase = 2.98 - ret.maxLateralAccel = 1.4 elif candidate == CAR.GOLF_MK7: ret.mass = 1397 + STD_CARGO_KG ret.wheelbase = 2.62 - ret.maxLateralAccel = 1.5 elif candidate == CAR.JETTA_MK7: ret.mass = 1328 + STD_CARGO_KG ret.wheelbase = 2.71 - ret.maxLateralAccel = 1.2 elif candidate == CAR.PASSAT_MK8: ret.mass = 1551 + STD_CARGO_KG @@ -95,7 +92,6 @@ class CarInterface(CarInterfaceBase): elif candidate == CAR.TIGUAN_MK2: ret.mass = 1715 + STD_CARGO_KG ret.wheelbase = 2.74 - ret.maxLateralAccel = 1.1 elif candidate == CAR.TOURAN_MK2: ret.mass = 1516 + STD_CARGO_KG @@ -113,7 +109,6 @@ class CarInterface(CarInterfaceBase): elif candidate == CAR.AUDI_A3_MK3: ret.mass = 1335 + STD_CARGO_KG ret.wheelbase = 2.61 - ret.maxLateralAccel = 1.7 elif candidate == CAR.AUDI_Q2_MK1: ret.mass = 1205 + STD_CARGO_KG @@ -122,7 +117,6 @@ class CarInterface(CarInterfaceBase): elif candidate == CAR.AUDI_Q3_MK2: ret.mass = 1623 + STD_CARGO_KG ret.wheelbase = 2.68 - ret.maxLateralAccel = 1.6 elif candidate == CAR.SEAT_ATECA_MK1: ret.mass = 1900 + STD_CARGO_KG diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 2f42570934..298de7999a 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -f301bdf52b271c8c4ef0f2bce3be9c8f90037652 +935abbc21282e10572c9324382feba3fee2fe379 \ No newline at end of file From f398b3efc92f59f407379d38ead0f99bf814b95c Mon Sep 17 00:00:00 2001 From: AlexandreSato <66435071+AlexandreSato@users.noreply.github.com> Date: Fri, 10 Jun 2022 22:45:32 -0300 Subject: [PATCH 006/302] Fix Lexus NX Hybrid 2020 engine ecu (#24817) Wrong address in engine ecu. --- selfdrive/car/toyota/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 7e6cfa0d09..2c151266cf 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1585,7 +1585,7 @@ FW_VERSIONS = { ], }, CAR.LEXUS_NXH_TSS2: { - (Ecu.engine, 0x700, None): [ + (Ecu.engine, 0x7e0, None): [ b'\x0237887000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ From 88a100435f1da9bf061b360e8a5cd02e414d6e8b Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 10 Jun 2022 22:52:34 -0700 Subject: [PATCH 007/302] compatibility docs: auto-generate star descriptions (#24809) * Auto-generate star descriptions * Need this for the website * And this * required changes to make the website generation work * better names * Revert "better names" This reverts commit be7dbbb5d846d7d55a1ad69533945e6a6c8a0b7c. * simpler --- selfdrive/car/CARS_template.md | 29 ++++++++-------------------- selfdrive/car/docs.py | 4 ++-- selfdrive/car/docs_definitions.py | 32 +++++++++++++++++++++++++++++++ 3 files changed, 42 insertions(+), 23 deletions(-) diff --git a/selfdrive/car/CARS_template.md b/selfdrive/car/CARS_template.md index f93dc64b06..891445a558 100644 --- a/selfdrive/car/CARS_template.md +++ b/selfdrive/car/CARS_template.md @@ -14,28 +14,15 @@ Cars are organized into three tiers: How We Rate The Cars --- -### openpilot Adaptive Cruise Control (ACC) -- {{star_icon.format(Star.FULL.value)}} - openpilot is able to control the gas and brakes. -- {{star_icon.format(Star.HALF.value)}} - openpilot is able to control the gas and brakes with some restrictions. -- {{star_icon.format(Star.EMPTY.value)}} - The gas and brakes are controlled by the car's stock Adaptive Cruise Control (ACC) system. - -### Stop and Go -- {{star_icon.format(Star.FULL.value)}} - Adaptive Cruise Control (ACC) operates down to 0 mph. -- {{star_icon.format(Star.EMPTY.value)}} - Adaptive Cruise Control (ACC) available only above certain speeds. See your car's manual for the minimum speed. - -### Steer to 0 -- {{star_icon.format(Star.FULL.value)}} - openpilot can control the steering wheel down to 0 mph. -- {{star_icon.format(Star.EMPTY.value)}} - No steering control below certain speeds. - -### Steering Torque -- {{star_icon.format(Star.FULL.value)}} - Car has enough steering torque to take tighter turns. -- {{star_icon.format(Star.HALF.value)}} - Car has enough steering torque for comfortable highway driving. -- {{star_icon.format(Star.EMPTY.value)}} - Limited ability to make turns. - -### Actively Maintained -- {{star_icon.format(Star.FULL.value)}} - Mainline software support, harness hardware sold by comma, lots of users, primary development target. -- {{star_icon.format(Star.EMPTY.value)}} - Low user count, community maintained, harness hardware not sold by comma. +{% for star_row in star_descriptions.values() %} +{% for name, stars in star_row.items() %} +### {{name}} +{% for star, description in stars %} +- {{star_icon.format(star)}} - {{description}} +{% endfor %} +{% endfor %} +{% endfor %} **All supported cars can move between the tiers as support changes.** {% for tier, cars in tiers.items() %} diff --git a/selfdrive/car/docs.py b/selfdrive/car/docs.py index 899f2c0878..860503dbdd 100755 --- a/selfdrive/car/docs.py +++ b/selfdrive/car/docs.py @@ -7,7 +7,7 @@ from natsort import natsorted from typing import Dict, List from common.basedir import BASEDIR -from selfdrive.car.docs_definitions import CarInfo, Column, Star, Tier +from selfdrive.car.docs_definitions import STAR_DESCRIPTIONS, CarInfo, Column, Star, Tier from selfdrive.car.car_helpers import interfaces, get_interface_attr from selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR as HKG_RADAR_START_ADDR from selfdrive.car.tests.routes import non_tested_cars @@ -65,7 +65,7 @@ def generate_cars_md(all_car_info: List[CarInfo], template_fn: str) -> str: footnotes = [fn.value.text for fn in ALL_FOOTNOTES] cars_md: str = template.render(tiers=sort_by_tier(all_car_info), all_car_info=all_car_info, - footnotes=footnotes, Star=Star, Column=Column) + footnotes=footnotes, Star=Star, Column=Column, star_descriptions=STAR_DESCRIPTIONS) return cars_md diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index 3700a24835..f09dad7860 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -150,3 +150,35 @@ class Harness(Enum): nissan_b = "Nissan B" mazda = "Mazda" none = "None" + + +STAR_DESCRIPTIONS = { + "Gas & Brakes": { # icon and row name + "openpilot Adaptive Cruise Control (ACC)": [ # star column + [Star.FULL.value, "openpilot is able to control the gas and brakes."], + [Star.HALF.value, "openpilot is able to control the gas and brakes with some restrictions."], + [Star.EMPTY.value, "The gas and brakes are controlled by the car's stock Adaptive Cruise Control (ACC) system."], + ], + Column.FSR_LONGITUDINAL.value: [ + [Star.FULL.value, "Adaptive Cruise Control (ACC) operates down to 0 mph."], + [Star.EMPTY.value, "Adaptive Cruise Control (ACC) available only above certain speeds. See your car's manual for the minimum speed."], + ], + }, + "Steering": { + Column.FSR_STEERING.value: [ + [Star.FULL.value, "openpilot can control the steering wheel down to 0 mph."], + [Star.EMPTY.value, "No steering control below certain speeds."], + ], + Column.STEERING_TORQUE.value: [ + [Star.FULL.value, "Car has enough steering torque to take tighter turns."], + [Star.HALF.value, "Car has enough steering torque for comfortable highway driving."], + [Star.EMPTY.value, "Limited ability to make turns."], + ], + }, + "Support": { + Column.MAINTAINED.value: [ + [Star.FULL.value, "Mainline software support, harness hardware sold by comma, lots of users, primary development target."], + [Star.EMPTY.value, "Low user count, community maintained, harness hardware not sold by comma."], + ], + }, +} From 843e59f6f0be33e6c51a35ef8912f5b7c4b58ca5 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Fri, 10 Jun 2022 22:52:48 -0700 Subject: [PATCH 008/302] Misc torque control fixes (#24801) * Fiction compensation should be based on error * Update refs * Add deadzone * update ref --- cereal | 2 +- selfdrive/car/toyota/interface.py | 2 +- selfdrive/car/toyota/tunes.py | 4 ++-- selfdrive/controls/lib/drive_helpers.py | 16 +++++++++++++--- selfdrive/controls/lib/latcontrol_torque.py | 20 +++++++++++--------- selfdrive/controls/lib/longcontrol.py | 12 +----------- selfdrive/test/process_replay/ref_commit | 2 +- 7 files changed, 30 insertions(+), 28 deletions(-) diff --git a/cereal b/cereal index ff49c8e126..a197e38c0c 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit ff49c8e126ea04889af13d690ceaf520ce7084d2 +Subproject commit a197e38c0cef00ececf4c7500438d37659d9199e diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index e737b4d2e7..83eed611c3 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -39,7 +39,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.6371 # hand-tune ret.mass = 3045. * CV.LB_TO_KG + STD_CARGO_KG ret.maxLateralAccel = 1.7 - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=ret.maxLateralAccel, FRICTION=0.06) + set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=ret.maxLateralAccel, FRICTION=0.06, steering_angle_deadzone_deg=1.0) elif candidate == CAR.PRIUS_V: stop_and_go = True diff --git a/selfdrive/car/toyota/tunes.py b/selfdrive/car/toyota/tunes.py index e97ed6b056..3de6daae21 100644 --- a/selfdrive/car/toyota/tunes.py +++ b/selfdrive/car/toyota/tunes.py @@ -50,9 +50,9 @@ def set_long_tune(tune, name): ###### LAT ###### -def set_lat_tune(tune, name, MAX_LAT_ACCEL=2.5, FRICTION=0.01, use_steering_angle=True): +def set_lat_tune(tune, name, MAX_LAT_ACCEL=2.5, FRICTION=0.01, steering_angle_deadzone_deg=0.0, use_steering_angle=True): if name == LatTunes.TORQUE: - set_torque_tune(tune, MAX_LAT_ACCEL, FRICTION) + set_torque_tune(tune, MAX_LAT_ACCEL, FRICTION, steering_angle_deadzone_deg) elif 'PID' in str(name): tune.init('pid') tune.pid.kiBP = [0.0] diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index 91981259aa..1fecdd7c63 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -38,6 +38,16 @@ class MPC_COST_LAT: STEER_RATE = 1.0 +def apply_deadzone(error, deadzone): + if error > deadzone: + error -= deadzone + elif error < - deadzone: + error += deadzone + else: + error = 0. + return error + + def rate_limit(new_value, last_value, dw_step, up_step): return clip(new_value, last_value + dw_step, last_value + up_step) @@ -98,10 +108,10 @@ def get_lag_adjusted_curvature(CP, v_ego, psis, curvatures, curvature_rates): curvatures = [0.0]*CONTROL_N curvature_rates = [0.0]*CONTROL_N v_ego = max(v_ego, 0.1) - + # TODO this needs more thought, use .2s extra for now to estimate other delays delay = CP.steerActuatorDelay + .2 - + # MPC can plan to turn the wheel and turn back before t_delay. This means # in high delay cases some corrections never even get commanded. So just use # psi to calculate a simple linearization of desired curvature @@ -109,7 +119,7 @@ def get_lag_adjusted_curvature(CP, v_ego, psis, curvatures, curvature_rates): psi = interp(delay, T_IDXS[:CONTROL_N], psis) average_curvature_desired = psi / (v_ego * delay) desired_curvature = 2 * average_curvature_desired - current_curvature_desired - + # This is the "desired rate of the setpoint" not an actual desired rate desired_curvature_rate = curvature_rates[0] max_curvature_rate = MAX_LATERAL_JERK / (v_ego**2) diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index 47f0b69f2b..12714082a6 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -4,6 +4,7 @@ from cereal import log from common.numpy_fast import interp from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED from selfdrive.controls.lib.pid import PIDController +from selfdrive.controls.lib.drive_helpers import apply_deadzone from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY # At higher speeds (25+mph) we can assume: @@ -22,13 +23,14 @@ LOW_SPEED_FACTOR = 200 JERK_THRESHOLD = 0.2 -def set_torque_tune(tune, MAX_LAT_ACCEL=2.5, FRICTION=0.01): +def set_torque_tune(tune, MAX_LAT_ACCEL=2.5, FRICTION=0.01, steering_angle_deadzone_deg=0.0): tune.init('torque') tune.torque.useSteeringAngle = True tune.torque.kp = 1.0 / MAX_LAT_ACCEL tune.torque.kf = 1.0 / MAX_LAT_ACCEL tune.torque.ki = 0.1 / MAX_LAT_ACCEL tune.torque.friction = FRICTION + tune.torque.steeringAngleDeadzoneDeg = steering_angle_deadzone_deg class LatControlTorque(LatControl): @@ -40,10 +42,7 @@ class LatControlTorque(LatControl): self.use_steering_angle = CP.lateralTuning.torque.useSteeringAngle self.friction = CP.lateralTuning.torque.friction self.kf = CP.lateralTuning.torque.kf - - def reset(self): - super().reset() - self.pid.reset() + self.steering_angle_deadzone_deg = CP.lateralTuning.torque.steeringAngleDeadzoneDeg def update(self, active, CS, VM, params, last_actuators, desired_curvature, desired_curvature_rate, llk): pid_log = log.ControlsState.LateralTorqueState.new_message() @@ -54,24 +53,27 @@ class LatControlTorque(LatControl): else: if self.use_steering_angle: actual_curvature = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll) + curvature_deadzone = abs(VM.calc_curvature(math.radians(self.steering_angle_deadzone_deg), CS.vEgo, 0.0)) else: actual_curvature_vm = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll) actual_curvature_llk = llk.angularVelocityCalibrated.value[2] / CS.vEgo actual_curvature = interp(CS.vEgo, [2.0, 5.0], [actual_curvature_vm, actual_curvature_llk]) + curvature_deadzone = 0.0 desired_lateral_accel = desired_curvature * CS.vEgo ** 2 - + # desired rate is the desired rate of change in the setpoint, not the absolute desired curvature - desired_lateral_jerk = desired_curvature_rate * CS.vEgo ** 2 + #desired_lateral_jerk = desired_curvature_rate * CS.vEgo ** 2 actual_lateral_accel = actual_curvature * CS.vEgo ** 2 + lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2 setpoint = desired_lateral_accel + LOW_SPEED_FACTOR * desired_curvature measurement = actual_lateral_accel + LOW_SPEED_FACTOR * actual_curvature - error = setpoint - measurement + error = apply_deadzone(setpoint - measurement, lateral_accel_deadzone) pid_log.error = error ff = desired_lateral_accel - params.roll * ACCELERATION_DUE_TO_GRAVITY # convert friction into lateral accel units for feedforward - friction_compensation = interp(desired_lateral_jerk, [-JERK_THRESHOLD, JERK_THRESHOLD], [-self.friction, self.friction]) + friction_compensation = interp(error, [-JERK_THRESHOLD, JERK_THRESHOLD], [-self.friction, self.friction]) ff += friction_compensation / self.kf freeze_integrator = CS.steeringRateLimited or CS.steeringPressed or CS.vEgo < 5 output_torque = self.pid.update(error, diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index f2cd282198..e9458607d5 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -1,7 +1,7 @@ from cereal import car from common.numpy_fast import clip, interp from common.realtime import DT_CTRL -from selfdrive.controls.lib.drive_helpers import CONTROL_N +from selfdrive.controls.lib.drive_helpers import CONTROL_N, apply_deadzone from selfdrive.controls.lib.pid import PIDController from selfdrive.modeld.constants import T_IDXS @@ -12,16 +12,6 @@ ACCEL_MIN_ISO = -3.5 # m/s^2 ACCEL_MAX_ISO = 2.0 # m/s^2 -def apply_deadzone(error, deadzone): - if error > deadzone: - error -= deadzone - elif error < - deadzone: - error += deadzone - else: - error = 0. - return error - - def long_control_state_trans(CP, active, long_control_state, v_ego, v_target, v_target_future, brake_pressed, cruise_standstill): """Update longitudinal control state machine""" diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 298de7999a..613b7f26ae 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -935abbc21282e10572c9324382feba3fee2fe379 \ No newline at end of file +123506cad1877e93bfe5c91ecdce654ef339959b From e3750877202a072e884ad0fb88709b23226c3a59 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Sat, 11 Jun 2022 00:14:58 -0700 Subject: [PATCH 009/302] Honda carcontroller and signal cleanup (#24806) * common signals * move stopping * space * clean up * bump opendbc --- opendbc | 2 +- selfdrive/car/honda/carcontroller.py | 27 ++++----------- selfdrive/car/honda/hondacan.py | 49 ++++++++++++---------------- 3 files changed, 29 insertions(+), 49 deletions(-) diff --git a/opendbc b/opendbc index ec0e1f20ba..58a2c9b2fc 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit ec0e1f20bae4c39326036c0061418404ac15ae9e +Subproject commit 58a2c9b2fc5c60ca68d3dced09f6c4c72ca72415 diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index cf01fa2aaa..a6aa84adf6 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -95,8 +95,8 @@ def process_hud_alert(hud_alert): HUDData = namedtuple("HUDData", - ["pcm_accel", "v_cruise", "car", - "lanes", "fcw", "acc_alert", "steer_required"]) + ["pcm_accel", "v_cruise", "lead_visible", + "lanes_visible", "fcw", "acc_alert", "steer_required"]) class CarController: @@ -138,19 +138,6 @@ class CarController: self.brake_last = rate_limit(pre_limit_brake, self.brake_last, -2., DT_CTRL) # vehicle hud display, wait for one update from 10Hz 0x304 msg - if hud_control.lanesVisible: - hud_lanes = 1 - else: - hud_lanes = 0 - - if CC.enabled: - if hud_control.leadVisible: - hud_car = 2 - else: - hud_car = 1 - else: - hud_car = 0 - fcw_display, steer_required, acc_alert = process_hud_alert(hud_control.visualAlert) # **** process the car messages **** @@ -172,8 +159,6 @@ class CarController: can_sends.append(hondacan.create_steering_control(self.packer, apply_steer, CC.latActive, self.CP.carFingerprint, idx, CS.CP.openpilotLongitudinalControl)) - stopping = actuators.longControlState == LongCtrlState.stopping - # wind brake from air resistance decel at high speed wind_brake = interp(CS.out.vEgo, [0.0, 2.3, 35.0], [0.001, 0.002, 0.15]) # all of this is only relevant for HONDA NIDEC @@ -222,6 +207,8 @@ class CarController: if self.CP.carFingerprint in HONDA_BOSCH: self.accel = clip(accel, self.params.BOSCH_ACCEL_MIN, self.params.BOSCH_ACCEL_MAX) self.gas = interp(accel, self.params.BOSCH_GAS_LOOKUP_BP, self.params.BOSCH_GAS_LOOKUP_V) + + stopping = actuators.longControlState == LongCtrlState.stopping can_sends.extend(hondacan.create_acc_commands(self.packer, CC.enabled, CC.longActive, self.accel, self.gas, idx, stopping, self.CP.carFingerprint)) else: @@ -252,9 +239,9 @@ class CarController: # Send dashboard UI commands. if self.frame % 10 == 0: idx = (self.frame // 10) % 4 - hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), hud_car, - hud_lanes, fcw_display, acc_alert, steer_required) - can_sends.extend(hondacan.create_ui_commands(self.packer, self.CP, pcm_speed, hud, CS.is_metric, idx, CS.stock_hud)) + hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), hud_control.leadVisible, + hud_control.lanesVisible, fcw_display, acc_alert, steer_required) + can_sends.extend(hondacan.create_ui_commands(self.packer, self.CP, CC.enabled, pcm_speed, hud, CS.is_metric, idx, CS.stock_hud)) if self.CP.openpilotLongitudinalControl and self.CP.carFingerprint not in HONDA_BOSCH: self.speed = pcm_speed diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py index dcdc0e5f94..9c9e873e18 100644 --- a/selfdrive/car/honda/hondacan.py +++ b/selfdrive/car/honda/hondacan.py @@ -98,47 +98,40 @@ def create_bosch_supplemental_1(packer, car_fingerprint, idx): return packer.make_can_msg("BOSCH_SUPPLEMENTAL_1", bus, values, idx) -def create_ui_commands(packer, CP, pcm_speed, hud, is_metric, idx, stock_hud): +def create_ui_commands(packer, CP, enabled, pcm_speed, hud, is_metric, idx, stock_hud): commands = [] bus_pt = get_pt_bus(CP.carFingerprint) radar_disabled = CP.carFingerprint in HONDA_BOSCH and CP.openpilotLongitudinalControl bus_lkas = get_lkas_cmd_bus(CP.carFingerprint, radar_disabled) if CP.openpilotLongitudinalControl: + acc_hud_values = { + 'CRUISE_SPEED': hud.v_cruise, + 'ENABLE_MINI_CAR': 1, + 'HUD_DISTANCE': 3, # max distance setting on display + 'IMPERIAL_UNIT': int(not is_metric), + 'HUD_LEAD': 2 if enabled and hud.lead_visible else 1 if enabled else 0, + 'SET_ME_X01_2': 1, + } + if CP.carFingerprint in HONDA_BOSCH: - acc_hud_values = { - 'CRUISE_SPEED': hud.v_cruise, - 'ENABLE_MINI_CAR': 1, - 'SET_TO_1': 1, - 'HUD_LEAD': hud.car, - 'HUD_DISTANCE': 3, - 'ACC_ON': hud.car != 0, - 'SET_TO_X1': 1, - 'IMPERIAL_UNIT': int(not is_metric), - 'FCM_OFF': 1, - } + acc_hud_values['ACC_ON'] = hud.car != 0 + acc_hud_values['FCM_OFF'] = 1 + acc_hud_values['FCM_OFF_2'] = 1 else: - acc_hud_values = { - 'PCM_SPEED': pcm_speed * CV.MS_TO_KPH, - 'PCM_GAS': hud.pcm_accel, - 'CRUISE_SPEED': hud.v_cruise, - 'ENABLE_MINI_CAR': 1, - 'HUD_LEAD': hud.car, - 'HUD_DISTANCE': 3, # max distance setting on display - 'IMPERIAL_UNIT': int(not is_metric), - 'SET_ME_X01_2': 1, - 'SET_ME_X01': 1, - "FCM_OFF": stock_hud["FCM_OFF"], - "FCM_OFF_2": stock_hud["FCM_OFF_2"], - "FCM_PROBLEM": stock_hud["FCM_PROBLEM"], - "ICONS": stock_hud["ICONS"], - } + acc_hud_values['PCM_SPEED'] = pcm_speed * CV.MS_TO_KPH + acc_hud_values['PCM_GAS'] = hud.pcm_accel + acc_hud_values['SET_ME_X01'] = 1 + acc_hud_values['FCM_OFF'] = stock_hud['FCM_OFF'] + acc_hud_values['FCM_OFF_2'] = stock_hud['FCM_OFF_2'] + acc_hud_values['FCM_PROBLEM'] = stock_hud['FCM_PROBLEM'] + acc_hud_values['ICONS'] = stock_hud['ICONS'] commands.append(packer.make_can_msg("ACC_HUD", bus_pt, acc_hud_values, idx)) lkas_hud_values = { 'SET_ME_X41': 0x41, 'STEERING_REQUIRED': hud.steer_required, - 'SOLID_LANES': hud.lanes, + 'SOLID_LANES': hud.lanes_visible, 'BEEP': 0, } From 1847a70a47b12ff5c7e7db9361f69d6d1e79a919 Mon Sep 17 00:00:00 2001 From: Maykon Pacheco <38124066+maykonpacheco@users.noreply.github.com> Date: Sat, 11 Jun 2022 14:08:24 -0400 Subject: [PATCH 010/302] test for the strip_bz2_extension method (#24826) --- selfdrive/athena/tests/test_athenad.py | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/selfdrive/athena/tests/test_athenad.py b/selfdrive/athena/tests/test_athenad.py index b6457ca01d..a0b308c216 100755 --- a/selfdrive/athena/tests/test_athenad.py +++ b/selfdrive/athena/tests/test_athenad.py @@ -120,6 +120,13 @@ class TestAthenadMethods(unittest.TestCase): self.assertTrue(resp, 'list empty!') self.assertCountEqual(resp, expected) + def test_strip_bz2_extension(self): + fn = os.path.join(athenad.ROOT, 'qlog.bz2') + Path(fn).touch() + if fn.endswith('.bz2'): + self.assertEqual(athenad.strip_bz2_extension(fn), fn[:-4]) + + @with_http_server def test_do_upload(self, host): fn = os.path.join(athenad.ROOT, 'qlog.bz2') From a029245a784acb9fe3d8db7f1023aab222ec0dba Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 11 Jun 2022 12:20:24 -0700 Subject: [PATCH 011/302] CI: fix docker push for base image --- .github/workflows/selfdrive_tests.yaml | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 04ae841f77..567fc05aa5 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -20,8 +20,7 @@ env: RUN: docker run --shm-size 1G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/scons_cache:/tmp/scons_cache -v /tmp/comma_download_cache:/tmp/comma_download_cache $BASE_IMAGE /bin/sh -c BUILD_CL: | - docker pull $(grep -iohP '(?<=^from)\s+\S+' Dockerfile.openpilot_base_cl) || true - docker pull $DOCKER_REGISTRY/$BASE_IMAGE:latest || true + docker pull $DOCKER_REGISTRY/$CL_BASE_IMAGE:latest || true docker build --cache-from $DOCKER_REGISTRY/$CL_BASE_IMAGE:latest -t $DOCKER_REGISTRY/$CL_BASE_IMAGE:latest -t $CL_BASE_IMAGE:latest -f Dockerfile.openpilot_base_cl . RUN_CL: docker run --shm-size 1G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/scons_cache:/tmp/scons_cache -v /tmp/comma_download_cache:/tmp/comma_download_cache $CL_BASE_IMAGE /bin/sh -c @@ -201,12 +200,15 @@ jobs: submodules: true - name: Build Docker image run: eval "$BUILD" + - name: Push to container registry + run: | + $DOCKER_LOGIN + docker push $DOCKER_REGISTRY/$BASE_IMAGE:latest - name: Build CL Docker image run: eval "$BUILD_CL" - name: Push to container registry run: | $DOCKER_LOGIN - docker push $DOCKER_REGISTRY/$BASE_IMAGE:latest docker push $DOCKER_REGISTRY/$CL_BASE_IMAGE:latest static_analysis: From 1c238e8c773eb58f88fc69cdcb77dba71430b735 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 11 Jun 2022 13:06:07 -0700 Subject: [PATCH 012/302] pylint: add PyQt5 support --- .pylintrc | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/.pylintrc b/.pylintrc index 73035360ca..27539b743c 100644 --- a/.pylintrc +++ b/.pylintrc @@ -3,7 +3,7 @@ # A comma-separated list of package or module names from where C extensions may # be loaded. Extensions are loading into the active Python interpreter and may # run arbitrary code -extension-pkg-whitelist=scipy cereal.messaging.messaging_pyx +extension-pkg-whitelist=scipy,cereal.messaging.messaging_pyx,PyQt5 # Add files or directories to the blacklist. They should be base names, not # paths. @@ -250,13 +250,6 @@ max-line-length=100 # Maximum number of lines in a module max-module-lines=1000 -# List of optional constructs for which whitespace checking is disabled. `dict- -# separator` is used to allow tabulation in dicts, etc.: {1 : 1,\n222: 2}. -# `trailing-comma` allows a space between comma and closing bracket: (a, ). -# `empty-line` allows space-only lines. -no-space-check=trailing-comma, - dict-separator - # Allow the body of a class to be on the same line as the declaration if body # contains single statement. single-line-class-stmt=no From 5add0c6159db3810c17f0b27afd3dda882f95586 Mon Sep 17 00:00:00 2001 From: Maxime Desroches Date: Sat, 11 Jun 2022 15:32:12 -0700 Subject: [PATCH 013/302] simulator: run simulator test in ci (#24691) * run simulator test in ci * block navd process * block ui * fix jenkins * build docker * remove tty * remove tty for carla * detach carla_sim * more retries * only build once * add more time for bridge * cleanup * use qt offscreen * expose to docker * block ui * use new dockerimage * fix * from ubuntu20.04 * install curl * add ssh * add locales * noninteractive * syntax * use base * smaller image * add git + git lfs * kill carla * run in parallel * fix missing agents * default agent? * little cleanup * default doesn't work * not in ci * fix path * fix path * new msg Co-authored-by: Adeeb Shihadeh --- Jenkinsfile | 129 ++++++++++-------- tools/sim/Dockerfile.sim | 2 +- tools/sim/Dockerfile.sim_nvidia | 21 +++ tools/sim/launch_openpilot.sh | 4 + tools/sim/lib/can.py | 1 + tools/sim/start_carla.sh | 7 +- tools/sim/start_openpilot_docker.sh | 22 +-- tools/sim/{test => tests}/__init__.py | 0 .../{test => tests}/test_carla_integration.py | 19 ++- 9 files changed, 133 insertions(+), 72 deletions(-) create mode 100644 tools/sim/Dockerfile.sim_nvidia rename tools/sim/{test => tests}/__init__.py (100%) rename tools/sim/{test => tests}/test_carla_integration.py (85%) diff --git a/Jenkinsfile b/Jenkinsfile index 3b134d7c0d..fed587bd21 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -42,6 +42,7 @@ def phone_steps(String device_type, steps) { pipeline { agent none environment { + CI = "1" TEST_DIR = "/data/openpilot" SOURCE_DIR = "/data/openpilot_source/" } @@ -74,71 +75,89 @@ pipeline { } } - stages { - stage('On-device Tests') { - agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } - stages { - stage('parallel tests') { - parallel { - stage('build') { - environment { - R3_PUSH = "${env.BRANCH_NAME == 'master' ? '1' : ' '}" - } - steps { - phone_steps("tici", [ - ["build master-ci", "cd $SOURCE_DIR/release && TARGET_DIR=$TEST_DIR EXTRA_FILES='tools/' ./build_devel.sh"], - ["build openpilot", "cd selfdrive/manager && ./build.py"], - ["test manager", "python selfdrive/manager/test/test_manager.py"], - ["onroad tests", "cd selfdrive/test/ && ./test_onroad.py"], - ["test car interfaces", "cd selfdrive/car/tests/ && ./test_car_interfaces.py"], - ]) - } - } - - stage('HW + Unit Tests') { - steps { - phone_steps("tici2", [ - ["build", "cd selfdrive/manager && ./build.py"], - ["test power draw", "python selfdrive/hardware/tici/test_power_draw.py"], - ["test boardd loopback", "python selfdrive/boardd/tests/test_boardd_loopback.py"], - ["test loggerd", "python selfdrive/loggerd/tests/test_loggerd.py"], - ["test encoder", "LD_LIBRARY_PATH=/usr/local/lib python selfdrive/loggerd/tests/test_encoder.py"], - ["test sensord", "python selfdrive/sensord/test/test_sensord.py"], - ]) - } - } - - stage('camerad') { - steps { - phone_steps("tici-party", [ - ["build", "cd selfdrive/manager && ./build.py"], - ["test camerad", "python selfdrive/camerad/test/test_camerad.py"], - ["test exposure", "python selfdrive/camerad/test/test_exposure.py"], - ]) - } - } - - stage('replay') { - steps { - phone_steps("tici3", [ - ["build", "cd selfdrive/manager && ./build.py"], - ["model replay", "cd selfdrive/test/process_replay && ./model_replay.py"], - ]) - } - } - - } + parallel { + + stage('simulator') { + agent { + dockerfile { + filename 'Dockerfile.sim_nvidia' + dir 'tools/sim' + args '--user=root' } } + steps { + sh "git config --global --add safe.directory ${WORKSPACE}" + sh "git lfs pull" + sh "${WORKSPACE}/tools/sim/build_container.sh" + sh "DETACH=1 ${WORKSPACE}/tools/sim/start_carla.sh" + sh "${WORKSPACE}/tools/sim/start_openpilot_docker.sh" + } post { always { - cleanWs() + sh "docker kill carla_sim || true" + sh "rm -rf ${WORKSPACE}/* || true" + sh "rm -rf .* || true" } } + } + stage('build') { + agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } + environment { + R3_PUSH = "${env.BRANCH_NAME == 'master' ? '1' : ' '}" + } + steps { + phone_steps("tici", [ + ["build master-ci", "cd $SOURCE_DIR/release && TARGET_DIR=$TEST_DIR EXTRA_FILES='tools/' ./build_devel.sh"], + ["build openpilot", "cd selfdrive/manager && ./build.py"], + ["test manager", "python selfdrive/manager/test/test_manager.py"], + ["onroad tests", "cd selfdrive/test/ && ./test_onroad.py"], + ["test car interfaces", "cd selfdrive/car/tests/ && ./test_car_interfaces.py"], + ]) + } + } + + stage('HW + Unit Tests') { + agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } + steps { + phone_steps("tici2", [ + ["build", "cd selfdrive/manager && ./build.py"], + ["test power draw", "python selfdrive/hardware/tici/test_power_draw.py"], + ["test boardd loopback", "python selfdrive/boardd/tests/test_boardd_loopback.py"], + ["test loggerd", "python selfdrive/loggerd/tests/test_loggerd.py"], + ["test encoder", "LD_LIBRARY_PATH=/usr/local/lib python selfdrive/loggerd/tests/test_encoder.py"], + ["test sensord", "python selfdrive/sensord/test/test_sensord.py"], + ]) + } } + stage('camerad') { + agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } + steps { + phone_steps("tici-party", [ + ["build", "cd selfdrive/manager && ./build.py"], + ["test camerad", "python selfdrive/camerad/test/test_camerad.py"], + ["test exposure", "python selfdrive/camerad/test/test_exposure.py"], + ]) + } + } + + stage('replay') { + agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } + steps { + phone_steps("tici3", [ + ["build", "cd selfdrive/manager && ./build.py"], + ["model replay", "cd selfdrive/test/process_replay && ./model_replay.py"], + ]) + } + } + } + + post { + always { + cleanWs() + } } } } diff --git a/tools/sim/Dockerfile.sim b/tools/sim/Dockerfile.sim index d869db90a6..d838efed13 100644 --- a/tools/sim/Dockerfile.sim +++ b/tools/sim/Dockerfile.sim @@ -27,6 +27,6 @@ COPY ./system $HOME/openpilot/system COPY ./tools $HOME/openpilot/tools WORKDIR $HOME/openpilot -RUN scons -j$(nproc) +RUN scons -j12 RUN python -c "from selfdrive.test.helpers import set_params_enabled; set_params_enabled()" diff --git a/tools/sim/Dockerfile.sim_nvidia b/tools/sim/Dockerfile.sim_nvidia new file mode 100644 index 0000000000..5e5dd263da --- /dev/null +++ b/tools/sim/Dockerfile.sim_nvidia @@ -0,0 +1,21 @@ +FROM ubuntu:20.04 + +ENV DEBIAN_FRONTEND=noninteractive +RUN apt-get update && \ + apt-get install -y --no-install-recommends \ + apt-utils \ + sudo \ + ssh \ + curl \ + ca-certificates \ + git \ + git-lfs && \ + rm -rf /var/lib/apt/lists/* + +RUN curl -fsSL https://get.docker.com -o get-docker.sh && \ + sudo sh get-docker.sh && \ + distribution=$(. /etc/os-release;echo $ID$VERSION_ID) && \ + curl -s -L https://nvidia.github.io/nvidia-docker/gpgkey | sudo apt-key add - && \ + curl -s -L https://nvidia.github.io/nvidia-docker/$distribution/nvidia-docker.list | sudo tee /etc/apt/sources.list.d/nvidia-docker.list && \ + sudo apt-get update && \ + sudo apt-get install -y nvidia-docker2 diff --git a/tools/sim/launch_openpilot.sh b/tools/sim/launch_openpilot.sh index 82fc4a71ac..15f45b4cc2 100755 --- a/tools/sim/launch_openpilot.sh +++ b/tools/sim/launch_openpilot.sh @@ -6,6 +6,10 @@ export SIMULATION="1" export FINGERPRINT="HONDA CIVIC 2016" export BLOCK="camerad,loggerd,encoderd" +if [[ "$CI" ]]; then + # TODO: offscreen UI should work + export BLOCK="${BLOCK},ui" +fi DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" cd ../../selfdrive/manager && exec ./manager.py diff --git a/tools/sim/lib/can.py b/tools/sim/lib/can.py index af0f415bbc..2b1048fef2 100755 --- a/tools/sim/lib/can.py +++ b/tools/sim/lib/can.py @@ -63,6 +63,7 @@ def can_function(pm, speed, angle, idx, cruise_button, is_engaged): msg.append(packer.make_can_msg("SCM_FEEDBACK", 0, {"MAIN_ON": 1}, idx)) msg.append(packer.make_can_msg("POWERTRAIN_DATA", 0, {"ACC_STATUS": int(is_engaged)}, idx)) msg.append(packer.make_can_msg("HUD_SETTING", 0, {})) + msg.append(packer.make_can_msg("CAR_SPEED", 0, {})) # *** cam bus *** msg.append(packer.make_can_msg("STEERING_CONTROL", 2, {}, idx)) diff --git a/tools/sim/start_carla.sh b/tools/sim/start_carla.sh index 912c7d6f08..abdaee4ea8 100755 --- a/tools/sim/start_carla.sh +++ b/tools/sim/start_carla.sh @@ -17,12 +17,17 @@ fi docker pull carlasim/carla:0.9.12 +EXTRA_ARGS="-it" +if [[ "$DETACH" ]]; then + EXTRA_ARGS="-d" +fi + docker run \ --name carla_sim \ --rm \ --gpus all \ --net=host \ -v /tmp/.X11-unix:/tmp/.X11-unix:rw \ - -it \ + $EXTRA_ARGS \ carlasim/carla:0.9.12 \ /bin/bash ./CarlaUE4.sh -opengl -nosound -RenderOffScreen -benchmark -fps=20 -quality-level=Low diff --git a/tools/sim/start_openpilot_docker.sh b/tools/sim/start_openpilot_docker.sh index 106dbdeccb..e48e63574d 100755 --- a/tools/sim/start_openpilot_docker.sh +++ b/tools/sim/start_openpilot_docker.sh @@ -3,22 +3,26 @@ DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" cd $DIR -# expose X to the container -xhost +local:root - -docker pull ghcr.io/commaai/openpilot-sim:latest - OPENPILOT_DIR="/openpilot" -if ! [[ -z "$MOUNT_OPENPILOT" ]] -then +if ! [[ -z "$MOUNT_OPENPILOT" ]]; then OPENPILOT_DIR="$(dirname $(dirname $DIR))" EXTRA_ARGS="-v $OPENPILOT_DIR:$OPENPILOT_DIR -e PYTHONPATH=$OPENPILOT_DIR:$PYTHONPATH" fi +if [[ "$CI" ]]; then + CMD="CI=1 ${OPENPILOT_DIR}/tools/sim/tests/test_carla_integration.py" +else + # expose X to the container + xhost +local:root + + docker pull ghcr.io/commaai/openpilot-sim:latest + CMD="./tmux_script.sh $*" + EXTRA_ARGS="${EXTRA_ARGS} -it" +fi + docker run --net=host\ --name openpilot_client \ --rm \ - -it \ --gpus all \ --device=/dev/dri:/dev/dri \ --device=/dev/input:/dev/input \ @@ -29,4 +33,4 @@ docker run --net=host\ -w "$OPENPILOT_DIR/tools/sim" \ $EXTRA_ARGS \ ghcr.io/commaai/openpilot-sim:latest \ - /bin/bash -c "./tmux_script.sh $*" + /bin/bash -c "$CMD" diff --git a/tools/sim/test/__init__.py b/tools/sim/tests/__init__.py similarity index 100% rename from tools/sim/test/__init__.py rename to tools/sim/tests/__init__.py diff --git a/tools/sim/test/test_carla_integration.py b/tools/sim/tests/test_carla_integration.py similarity index 85% rename from tools/sim/test/test_carla_integration.py rename to tools/sim/tests/test_carla_integration.py index 8f76abb561..43db783f4e 100755 --- a/tools/sim/test/test_carla_integration.py +++ b/tools/sim/tests/test_carla_integration.py @@ -2,13 +2,18 @@ import subprocess import time import unittest +import os from multiprocessing import Queue from cereal import messaging +from common.basedir import BASEDIR from selfdrive.manager.helpers import unblock_stdout from tools.sim import bridge from tools.sim.bridge import CarlaBridge +CI = "CI" in os.environ + +SIM_DIR = os.path.join(BASEDIR, "tools/sim") class TestCarlaIntegration(unittest.TestCase): """ @@ -19,10 +24,12 @@ class TestCarlaIntegration(unittest.TestCase): def setUp(self): self.processes = [] - # We want to make sure that carla_sim docker isn't still running. - subprocess.run("docker rm -f carla_sim", shell=True, stderr=subprocess.PIPE, check=False) - self.carla_process = subprocess.Popen(".././start_carla.sh") + if not CI: + # We want to make sure that carla_sim docker isn't still running. + subprocess.run("docker rm -f carla_sim", shell=True, stderr=subprocess.PIPE, check=False) + self.carla_process = subprocess.Popen("./start_carla.sh", cwd=SIM_DIR) + # Too many lagging messages in bridge.py can cause a crash. This prevents it. unblock_stdout() # Wait 10 seconds to startup carla @@ -30,16 +37,16 @@ class TestCarlaIntegration(unittest.TestCase): def test_engage(self): # Startup manager and bridge.py. Check processes are running, then engage and verify. - p_manager = subprocess.Popen("./launch_openpilot.sh", cwd='../') + p_manager = subprocess.Popen("./launch_openpilot.sh", cwd=SIM_DIR) self.processes.append(p_manager) sm = messaging.SubMaster(['controlsState', 'carEvents', 'managerState']) q = Queue() carla_bridge = CarlaBridge(bridge.parse_args([])) - p_bridge = carla_bridge.run(q, retries=3) + p_bridge = carla_bridge.run(q, retries=10) self.processes.append(p_bridge) - max_time_per_step = 20 + max_time_per_step = 60 # Wait for bridge to startup start_waiting = time.monotonic() From 1139fe507b01f34de9714c99228f411558b44231 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 11 Jun 2022 16:38:24 -0700 Subject: [PATCH 014/302] Move selfdrive/hardware/ to system/ (#24725) * move hardware to system/ * fix mypy --- Jenkinsfile | 2 +- common/basedir.py | 2 +- common/modeldata.h | 2 +- common/params.cc | 2 +- common/realtime.py | 2 +- common/swaglog.cc | 2 +- common/tests/test_swaglog.cc | 2 +- launch_chffrplus.sh | 6 ++-- release/files_common | 30 +++++++++--------- scripts/disable-powersave.py | 2 +- selfdrive/athena/athenad.py | 2 +- selfdrive/athena/registration.py | 2 +- selfdrive/boardd/boardd.cc | 2 +- selfdrive/boardd/main.cc | 2 +- selfdrive/boardd/pandad.py | 2 +- .../boardd/tests/test_boardd_loopback.py | 2 +- selfdrive/camerad/cameras/camera_common.cc | 2 +- selfdrive/camerad/cameras/camera_common.h | 2 +- selfdrive/camerad/main.cc | 2 +- selfdrive/camerad/snapshot/snapshot.py | 2 +- selfdrive/camerad/test/test_camerad.py | 2 +- selfdrive/camerad/test/test_exposure.py | 2 +- selfdrive/controls/controlsd.py | 2 +- selfdrive/hardware | 1 + selfdrive/loggerd/config.py | 2 +- selfdrive/loggerd/logger.h | 2 +- selfdrive/loggerd/loggerd.h | 2 +- selfdrive/loggerd/tests/test_encoder.py | 2 +- selfdrive/loggerd/uploader.py | 2 +- selfdrive/manager/build.py | 2 +- selfdrive/manager/manager.py | 2 +- selfdrive/manager/process.py | 2 +- selfdrive/manager/process_config.py | 2 +- selfdrive/manager/test/test_manager.py | 2 +- selfdrive/modeld/modeld.cc | 2 +- selfdrive/modeld/models/dmonitoring.cc | 2 +- selfdrive/modeld/thneed/compile.cc | 2 +- selfdrive/sensord/test/test_sensord.py | 2 +- selfdrive/sentry.py | 2 +- selfdrive/statsd.py | 2 +- selfdrive/swaglog.py | 2 +- selfdrive/test/helpers.py | 2 +- selfdrive/test/process_replay/model_replay.py | 2 +- selfdrive/test/process_replay/test_debayer.py | 2 +- selfdrive/thermald/power_monitoring.py | 2 +- selfdrive/thermald/thermald.py | 2 +- selfdrive/timezoned.py | 2 +- selfdrive/ui/main.cc | 2 +- selfdrive/ui/qt/api.cc | 2 +- selfdrive/ui/qt/maps/map_helpers.cc | 2 +- selfdrive/ui/qt/offroad/settings.cc | 2 +- selfdrive/ui/qt/qt_window.h | 2 +- selfdrive/ui/qt/setup/setup.cc | 2 +- selfdrive/ui/qt/setup/updater.cc | 2 +- selfdrive/ui/qt/spinner.cc | 2 +- selfdrive/ui/qt/text.cc | 2 +- selfdrive/ui/qt/util.cc | 2 +- selfdrive/ui/qt/widgets/input.cc | 2 +- selfdrive/ui/qt/widgets/offroad_alerts.cc | 2 +- selfdrive/ui/qt/widgets/ssh_keys.h | 2 +- selfdrive/ui/qt/window.cc | 2 +- selfdrive/ui/replay/replay.cc | 2 +- selfdrive/ui/replay/route.cc | 2 +- selfdrive/ui/soundd/sound.h | 2 +- selfdrive/ui/tests/test_soundd.py | 2 +- selfdrive/ui/ui.cc | 2 +- selfdrive/updated.py | 6 ++-- {selfdrive/hardware/pc => system}/__init__.py | 0 {selfdrive => system}/hardware/.gitignore | 0 {selfdrive => system}/hardware/__init__.py | 6 ++-- {selfdrive => system}/hardware/base.h | 0 {selfdrive => system}/hardware/base.py | 0 {selfdrive => system}/hardware/hw.h | 4 +-- .../tici => system/hardware/pc}/__init__.py | 0 {selfdrive => system}/hardware/pc/hardware.py | 2 +- system/hardware/tici/__init__.py | 0 .../hardware/tici/agnos.json | 0 {selfdrive => system}/hardware/tici/agnos.py | 0 .../hardware/tici/amplifier.py | 0 .../hardware/tici/hardware.h | 2 +- .../hardware/tici/hardware.py | 8 ++--- {selfdrive => system}/hardware/tici/iwlist.py | 0 {selfdrive => system}/hardware/tici/pins.py | 0 .../hardware/tici/power_draw_test.py | 4 +-- .../hardware/tici/power_monitor.py | 0 .../hardware/tici/precise_power_measure.py | 2 +- .../hardware/tici/restart_modem.sh | 0 .../hardware/tici/test_agnos_updater.py | 0 .../hardware/tici/test_power_draw.py | 4 +-- {selfdrive => system}/hardware/tici/updater | Bin tools/lib/auth_config.py | 2 +- 91 files changed, 102 insertions(+), 101 deletions(-) create mode 120000 selfdrive/hardware rename {selfdrive/hardware/pc => system}/__init__.py (100%) rename {selfdrive => system}/hardware/.gitignore (100%) rename {selfdrive => system}/hardware/__init__.py (56%) rename {selfdrive => system}/hardware/base.h (100%) rename {selfdrive => system}/hardware/base.py (100%) rename {selfdrive => system}/hardware/hw.h (92%) rename {selfdrive/hardware/tici => system/hardware/pc}/__init__.py (100%) rename {selfdrive => system}/hardware/pc/hardware.py (96%) create mode 100644 system/hardware/tici/__init__.py rename {selfdrive => system}/hardware/tici/agnos.json (100%) rename {selfdrive => system}/hardware/tici/agnos.py (100%) rename {selfdrive => system}/hardware/tici/amplifier.py (100%) rename {selfdrive => system}/hardware/tici/hardware.h (97%) rename {selfdrive => system}/hardware/tici/hardware.py (98%) rename {selfdrive => system}/hardware/tici/iwlist.py (100%) rename {selfdrive => system}/hardware/tici/pins.py (100%) rename {selfdrive => system}/hardware/tici/power_draw_test.py (97%) rename {selfdrive => system}/hardware/tici/power_monitor.py (100%) rename {selfdrive => system}/hardware/tici/precise_power_measure.py (77%) rename {selfdrive => system}/hardware/tici/restart_modem.sh (100%) rename {selfdrive => system}/hardware/tici/test_agnos_updater.py (100%) rename {selfdrive => system}/hardware/tici/test_power_draw.py (92%) rename {selfdrive => system}/hardware/tici/updater (100%) diff --git a/Jenkinsfile b/Jenkinsfile index fed587bd21..250893d1af 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -123,7 +123,7 @@ pipeline { steps { phone_steps("tici2", [ ["build", "cd selfdrive/manager && ./build.py"], - ["test power draw", "python selfdrive/hardware/tici/test_power_draw.py"], + ["test power draw", "python system/hardware/tici/test_power_draw.py"], ["test boardd loopback", "python selfdrive/boardd/tests/test_boardd_loopback.py"], ["test loggerd", "python selfdrive/loggerd/tests/test_loggerd.py"], ["test encoder", "LD_LIBRARY_PATH=/usr/local/lib python selfdrive/loggerd/tests/test_encoder.py"], diff --git a/common/basedir.py b/common/basedir.py index 8be1cf6afa..371b54d3ef 100644 --- a/common/basedir.py +++ b/common/basedir.py @@ -1,7 +1,7 @@ import os from pathlib import Path -from selfdrive.hardware import PC +from system.hardware import PC BASEDIR = os.path.abspath(os.path.join(os.path.dirname(os.path.realpath(__file__)), "../")) diff --git a/common/modeldata.h b/common/modeldata.h index 06d9398031..aee9fdfd83 100644 --- a/common/modeldata.h +++ b/common/modeldata.h @@ -2,7 +2,7 @@ #include #include "common/mat.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" const int TRAJECTORY_SIZE = 33; const int LAT_MPC_N = 16; diff --git a/common/params.cc b/common/params.cc index 330eddc1a9..b740e5a71e 100644 --- a/common/params.cc +++ b/common/params.cc @@ -8,7 +8,7 @@ #include "common/swaglog.h" #include "common/util.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" namespace { diff --git a/common/realtime.py b/common/realtime.py index 03051c6f67..8a79d8d39f 100644 --- a/common/realtime.py +++ b/common/realtime.py @@ -8,7 +8,7 @@ from typing import Optional, List, Union from setproctitle import getproctitle # pylint: disable=no-name-in-module from common.clock import sec_since_boot # pylint: disable=no-name-in-module, import-error -from selfdrive.hardware import PC +from system.hardware import PC # time step for each process diff --git a/common/swaglog.cc b/common/swaglog.cc index 75223854fe..6b0028326a 100644 --- a/common/swaglog.cc +++ b/common/swaglog.cc @@ -15,7 +15,7 @@ #include "common/util.h" #include "common/version.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" class SwaglogState : public LogState { public: diff --git a/common/tests/test_swaglog.cc b/common/tests/test_swaglog.cc index b54d1d6338..20455ec74c 100644 --- a/common/tests/test_swaglog.cc +++ b/common/tests/test_swaglog.cc @@ -7,7 +7,7 @@ #include "common/swaglog.h" #include "common/util.h" #include "common/version.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" const char *SWAGLOG_ADDR = "ipc:///tmp/logmessage"; std::string daemon_name = "testy"; diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index a37e27c4fe..911774a4eb 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -22,12 +22,12 @@ function agnos_init { # Check if AGNOS update is required if [ $(< /VERSION) != "$AGNOS_VERSION" ]; then - AGNOS_PY="$DIR/selfdrive/hardware/tici/agnos.py" - MANIFEST="$DIR/selfdrive/hardware/tici/agnos.json" + AGNOS_PY="$DIR/system/hardware/tici/agnos.py" + MANIFEST="$DIR/system/hardware/tici/agnos.json" if $AGNOS_PY --verify $MANIFEST; then sudo reboot fi - $DIR/selfdrive/hardware/tici/updater $AGNOS_PY $MANIFEST + $DIR/system/hardware/tici/updater $AGNOS_PY $MANIFEST fi } diff --git a/release/files_common b/release/files_common index 5230511ddd..e89163aba0 100644 --- a/release/files_common +++ b/release/files_common @@ -182,21 +182,21 @@ selfdrive/controls/lib/longitudinal_mpc_lib/.gitignore selfdrive/controls/lib/lateral_mpc_lib/* selfdrive/controls/lib/longitudinal_mpc_lib/* -selfdrive/hardware/__init__.py -selfdrive/hardware/base.h -selfdrive/hardware/base.py -selfdrive/hardware/hw.h -selfdrive/hardware/tici/__init__.py -selfdrive/hardware/tici/hardware.h -selfdrive/hardware/tici/hardware.py -selfdrive/hardware/tici/pins.py -selfdrive/hardware/tici/agnos.py -selfdrive/hardware/tici/agnos.json -selfdrive/hardware/tici/amplifier.py -selfdrive/hardware/tici/updater -selfdrive/hardware/tici/iwlist.py -selfdrive/hardware/pc/__init__.py -selfdrive/hardware/pc/hardware.py +system/hardware/__init__.py +system/hardware/base.h +system/hardware/base.py +system/hardware/hw.h +system/hardware/tici/__init__.py +system/hardware/tici/hardware.h +system/hardware/tici/hardware.py +system/hardware/tici/pins.py +system/hardware/tici/agnos.py +system/hardware/tici/agnos.json +system/hardware/tici/amplifier.py +system/hardware/tici/updater +system/hardware/tici/iwlist.py +system/hardware/pc/__init__.py +system/hardware/pc/hardware.py selfdrive/locationd/__init__.py selfdrive/locationd/.gitignore diff --git a/scripts/disable-powersave.py b/scripts/disable-powersave.py index f651bc87f1..93688504f3 100755 --- a/scripts/disable-powersave.py +++ b/scripts/disable-powersave.py @@ -1,5 +1,5 @@ #!/usr/bin/env python3 -from selfdrive.hardware import HARDWARE +from system.hardware import HARDWARE if __name__ == "__main__": HARDWARE.set_power_save(False) diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index ba86e02cc6..0dc7d704a8 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -32,7 +32,7 @@ from common.basedir import PERSIST from common.file_helpers import CallbackReader from common.params import Params from common.realtime import sec_since_boot, set_core_affinity -from selfdrive.hardware import HARDWARE, PC, AGNOS +from system.hardware import HARDWARE, PC, AGNOS from selfdrive.loggerd.config import ROOT from selfdrive.loggerd.xattr_cache import getxattr, setxattr from selfdrive.statsd import STATS_DIR diff --git a/selfdrive/athena/registration.py b/selfdrive/athena/registration.py index 2748934361..c44ca4c28b 100755 --- a/selfdrive/athena/registration.py +++ b/selfdrive/athena/registration.py @@ -11,7 +11,7 @@ from common.params import Params from common.spinner import Spinner from common.basedir import PERSIST from selfdrive.controls.lib.alertmanager import set_offroad_alert -from selfdrive.hardware import HARDWARE, PC +from system.hardware import HARDWARE, PC from selfdrive.swaglog import cloudlog diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 2745c037b6..f47b5936be 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -27,7 +27,7 @@ #include "common/swaglog.h" #include "common/timing.h" #include "common/util.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/boardd/pigeon.h" diff --git a/selfdrive/boardd/main.cc b/selfdrive/boardd/main.cc index 6f1f83685b..cb17a584bd 100644 --- a/selfdrive/boardd/main.cc +++ b/selfdrive/boardd/main.cc @@ -3,7 +3,7 @@ #include "selfdrive/boardd/boardd.h" #include "common/swaglog.h" #include "common/util.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" int main(int argc, char *argv[]) { LOGW("starting boardd"); diff --git a/selfdrive/boardd/pandad.py b/selfdrive/boardd/pandad.py index 306d764e59..51bfb92dd9 100755 --- a/selfdrive/boardd/pandad.py +++ b/selfdrive/boardd/pandad.py @@ -10,7 +10,7 @@ from functools import cmp_to_key from panda import DEFAULT_FW_FN, DEFAULT_H7_FW_FN, MCU_TYPE_H7, Panda, PandaDFU from common.basedir import BASEDIR from common.params import Params -from selfdrive.hardware import HARDWARE +from system.hardware import HARDWARE from selfdrive.swaglog import cloudlog diff --git a/selfdrive/boardd/tests/test_boardd_loopback.py b/selfdrive/boardd/tests/test_boardd_loopback.py index 631b4c987f..e9bbcb4586 100755 --- a/selfdrive/boardd/tests/test_boardd_loopback.py +++ b/selfdrive/boardd/tests/test_boardd_loopback.py @@ -12,7 +12,7 @@ from common.spinner import Spinner from common.timeout import Timeout from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.car import make_can_msg -from selfdrive.hardware import TICI +from system.hardware import TICI from selfdrive.test.helpers import phone_only, with_processes diff --git a/selfdrive/camerad/cameras/camera_common.cc b/selfdrive/camerad/cameras/camera_common.cc index 049324f085..a94cfedf1a 100644 --- a/selfdrive/camerad/cameras/camera_common.cc +++ b/selfdrive/camerad/cameras/camera_common.cc @@ -15,7 +15,7 @@ #include "common/modeldata.h" #include "common/swaglog.h" #include "common/util.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "msm_media_info.h" #ifdef QCOM2 diff --git a/selfdrive/camerad/cameras/camera_common.h b/selfdrive/camerad/cameras/camera_common.h index 74d6a6eb3f..e9c7ccd757 100644 --- a/selfdrive/camerad/cameras/camera_common.h +++ b/selfdrive/camerad/cameras/camera_common.h @@ -13,7 +13,7 @@ #include "common/mat.h" #include "common/queue.h" #include "common/swaglog.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #define CAMERA_ID_IMX298 0 #define CAMERA_ID_IMX179 1 diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index c86543265c..32899a8547 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -4,7 +4,7 @@ #include "common/params.h" #include "common/util.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" int main(int argc, char *argv[]) { if (!Hardware::PC()) { diff --git a/selfdrive/camerad/snapshot/snapshot.py b/selfdrive/camerad/snapshot/snapshot.py index 9f9072c962..fa88849b69 100755 --- a/selfdrive/camerad/snapshot/snapshot.py +++ b/selfdrive/camerad/snapshot/snapshot.py @@ -9,7 +9,7 @@ import cereal.messaging as messaging from cereal.visionipc import VisionIpcClient, VisionStreamType from common.params import Params from common.realtime import DT_MDL -from selfdrive.hardware import PC +from system.hardware import PC from selfdrive.controls.lib.alertmanager import set_offroad_alert from selfdrive.manager.process_config import managed_processes diff --git a/selfdrive/camerad/test/test_camerad.py b/selfdrive/camerad/test/test_camerad.py index c311c17169..1a2e365a8f 100755 --- a/selfdrive/camerad/test/test_camerad.py +++ b/selfdrive/camerad/test/test_camerad.py @@ -4,7 +4,7 @@ import time import unittest import cereal.messaging as messaging -from selfdrive.hardware import TICI +from system.hardware import TICI from selfdrive.test.helpers import with_processes TEST_TIMESPAN = 30 # random.randint(60, 180) # seconds diff --git a/selfdrive/camerad/test/test_exposure.py b/selfdrive/camerad/test/test_exposure.py index 31bcc28681..f42d0bfbe3 100755 --- a/selfdrive/camerad/test/test_exposure.py +++ b/selfdrive/camerad/test/test_exposure.py @@ -6,7 +6,7 @@ import numpy as np from selfdrive.test.helpers import with_processes from selfdrive.camerad.snapshot.snapshot import get_snapshots -from selfdrive.hardware import TICI +from system.hardware import TICI TEST_TIME = 45 REPEAT = 5 diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index edb1538c31..31807b0187 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -27,7 +27,7 @@ from selfdrive.controls.lib.events import Events, ET from selfdrive.controls.lib.alertmanager import AlertManager, set_offroad_alert from selfdrive.controls.lib.vehicle_model import VehicleModel from selfdrive.locationd.calibrationd import Calibration -from selfdrive.hardware import HARDWARE +from system.hardware import HARDWARE from selfdrive.manager.process_config import managed_processes SOFT_DISABLE_TIME = 3 # seconds diff --git a/selfdrive/hardware b/selfdrive/hardware new file mode 120000 index 0000000000..02a42c502f --- /dev/null +++ b/selfdrive/hardware @@ -0,0 +1 @@ +../system/hardware/ \ No newline at end of file diff --git a/selfdrive/loggerd/config.py b/selfdrive/loggerd/config.py index 6cd20a68ab..168c9fba91 100644 --- a/selfdrive/loggerd/config.py +++ b/selfdrive/loggerd/config.py @@ -1,6 +1,6 @@ import os from pathlib import Path -from selfdrive.hardware import PC +from system.hardware import PC if os.environ.get('LOG_ROOT', False): ROOT = os.environ['LOG_ROOT'] diff --git a/selfdrive/loggerd/logger.h b/selfdrive/loggerd/logger.h index ca08e64717..e7594cee88 100644 --- a/selfdrive/loggerd/logger.h +++ b/selfdrive/loggerd/logger.h @@ -13,7 +13,7 @@ #include "cereal/messaging/messaging.h" #include "common/util.h" #include "common/swaglog.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" const std::string LOG_ROOT = Path::log_root(); diff --git a/selfdrive/loggerd/loggerd.h b/selfdrive/loggerd/loggerd.h index 3b9b01a0fc..7e13e90e63 100644 --- a/selfdrive/loggerd/loggerd.h +++ b/selfdrive/loggerd/loggerd.h @@ -20,7 +20,7 @@ #include "common/swaglog.h" #include "common/timing.h" #include "common/util.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/loggerd/encoder/encoder.h" #include "selfdrive/loggerd/logger.h" diff --git a/selfdrive/loggerd/tests/test_encoder.py b/selfdrive/loggerd/tests/test_encoder.py index 49baa8a6e3..1b9bcef2d7 100755 --- a/selfdrive/loggerd/tests/test_encoder.py +++ b/selfdrive/loggerd/tests/test_encoder.py @@ -13,7 +13,7 @@ from tqdm import trange from common.params import Params from common.timeout import Timeout -from selfdrive.hardware import TICI +from system.hardware import TICI from selfdrive.loggerd.config import ROOT from selfdrive.manager.process_config import managed_processes from tools.lib.logreader import LogReader diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index b7d8df861a..9de1c421bd 100644 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -15,7 +15,7 @@ import cereal.messaging as messaging from common.api import Api from common.params import Params from common.realtime import set_core_affinity -from selfdrive.hardware import TICI +from system.hardware import TICI from selfdrive.loggerd.xattr_cache import getxattr, setxattr from selfdrive.loggerd.config import ROOT from selfdrive.swaglog import cloudlog diff --git a/selfdrive/manager/build.py b/selfdrive/manager/build.py index 8421605a55..f0a5aec927 100755 --- a/selfdrive/manager/build.py +++ b/selfdrive/manager/build.py @@ -10,7 +10,7 @@ from pathlib import Path from common.basedir import BASEDIR from common.spinner import Spinner from common.text_window import TextWindow -from selfdrive.hardware import AGNOS +from system.hardware import AGNOS from selfdrive.swaglog import cloudlog, add_file_handler from selfdrive.version import is_dirty diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index cd7817fa97..94af397c7d 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -13,7 +13,7 @@ from common.basedir import BASEDIR from common.params import Params, ParamKeyType from common.text_window import TextWindow from selfdrive.boardd.set_time import set_time -from selfdrive.hardware import HARDWARE, PC +from system.hardware import HARDWARE, PC from selfdrive.manager.helpers import unblock_stdout from selfdrive.manager.process import ensure_running from selfdrive.manager.process_config import managed_processes diff --git a/selfdrive/manager/process.py b/selfdrive/manager/process.py index e2bb41c217..22f55f3b36 100644 --- a/selfdrive/manager/process.py +++ b/selfdrive/manager/process.py @@ -17,7 +17,7 @@ from common.basedir import BASEDIR from common.params import Params from common.realtime import sec_since_boot from selfdrive.swaglog import cloudlog -from selfdrive.hardware import HARDWARE +from system.hardware import HARDWARE from cereal import log WATCHDOG_FN = "/dev/shm/wd_" diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index 5d996d1169..443ebbb419 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -2,7 +2,7 @@ import os from cereal import car from common.params import Params -from selfdrive.hardware import PC +from system.hardware import PC from selfdrive.manager.process import PythonProcess, NativeProcess, DaemonProcess WEBCAM = os.getenv("USE_WEBCAM") is not None diff --git a/selfdrive/manager/test/test_manager.py b/selfdrive/manager/test/test_manager.py index 31949de0b9..e4c3ef7c4c 100755 --- a/selfdrive/manager/test/test_manager.py +++ b/selfdrive/manager/test/test_manager.py @@ -5,7 +5,7 @@ import time import unittest import selfdrive.manager.manager as manager -from selfdrive.hardware import AGNOS, HARDWARE +from system.hardware import AGNOS, HARDWARE from selfdrive.manager.process import DaemonProcess from selfdrive.manager.process_config import managed_processes diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 10cc2fe56e..0aac9b3c4a 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -11,7 +11,7 @@ #include "common/params.h" #include "common/swaglog.h" #include "common/util.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/modeld/models/driving.h" ExitHandler do_exit; diff --git a/selfdrive/modeld/models/dmonitoring.cc b/selfdrive/modeld/models/dmonitoring.cc index e134ad3a5a..71da8dad53 100644 --- a/selfdrive/modeld/models/dmonitoring.cc +++ b/selfdrive/modeld/models/dmonitoring.cc @@ -6,7 +6,7 @@ #include "common/modeldata.h" #include "common/params.h" #include "common/timing.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/modeld/models/dmonitoring.h" diff --git a/selfdrive/modeld/thneed/compile.cc b/selfdrive/modeld/thneed/compile.cc index 8698ce482e..f76c63b2b9 100644 --- a/selfdrive/modeld/thneed/compile.cc +++ b/selfdrive/modeld/thneed/compile.cc @@ -3,7 +3,7 @@ #include "selfdrive/modeld/runners/snpemodel.h" #include "selfdrive/modeld/thneed/thneed.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #define TEMPORAL_SIZE 512 #define DESIRE_LEN 8 diff --git a/selfdrive/sensord/test/test_sensord.py b/selfdrive/sensord/test/test_sensord.py index 96d8891265..9fd918c971 100755 --- a/selfdrive/sensord/test/test_sensord.py +++ b/selfdrive/sensord/test/test_sensord.py @@ -4,7 +4,7 @@ import time import unittest import cereal.messaging as messaging -from selfdrive.hardware import TICI +from system.hardware import TICI from selfdrive.test.helpers import with_processes TEST_TIMESPAN = 10 diff --git a/selfdrive/sentry.py b/selfdrive/sentry.py index 5f22bf18e0..10e43ee03c 100644 --- a/selfdrive/sentry.py +++ b/selfdrive/sentry.py @@ -5,7 +5,7 @@ from sentry_sdk.integrations.threading import ThreadingIntegration from common.params import Params from selfdrive.athena.registration import is_registered_device -from selfdrive.hardware import HARDWARE, PC +from system.hardware import HARDWARE, PC from selfdrive.swaglog import cloudlog from selfdrive.version import get_branch, get_commit, get_origin, get_version, \ is_comma_remote, is_dirty, is_tested_branch diff --git a/selfdrive/statsd.py b/selfdrive/statsd.py index 5755e5111b..a48ba56003 100755 --- a/selfdrive/statsd.py +++ b/selfdrive/statsd.py @@ -10,7 +10,7 @@ from typing import NoReturn, Union, List, Dict from common.params import Params from cereal.messaging import SubMaster from selfdrive.swaglog import cloudlog -from selfdrive.hardware import HARDWARE +from system.hardware import HARDWARE from common.file_helpers import atomic_write_in_dir from selfdrive.version import get_normalized_origin, get_short_branch, get_short_version, is_dirty from selfdrive.loggerd.config import STATS_DIR, STATS_DIR_FILE_LIMIT, STATS_SOCKET, STATS_FLUSH_TIME_S diff --git a/selfdrive/swaglog.py b/selfdrive/swaglog.py index a987bfe72c..68664330a5 100644 --- a/selfdrive/swaglog.py +++ b/selfdrive/swaglog.py @@ -7,7 +7,7 @@ from logging.handlers import BaseRotatingHandler import zmq from common.logging_extra import SwagLogger, SwagFormatter, SwagLogFileFormatter -from selfdrive.hardware import PC +from system.hardware import PC if PC: SWAGLOG_DIR = os.path.join(str(Path.home()), ".comma", "log") diff --git a/selfdrive/test/helpers.py b/selfdrive/test/helpers.py index 5abc0d964f..cc8efd6e46 100644 --- a/selfdrive/test/helpers.py +++ b/selfdrive/test/helpers.py @@ -2,7 +2,7 @@ import os import time from functools import wraps -from selfdrive.hardware import PC +from system.hardware import PC from selfdrive.manager.process_config import managed_processes from selfdrive.version import training_version, terms_version diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index b83629c76a..b466aa8193 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -11,7 +11,7 @@ from cereal.visionipc import VisionIpcServer, VisionStreamType from common.spinner import Spinner from common.timeout import Timeout from common.transformations.camera import get_view_frame_from_road_frame, tici_f_frame_size, tici_d_frame_size -from selfdrive.hardware import PC +from system.hardware import PC from selfdrive.manager.process_config import managed_processes from selfdrive.test.openpilotci import BASE_URL, get_url from selfdrive.test.process_replay.compare_logs import compare_logs, save_log diff --git a/selfdrive/test/process_replay/test_debayer.py b/selfdrive/test/process_replay/test_debayer.py index a17c71b602..cf939e3672 100755 --- a/selfdrive/test/process_replay/test_debayer.py +++ b/selfdrive/test/process_replay/test_debayer.py @@ -6,7 +6,7 @@ import numpy as np import pyopencl as cl # install with `PYOPENCL_CL_PRETEND_VERSION=2.0 pip install pyopencl` -from selfdrive.hardware import PC, TICI +from system.hardware import PC, TICI from common.basedir import BASEDIR from selfdrive.test.openpilotci import BASE_URL, get_url from selfdrive.version import get_commit diff --git a/selfdrive/thermald/power_monitoring.py b/selfdrive/thermald/power_monitoring.py index d7a1f2a360..acc2fd90bc 100644 --- a/selfdrive/thermald/power_monitoring.py +++ b/selfdrive/thermald/power_monitoring.py @@ -4,7 +4,7 @@ from typing import Optional from cereal import log from common.params import Params, put_nonblocking from common.realtime import sec_since_boot -from selfdrive.hardware import HARDWARE +from system.hardware import HARDWARE from selfdrive.swaglog import cloudlog from selfdrive.statsd import statlog diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 4df1e072b8..84663e8eb0 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -17,7 +17,7 @@ from common.filter_simple import FirstOrderFilter from common.params import Params from common.realtime import DT_TRML, sec_since_boot from selfdrive.controls.lib.alertmanager import set_offroad_alert -from selfdrive.hardware import HARDWARE, TICI, AGNOS +from system.hardware import HARDWARE, TICI, AGNOS from selfdrive.loggerd.config import get_available_percent from selfdrive.statsd import statlog from selfdrive.swaglog import cloudlog diff --git a/selfdrive/timezoned.py b/selfdrive/timezoned.py index fc1ca92cdf..c1d5676db6 100755 --- a/selfdrive/timezoned.py +++ b/selfdrive/timezoned.py @@ -9,7 +9,7 @@ import requests from timezonefinder import TimezoneFinder from common.params import Params -from selfdrive.hardware import AGNOS +from system.hardware import AGNOS from selfdrive.swaglog import cloudlog diff --git a/selfdrive/ui/main.cc b/selfdrive/ui/main.cc index cffa459622..1eecd78b19 100644 --- a/selfdrive/ui/main.cc +++ b/selfdrive/ui/main.cc @@ -2,7 +2,7 @@ #include -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/window.h" diff --git a/selfdrive/ui/qt/api.cc b/selfdrive/ui/qt/api.cc index 94beb12186..84e1a4032e 100644 --- a/selfdrive/ui/qt/api.cc +++ b/selfdrive/ui/qt/api.cc @@ -14,7 +14,7 @@ #include "common/params.h" #include "common/util.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/ui/qt/util.h" namespace CommaApi { diff --git a/selfdrive/ui/qt/maps/map_helpers.cc b/selfdrive/ui/qt/maps/map_helpers.cc index 83576eb630..2b2c27418e 100644 --- a/selfdrive/ui/qt/maps/map_helpers.cc +++ b/selfdrive/ui/qt/maps/map_helpers.cc @@ -4,7 +4,7 @@ #include #include "common/params.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/ui/qt/api.h" QString get_mapbox_token() { diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index ac6f1f1ba0..175e6cf5a3 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -14,7 +14,7 @@ #include "common/params.h" #include "common/util.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/ui/qt/widgets/controls.h" #include "selfdrive/ui/qt/widgets/input.h" #include "selfdrive/ui/qt/widgets/scrollview.h" diff --git a/selfdrive/ui/qt/qt_window.h b/selfdrive/ui/qt/qt_window.h index 2c9a24e55b..02d127e7ff 100644 --- a/selfdrive/ui/qt/qt_window.h +++ b/selfdrive/ui/qt/qt_window.h @@ -12,7 +12,7 @@ #include #endif -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" const QString ASSET_PATH = ":/"; diff --git a/selfdrive/ui/qt/setup/setup.cc b/selfdrive/ui/qt/setup/setup.cc index 0da1752fed..10a2d05f34 100644 --- a/selfdrive/ui/qt/setup/setup.cc +++ b/selfdrive/ui/qt/setup/setup.cc @@ -11,7 +11,7 @@ #include #include "common/util.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/ui/qt/api.h" #include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/ui/qt/offroad/networking.h" diff --git a/selfdrive/ui/qt/setup/updater.cc b/selfdrive/ui/qt/setup/updater.cc index b906b5739d..6e8189f4ba 100644 --- a/selfdrive/ui/qt/setup/updater.cc +++ b/selfdrive/ui/qt/setup/updater.cc @@ -2,7 +2,7 @@ #include #include -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/ui/qt/setup/updater.h" diff --git a/selfdrive/ui/qt/spinner.cc b/selfdrive/ui/qt/spinner.cc index e0b263227b..8f13576fb2 100644 --- a/selfdrive/ui/qt/spinner.cc +++ b/selfdrive/ui/qt/spinner.cc @@ -10,7 +10,7 @@ #include #include -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/ui/qt/util.h" diff --git a/selfdrive/ui/qt/text.cc b/selfdrive/ui/qt/text.cc index 04fda35483..ac8e7bcd18 100644 --- a/selfdrive/ui/qt/text.cc +++ b/selfdrive/ui/qt/text.cc @@ -5,7 +5,7 @@ #include #include -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/ui/qt/widgets/scrollview.h" diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc index 7ce7a267df..600885fb37 100644 --- a/selfdrive/ui/qt/util.cc +++ b/selfdrive/ui/qt/util.cc @@ -6,7 +6,7 @@ #include "common/params.h" #include "common/swaglog.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" QString getVersion() { static QString version = QString::fromStdString(Params().get("Version")); diff --git a/selfdrive/ui/qt/widgets/input.cc b/selfdrive/ui/qt/widgets/input.cc index 1122faf4c7..8a5d492804 100644 --- a/selfdrive/ui/qt/widgets/input.cc +++ b/selfdrive/ui/qt/widgets/input.cc @@ -2,7 +2,7 @@ #include -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/ui/qt/widgets/scrollview.h" diff --git a/selfdrive/ui/qt/widgets/offroad_alerts.cc b/selfdrive/ui/qt/widgets/offroad_alerts.cc index 53f7eb677c..433193df5d 100644 --- a/selfdrive/ui/qt/widgets/offroad_alerts.cc +++ b/selfdrive/ui/qt/widgets/offroad_alerts.cc @@ -5,7 +5,7 @@ #include #include "common/util.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/ui/qt/widgets/scrollview.h" AbstractAlert::AbstractAlert(bool hasRebootBtn, QWidget *parent) : QFrame(parent) { diff --git a/selfdrive/ui/qt/widgets/ssh_keys.h b/selfdrive/ui/qt/widgets/ssh_keys.h index 0614e8c1d8..596d1d83b9 100644 --- a/selfdrive/ui/qt/widgets/ssh_keys.h +++ b/selfdrive/ui/qt/widgets/ssh_keys.h @@ -2,7 +2,7 @@ #include -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/ui/qt/widgets/controls.h" // SSH enable toggle diff --git a/selfdrive/ui/qt/window.cc b/selfdrive/ui/qt/window.cc index fb21f6f7af..d9613df0d0 100644 --- a/selfdrive/ui/qt/window.cc +++ b/selfdrive/ui/qt/window.cc @@ -2,7 +2,7 @@ #include -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" MainWindow::MainWindow(QWidget *parent) : QWidget(parent) { main_layout = new QStackedLayout(this); diff --git a/selfdrive/ui/replay/replay.cc b/selfdrive/ui/replay/replay.cc index 4036086e1b..5eb7469c92 100644 --- a/selfdrive/ui/replay/replay.cc +++ b/selfdrive/ui/replay/replay.cc @@ -7,7 +7,7 @@ #include "cereal/services.h" #include "common/params.h" #include "common/timing.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/ui/replay/util.h" Replay::Replay(QString route, QStringList allow, QStringList block, SubMaster *sm_, uint32_t flags, QString data_dir, QObject *parent) diff --git a/selfdrive/ui/replay/route.cc b/selfdrive/ui/replay/route.cc index ad93263ae9..3d595141cd 100644 --- a/selfdrive/ui/replay/route.cc +++ b/selfdrive/ui/replay/route.cc @@ -9,7 +9,7 @@ #include -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/ui/qt/api.h" #include "selfdrive/ui/replay/replay.h" #include "selfdrive/ui/replay/util.h" diff --git a/selfdrive/ui/soundd/sound.h b/selfdrive/ui/soundd/sound.h index 82b360fd38..7e009d28ad 100644 --- a/selfdrive/ui/soundd/sound.h +++ b/selfdrive/ui/soundd/sound.h @@ -2,7 +2,7 @@ #include #include -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #include "selfdrive/ui/ui.h" const std::tuple sound_list[] = { diff --git a/selfdrive/ui/tests/test_soundd.py b/selfdrive/ui/tests/test_soundd.py index cba0f6dbd1..8cc9215b74 100755 --- a/selfdrive/ui/tests/test_soundd.py +++ b/selfdrive/ui/tests/test_soundd.py @@ -8,7 +8,7 @@ import cereal.messaging as messaging from selfdrive.test.helpers import phone_only, with_processes # TODO: rewrite for unittest from common.realtime import DT_CTRL -from selfdrive.hardware import HARDWARE +from system.hardware import HARDWARE AudibleAlert = car.CarControl.HUDControl.AudibleAlert diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index c1af4ed6f4..4d1e1ab746 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -10,7 +10,7 @@ #include "common/swaglog.h" #include "common/util.h" #include "common/watchdog.h" -#include "selfdrive/hardware/hw.h" +#include "system/hardware/hw.h" #define BACKLIGHT_DT 0.05 #define BACKLIGHT_TS 10.00 diff --git a/selfdrive/updated.py b/selfdrive/updated.py index f835522cdb..33e2d5d418 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -37,7 +37,7 @@ from markdown_it import MarkdownIt from common.basedir import BASEDIR from common.params import Params -from selfdrive.hardware import AGNOS, HARDWARE +from system.hardware import AGNOS, HARDWARE from selfdrive.swaglog import cloudlog from selfdrive.controls.lib.alertmanager import set_offroad_alert from selfdrive.version import is_tested_branch @@ -265,7 +265,7 @@ def finalize_update(wait_helper: WaitTimeHelper) -> None: def handle_agnos_update(wait_helper: WaitTimeHelper) -> None: - from selfdrive.hardware.tici.agnos import flash_agnos_update, get_target_slot_number + from system.hardware.tici.agnos import flash_agnos_update, get_target_slot_number cur_version = HARDWARE.get_os_version() updated_version = run(["bash", "-c", r"unset AGNOS_VERSION && source launch_env.sh && \ @@ -281,7 +281,7 @@ def handle_agnos_update(wait_helper: WaitTimeHelper) -> None: cloudlog.info(f"Beginning background installation for AGNOS {updated_version}") set_offroad_alert("Offroad_NeosUpdate", True) - manifest_path = os.path.join(OVERLAY_MERGED, "selfdrive/hardware/tici/agnos.json") + manifest_path = os.path.join(OVERLAY_MERGED, "system/hardware/tici/agnos.json") target_slot_number = get_target_slot_number() flash_agnos_update(manifest_path, target_slot_number, cloudlog) set_offroad_alert("Offroad_NeosUpdate", False) diff --git a/selfdrive/hardware/pc/__init__.py b/system/__init__.py similarity index 100% rename from selfdrive/hardware/pc/__init__.py rename to system/__init__.py diff --git a/selfdrive/hardware/.gitignore b/system/hardware/.gitignore similarity index 100% rename from selfdrive/hardware/.gitignore rename to system/hardware/.gitignore diff --git a/selfdrive/hardware/__init__.py b/system/hardware/__init__.py similarity index 56% rename from selfdrive/hardware/__init__.py rename to system/hardware/__init__.py index a1bf2e912f..780a20f9c0 100644 --- a/selfdrive/hardware/__init__.py +++ b/system/hardware/__init__.py @@ -1,9 +1,9 @@ import os from typing import cast -from selfdrive.hardware.base import HardwareBase -from selfdrive.hardware.tici.hardware import Tici -from selfdrive.hardware.pc.hardware import Pc +from system.hardware.base import HardwareBase +from system.hardware.tici.hardware import Tici +from system.hardware.pc.hardware import Pc TICI = os.path.isfile('/TICI') AGNOS = TICI diff --git a/selfdrive/hardware/base.h b/system/hardware/base.h similarity index 100% rename from selfdrive/hardware/base.h rename to system/hardware/base.h diff --git a/selfdrive/hardware/base.py b/system/hardware/base.py similarity index 100% rename from selfdrive/hardware/base.py rename to system/hardware/base.py diff --git a/selfdrive/hardware/hw.h b/system/hardware/hw.h similarity index 92% rename from selfdrive/hardware/hw.h rename to system/hardware/hw.h index 364a1c5c33..f50e94abe1 100644 --- a/selfdrive/hardware/hw.h +++ b/system/hardware/hw.h @@ -1,10 +1,10 @@ #pragma once -#include "selfdrive/hardware/base.h" +#include "system/hardware/base.h" #include "common/util.h" #if QCOM2 -#include "selfdrive/hardware/tici/hardware.h" +#include "system/hardware/tici/hardware.h" #define Hardware HardwareTici #else class HardwarePC : public HardwareNone { diff --git a/selfdrive/hardware/tici/__init__.py b/system/hardware/pc/__init__.py similarity index 100% rename from selfdrive/hardware/tici/__init__.py rename to system/hardware/pc/__init__.py diff --git a/selfdrive/hardware/pc/hardware.py b/system/hardware/pc/hardware.py similarity index 96% rename from selfdrive/hardware/pc/hardware.py rename to system/hardware/pc/hardware.py index 2f5db925a9..b2c4a4343b 100644 --- a/selfdrive/hardware/pc/hardware.py +++ b/system/hardware/pc/hardware.py @@ -1,7 +1,7 @@ import random from cereal import log -from selfdrive.hardware.base import HardwareBase, ThermalConfig +from system.hardware.base import HardwareBase, ThermalConfig NetworkType = log.DeviceState.NetworkType NetworkStrength = log.DeviceState.NetworkStrength diff --git a/system/hardware/tici/__init__.py b/system/hardware/tici/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/hardware/tici/agnos.json b/system/hardware/tici/agnos.json similarity index 100% rename from selfdrive/hardware/tici/agnos.json rename to system/hardware/tici/agnos.json diff --git a/selfdrive/hardware/tici/agnos.py b/system/hardware/tici/agnos.py similarity index 100% rename from selfdrive/hardware/tici/agnos.py rename to system/hardware/tici/agnos.py diff --git a/selfdrive/hardware/tici/amplifier.py b/system/hardware/tici/amplifier.py similarity index 100% rename from selfdrive/hardware/tici/amplifier.py rename to system/hardware/tici/amplifier.py diff --git a/selfdrive/hardware/tici/hardware.h b/system/hardware/tici/hardware.h similarity index 97% rename from selfdrive/hardware/tici/hardware.h rename to system/hardware/tici/hardware.h index b11a0a5bb0..dcccb9f3d1 100644 --- a/selfdrive/hardware/tici/hardware.h +++ b/system/hardware/tici/hardware.h @@ -5,7 +5,7 @@ #include "common/params.h" #include "common/util.h" -#include "selfdrive/hardware/base.h" +#include "system/hardware/base.h" class HardwareTici : public HardwareNone { public: diff --git a/selfdrive/hardware/tici/hardware.py b/system/hardware/tici/hardware.py similarity index 98% rename from selfdrive/hardware/tici/hardware.py rename to system/hardware/tici/hardware.py index 0a92340598..a69d3eb743 100644 --- a/selfdrive/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -9,10 +9,10 @@ from pathlib import Path from cereal import log from common.gpio import gpio_set, gpio_init -from selfdrive.hardware.base import HardwareBase, ThermalConfig -from selfdrive.hardware.tici import iwlist -from selfdrive.hardware.tici.pins import GPIO -from selfdrive.hardware.tici.amplifier import Amplifier +from system.hardware.base import HardwareBase, ThermalConfig +from system.hardware.tici import iwlist +from system.hardware.tici.pins import GPIO +from system.hardware.tici.amplifier import Amplifier NM = 'org.freedesktop.NetworkManager' NM_CON_ACT = NM + '.Connection.Active' diff --git a/selfdrive/hardware/tici/iwlist.py b/system/hardware/tici/iwlist.py similarity index 100% rename from selfdrive/hardware/tici/iwlist.py rename to system/hardware/tici/iwlist.py diff --git a/selfdrive/hardware/tici/pins.py b/system/hardware/tici/pins.py similarity index 100% rename from selfdrive/hardware/tici/pins.py rename to system/hardware/tici/pins.py diff --git a/selfdrive/hardware/tici/power_draw_test.py b/system/hardware/tici/power_draw_test.py similarity index 97% rename from selfdrive/hardware/tici/power_draw_test.py rename to system/hardware/tici/power_draw_test.py index 1af51fc018..bde92ae4a5 100755 --- a/selfdrive/hardware/tici/power_draw_test.py +++ b/system/hardware/tici/power_draw_test.py @@ -2,8 +2,8 @@ import os import time import numpy as np -from selfdrive.hardware.tici.hardware import Tici -from selfdrive.hardware.tici.pins import GPIO +from system.hardware.tici.hardware import Tici +from system.hardware.tici.pins import GPIO from common.gpio import gpio_init, gpio_set def read_power(): diff --git a/selfdrive/hardware/tici/power_monitor.py b/system/hardware/tici/power_monitor.py similarity index 100% rename from selfdrive/hardware/tici/power_monitor.py rename to system/hardware/tici/power_monitor.py diff --git a/selfdrive/hardware/tici/precise_power_measure.py b/system/hardware/tici/precise_power_measure.py similarity index 77% rename from selfdrive/hardware/tici/precise_power_measure.py rename to system/hardware/tici/precise_power_measure.py index c66936aef8..5d68851367 100755 --- a/selfdrive/hardware/tici/precise_power_measure.py +++ b/system/hardware/tici/precise_power_measure.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 import numpy as np -from selfdrive.hardware.tici.power_monitor import sample_power +from system.hardware.tici.power_monitor import sample_power if __name__ == '__main__': print("measuring for 5 seconds") diff --git a/selfdrive/hardware/tici/restart_modem.sh b/system/hardware/tici/restart_modem.sh similarity index 100% rename from selfdrive/hardware/tici/restart_modem.sh rename to system/hardware/tici/restart_modem.sh diff --git a/selfdrive/hardware/tici/test_agnos_updater.py b/system/hardware/tici/test_agnos_updater.py similarity index 100% rename from selfdrive/hardware/tici/test_agnos_updater.py rename to system/hardware/tici/test_agnos_updater.py diff --git a/selfdrive/hardware/tici/test_power_draw.py b/system/hardware/tici/test_power_draw.py similarity index 92% rename from selfdrive/hardware/tici/test_power_draw.py rename to system/hardware/tici/test_power_draw.py index ab2d691a09..31b8471328 100755 --- a/selfdrive/hardware/tici/test_power_draw.py +++ b/system/hardware/tici/test_power_draw.py @@ -4,8 +4,8 @@ import time import math from dataclasses import dataclass -from selfdrive.hardware import HARDWARE, TICI -from selfdrive.hardware.tici.power_monitor import get_power +from system.hardware import HARDWARE, TICI +from system.hardware.tici.power_monitor import get_power from selfdrive.manager.process_config import managed_processes from selfdrive.manager.manager import manager_cleanup diff --git a/selfdrive/hardware/tici/updater b/system/hardware/tici/updater similarity index 100% rename from selfdrive/hardware/tici/updater rename to system/hardware/tici/updater diff --git a/tools/lib/auth_config.py b/tools/lib/auth_config.py index 1699d94e53..7952fee495 100644 --- a/tools/lib/auth_config.py +++ b/tools/lib/auth_config.py @@ -1,7 +1,7 @@ import json import os from common.file_helpers import mkdirs_exists_ok -from selfdrive.hardware import PC +from system.hardware import PC class MissingAuthConfigError(Exception): From 6856c2d4efda54708be3790bb094b5c377dee575 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 11 Jun 2022 17:43:34 -0700 Subject: [PATCH 015/302] jenkins: remove unnecessary workstation clean --- Jenkinsfile | 5 ----- 1 file changed, 5 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 250893d1af..9d1ab33761 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -154,11 +154,6 @@ pipeline { } } - post { - always { - cleanWs() - } - } } } } From 83c5d2ede6c058a8eb723933a45bd3abc810bf51 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 11 Jun 2022 17:56:59 -0700 Subject: [PATCH 016/302] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index a197e38c0c..78870ba056 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit a197e38c0cef00ececf4c7500438d37659d9199e +Subproject commit 78870ba056174352218988610e5010fde4eca956 From 9cda2d63380dc9b554212ba15e82ca0621ab1945 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 11 Jun 2022 18:43:24 -0700 Subject: [PATCH 017/302] set AGNOS from /AGNOS file --- system/hardware/__init__.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/hardware/__init__.py b/system/hardware/__init__.py index 780a20f9c0..77bb0e5e2a 100644 --- a/system/hardware/__init__.py +++ b/system/hardware/__init__.py @@ -6,7 +6,7 @@ from system.hardware.tici.hardware import Tici from system.hardware.pc.hardware import Pc TICI = os.path.isfile('/TICI') -AGNOS = TICI +AGNOS = os.path.isfile('/AGNOS') PC = not TICI From fbd98b0e541b89f477061bab34dfc41495ac9399 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 11 Jun 2022 22:51:09 -0700 Subject: [PATCH 018/302] CI: add build job for latest Ubuntu (#24637) * CI: add build job for latest Ubuntu * source * source env * scons cache * cache pyenv * fix key * source --- .github/workflows/selfdrive_tests.yaml | 2 +- .github/workflows/tools_tests.yaml | 40 ++++++++++++++++++++++++++ 2 files changed, 41 insertions(+), 1 deletion(-) diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 567fc05aa5..5bd9acc200 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -94,7 +94,7 @@ jobs: run: | ${{ env.RUN }} "scons -j$(nproc) --extras --test && \ rm -rf /tmp/scons_cache/* && \ - scons -j$(nproc) --cache-populate" + scons -j$(nproc) --extras --test --cache-populate" #build_mac: # name: build macos diff --git a/.github/workflows/tools_tests.yaml b/.github/workflows/tools_tests.yaml index 1e4ce7a4ae..b2433fba8f 100644 --- a/.github/workflows/tools_tests.yaml +++ b/.github/workflows/tools_tests.yaml @@ -21,6 +21,46 @@ env: GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/comma_download_cache:/tmp/comma_download_cache $BASE_IMAGE /bin/sh -c jobs: + build_latest_ubuntu: + name: build latest ubuntu + runs-on: ubuntu-20.04 + timeout-minutes: 60 + steps: + - uses: actions/checkout@v3 + with: + submodules: true + - name: Cache pyenv + id: ubuntu-latest-pyenv + uses: actions/cache@v3 + with: + path: | + ~/.pyenv + ~/.local/share/virtualenvs/ + key: ubuntu-latest-python-${{ hashFiles('tools/ubuntu_setup.sh') }}- + - name: Cache scons + id: ubuntu-latest-scons + uses: actions/cache@v3 + with: + path: /tmp/scons_cache + key: ubuntu-latest-scons-${{ hashFiles('.github/workflows/tools_test.yaml') }}- + restore-keys: | + ubuntu-latest-scons-${{ hashFiles('.github/workflows/tools_test.yaml') }}- + ubuntu-latest-scons- + + - name: tools/ubuntu_setup.sh + run: | + source tools/openpilot_env.sh + tools/ubuntu_setup.sh + - name: Build openpilot + run: | + source tools/openpilot_env.sh + pipenv run scons -j$(nproc) --extras --test + - name: Cleanup scons cache + run: | + source tools/openpilot_env.sh + rm -rf /tmp/scons_cache/* + pipenv run scons -j$(nproc) --extras --test --cache-populate + plotjuggler: name: plotjuggler runs-on: ubuntu-20.04 From 0fce5d90459b77bf2cfa70f55f322f0e1fb8d01c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 11 Jun 2022 23:19:27 -0700 Subject: [PATCH 019/302] Move a bunch of stuff to system/ part 3 (#24829) * move swaglog.py * timezoned * logmessaged * version.py * fix linter --- .pylintrc | 2 +- common/api/__init__.py | 2 +- docs/conf.py | 6 ++++-- release/files_common | 8 ++++---- release/files_tici | 2 +- selfdrive/athena/athenad.py | 4 ++-- selfdrive/athena/manage_athenad.py | 4 ++-- selfdrive/athena/registration.py | 2 +- selfdrive/athena/tests/test_athenad.py | 2 +- selfdrive/boardd/pandad.py | 2 +- selfdrive/boardd/tests/boardd_old.py | 2 +- selfdrive/car/car_helpers.py | 4 ++-- selfdrive/car/disable_ecu.py | 2 +- selfdrive/car/fw_versions.py | 2 +- selfdrive/car/isotp_parallel_query.py | 2 +- selfdrive/car/mock/interface.py | 2 +- selfdrive/car/vin.py | 2 +- selfdrive/controls/controlsd.py | 2 +- selfdrive/controls/lib/events.py | 2 +- selfdrive/controls/lib/lane_planner.py | 2 +- selfdrive/controls/lib/lateral_planner.py | 2 +- .../controls/lib/longitudinal_mpc_lib/long_mpc.py | 2 +- selfdrive/controls/lib/longitudinal_planner.py | 2 +- selfdrive/controls/plannerd.py | 2 +- selfdrive/controls/radard.py | 2 +- selfdrive/debug/disable_ecu.py | 2 +- selfdrive/locationd/calibrationd.py | 2 +- selfdrive/locationd/laikad.py | 2 +- selfdrive/locationd/models/car_kf.py | 2 +- selfdrive/locationd/paramsd.py | 2 +- selfdrive/loggerd/deleter.py | 2 +- selfdrive/loggerd/tests/test_loggerd.py | 2 +- selfdrive/loggerd/tests/test_uploader.py | 2 +- selfdrive/loggerd/uploader.py | 2 +- selfdrive/manager/build.py | 4 ++-- selfdrive/manager/manager.py | 4 ++-- selfdrive/manager/process.py | 2 +- selfdrive/manager/process_config.py | 11 ++++++----- selfdrive/navd/navd.py | 2 +- selfdrive/sensord/rawgps/rawgpsd.py | 2 +- selfdrive/sentry.py | 4 ++-- selfdrive/statsd.py | 4 ++-- selfdrive/test/helpers.py | 2 +- selfdrive/test/process_replay/model_replay.py | 2 +- selfdrive/test/process_replay/test_debayer.py | 2 +- selfdrive/test/process_replay/test_processes.py | 2 +- selfdrive/test/test_onroad.py | 2 +- selfdrive/thermald/fan_controller.py | 2 +- selfdrive/thermald/power_monitoring.py | 2 +- selfdrive/thermald/thermald.py | 4 ++-- selfdrive/tombstoned.py | 4 ++-- selfdrive/updated.py | 4 ++-- {selfdrive => system}/logmessaged.py | 2 +- {selfdrive => system}/swaglog.py | 0 {selfdrive => system}/timezoned.py | 2 +- {selfdrive => system}/version.py | 2 +- 56 files changed, 76 insertions(+), 73 deletions(-) rename {selfdrive => system}/logmessaged.py (95%) rename {selfdrive => system}/swaglog.py (100%) rename {selfdrive => system}/timezoned.py (98%) rename {selfdrive => system}/version.py (99%) diff --git a/.pylintrc b/.pylintrc index 27539b743c..58988c5d74 100644 --- a/.pylintrc +++ b/.pylintrc @@ -3,7 +3,7 @@ # A comma-separated list of package or module names from where C extensions may # be loaded. Extensions are loading into the active Python interpreter and may # run arbitrary code -extension-pkg-whitelist=scipy,cereal.messaging.messaging_pyx,PyQt5 +extension-pkg-whitelist=scipy,cereal.messaging.messaging_pyx,PyQt5,av # Add files or directories to the blacklist. They should be base names, not # paths. diff --git a/common/api/__init__.py b/common/api/__init__.py index fd2e70910e..c1fa635bd6 100644 --- a/common/api/__init__.py +++ b/common/api/__init__.py @@ -3,7 +3,7 @@ import os import requests from datetime import datetime, timedelta from common.basedir import PERSIST -from selfdrive.version import get_version +from system.version import get_version API_HOST = os.getenv('API_HOST', 'https://api.commadotai.com') diff --git a/docs/conf.py b/docs/conf.py index c11d17455d..fea921de1f 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -14,10 +14,12 @@ # documentation root, use os.path.abspath to make it absolute, like shown here. # import os -from os.path import exists import sys -from selfdrive.version import get_version +from os.path import exists + from common.basedir import BASEDIR +from system.version import get_version + sys.path.insert(0, os.path.abspath('.')) sys.path.insert(0, os.path.abspath('..')) diff --git a/release/files_common b/release/files_common index e89163aba0..76d440c402 100644 --- a/release/files_common +++ b/release/files_common @@ -61,17 +61,17 @@ release/* tools/lib/* tools/joystick/* -selfdrive/version.py - selfdrive/__init__.py selfdrive/sentry.py -selfdrive/swaglog.py -selfdrive/logmessaged.py selfdrive/tombstoned.py selfdrive/updated.py selfdrive/rtshield.py selfdrive/statsd.py +system/logmessaged.py +system/swaglog.py +system/version.py + selfdrive/athena/__init__.py selfdrive/athena/athenad.py selfdrive/athena/manage_athenad.py diff --git a/release/files_tici b/release/files_tici index ee1ac63c34..485a898799 100644 --- a/release/files_tici +++ b/release/files_tici @@ -2,7 +2,7 @@ third_party/snpe/larch64** third_party/snpe/aarch64-ubuntu-gcc7.5/* third_party/mapbox-gl-native-qt/include/* -selfdrive/timezoned.py +system/timezoned.py selfdrive/assets/navigation/* selfdrive/assets/training_wide/* diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index 0dc7d704a8..26220dfa99 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -36,8 +36,8 @@ from system.hardware import HARDWARE, PC, AGNOS from selfdrive.loggerd.config import ROOT from selfdrive.loggerd.xattr_cache import getxattr, setxattr from selfdrive.statsd import STATS_DIR -from selfdrive.swaglog import SWAGLOG_DIR, cloudlog -from selfdrive.version import get_commit, get_origin, get_short_branch, get_version +from system.swaglog import SWAGLOG_DIR, cloudlog +from system.version import get_commit, get_origin, get_short_branch, get_version ATHENA_HOST = os.getenv('ATHENA_HOST', 'wss://athena.comma.ai') HANDLER_THREADS = int(os.getenv('HANDLER_THREADS', "4")) diff --git a/selfdrive/athena/manage_athenad.py b/selfdrive/athena/manage_athenad.py index 58ad58310f..6bbb03a799 100755 --- a/selfdrive/athena/manage_athenad.py +++ b/selfdrive/athena/manage_athenad.py @@ -5,8 +5,8 @@ from multiprocessing import Process from common.params import Params from selfdrive.manager.process import launcher -from selfdrive.swaglog import cloudlog -from selfdrive.version import get_version, is_dirty +from system.swaglog import cloudlog +from system.version import get_version, is_dirty ATHENA_MGR_PID_PARAM = "AthenadPid" diff --git a/selfdrive/athena/registration.py b/selfdrive/athena/registration.py index c44ca4c28b..32bc92059c 100755 --- a/selfdrive/athena/registration.py +++ b/selfdrive/athena/registration.py @@ -12,7 +12,7 @@ from common.spinner import Spinner from common.basedir import PERSIST from selfdrive.controls.lib.alertmanager import set_offroad_alert from system.hardware import HARDWARE, PC -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog UNREGISTERED_DONGLE_ID = "UnregisteredDevice" diff --git a/selfdrive/athena/tests/test_athenad.py b/selfdrive/athena/tests/test_athenad.py index a0b308c216..382b549c1b 100755 --- a/selfdrive/athena/tests/test_athenad.py +++ b/selfdrive/athena/tests/test_athenad.py @@ -16,7 +16,7 @@ from unittest import mock from websocket import ABNF from websocket._exceptions import WebSocketConnectionClosedException -from selfdrive import swaglog +from system import swaglog from selfdrive.athena import athenad from selfdrive.athena.athenad import MAX_RETRY_COUNT, dispatcher from selfdrive.athena.tests.helpers import MockWebsocket, MockParams, MockApi, EchoSocket, with_http_server diff --git a/selfdrive/boardd/pandad.py b/selfdrive/boardd/pandad.py index 51bfb92dd9..54a28a6782 100755 --- a/selfdrive/boardd/pandad.py +++ b/selfdrive/boardd/pandad.py @@ -11,7 +11,7 @@ from panda import DEFAULT_FW_FN, DEFAULT_H7_FW_FN, MCU_TYPE_H7, Panda, PandaDFU from common.basedir import BASEDIR from common.params import Params from system.hardware import HARDWARE -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog def get_expected_signature(panda: Panda) -> bytes: diff --git a/selfdrive/boardd/tests/boardd_old.py b/selfdrive/boardd/tests/boardd_old.py index 5e740fbcd8..fad29f6f34 100755 --- a/selfdrive/boardd/tests/boardd_old.py +++ b/selfdrive/boardd/tests/boardd_old.py @@ -13,7 +13,7 @@ import time import cereal.messaging as messaging from common.realtime import Ratekeeper -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog from selfdrive.boardd.boardd import can_capnp_to_can_list from cereal import car diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 7863f0d882..3bfd99f88d 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -4,12 +4,12 @@ from typing import Dict, List from cereal import car from common.params import Params from common.basedir import BASEDIR -from selfdrive.version import is_comma_remote, is_tested_branch +from system.version import is_comma_remote, is_tested_branch from selfdrive.car.interfaces import get_interface_attr from selfdrive.car.fingerprints import eliminate_incompatible_cars, all_legacy_fingerprint_cars from selfdrive.car.vin import get_vin, VIN_UNKNOWN from selfdrive.car.fw_versions import get_fw_versions, match_fw_to_car -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog import cereal.messaging as messaging from selfdrive.car import gen_empty_fingerprint diff --git a/selfdrive/car/disable_ecu.py b/selfdrive/car/disable_ecu.py index 3a06cc06f1..ac5c6c9f8f 100644 --- a/selfdrive/car/disable_ecu.py +++ b/selfdrive/car/disable_ecu.py @@ -1,5 +1,5 @@ from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog EXT_DIAG_REQUEST = b'\x10\x03' EXT_DIAG_RESPONSE = b'\x50\x03' diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 69b7c5f452..c7253d794d 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -12,7 +12,7 @@ from selfdrive.car.interfaces import get_interface_attr from selfdrive.car.fingerprints import FW_VERSIONS from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery from selfdrive.car.toyota.values import CAR as TOYOTA -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog Ecu = car.CarParams.Ecu diff --git a/selfdrive/car/isotp_parallel_query.py b/selfdrive/car/isotp_parallel_query.py index dc79babb13..0e807512cf 100644 --- a/selfdrive/car/isotp_parallel_query.py +++ b/selfdrive/car/isotp_parallel_query.py @@ -4,7 +4,7 @@ from functools import partial from typing import Optional import cereal.messaging as messaging -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog from selfdrive.boardd.boardd import can_list_to_can_capnp from panda.python.uds import CanClient, IsoTpMessage, FUNCTIONAL_ADDRS, get_rx_addr_for_tx_addr diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py index 65e886751d..715850c227 100755 --- a/selfdrive/car/mock/interface.py +++ b/selfdrive/car/mock/interface.py @@ -2,7 +2,7 @@ import math from cereal import car from common.conversions import Conversions as CV -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog import cereal.messaging as messaging from selfdrive.car import gen_empty_fingerprint, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase diff --git a/selfdrive/car/vin.py b/selfdrive/car/vin.py index 2c5b623b06..7413c3f235 100755 --- a/selfdrive/car/vin.py +++ b/selfdrive/car/vin.py @@ -6,7 +6,7 @@ import cereal.messaging as messaging import panda.python.uds as uds from panda.python.uds import FUNCTIONAL_ADDRS from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog OBD_VIN_REQUEST = b'\x09\x02' OBD_VIN_RESPONSE = b'\x49\x02\x01' diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 31807b0187..033072aa73 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -11,7 +11,7 @@ from common.params import Params, put_nonblocking import cereal.messaging as messaging from common.conversions import Conversions as CV from panda import ALTERNATIVE_EXPERIENCE -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.car.car_helpers import get_car, get_startup_event, get_one_can from selfdrive.controls.lib.lane_planner import CAMERA_OFFSET diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 7ca05cc744..cc63d4995d 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -8,7 +8,7 @@ import cereal.messaging as messaging from common.conversions import Conversions as CV from common.realtime import DT_CTRL from selfdrive.locationd.calibrationd import MIN_SPEED_FILTER -from selfdrive.version import get_short_branch +from system.version import get_short_branch AlertSize = log.ControlsState.AlertSize AlertStatus = log.ControlsState.AlertStatus diff --git a/selfdrive/controls/lib/lane_planner.py b/selfdrive/controls/lib/lane_planner.py index 9bbad59084..1facb66d63 100644 --- a/selfdrive/controls/lib/lane_planner.py +++ b/selfdrive/controls/lib/lane_planner.py @@ -3,7 +3,7 @@ from cereal import log from common.filter_simple import FirstOrderFilter from common.numpy_fast import interp from common.realtime import DT_MDL -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog TRAJECTORY_SIZE = 33 diff --git a/selfdrive/controls/lib/lateral_planner.py b/selfdrive/controls/lib/lateral_planner.py index f3f59ee308..ec21c16e91 100644 --- a/selfdrive/controls/lib/lateral_planner.py +++ b/selfdrive/controls/lib/lateral_planner.py @@ -1,7 +1,7 @@ import numpy as np from common.realtime import sec_since_boot, DT_MDL from common.numpy_fast import interp -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog from selfdrive.controls.lib.lateral_mpc_lib.lat_mpc import LateralMpc from selfdrive.controls.lib.drive_helpers import CONTROL_N, MPC_COST_LAT, LAT_MPC_N, CAR_ROTATION_RADIUS from selfdrive.controls.lib.lane_planner import LanePlanner, TRAJECTORY_SIZE diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index b99ee9e9ac..bc0fc9fea6 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -4,7 +4,7 @@ import numpy as np from common.realtime import sec_since_boot from common.numpy_fast import clip, interp -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog from selfdrive.modeld.constants import index_function from selfdrive.controls.lib.radar_helpers import _LEAD_ACCEL_TAU diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 0d21c519a3..d4a6aaef8f 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -12,7 +12,7 @@ from selfdrive.controls.lib.longcontrol import LongCtrlState from selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import LongitudinalMpc from selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import T_IDXS as T_IDXS_MPC from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX, CONTROL_N -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog LON_MPC_STEP = 0.2 # first step is 0.2s AWARENESS_DECEL = -0.2 # car smoothly decel at .2m/s^2 when user is distracted diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py index 083aeb79cc..06807b2a5c 100755 --- a/selfdrive/controls/plannerd.py +++ b/selfdrive/controls/plannerd.py @@ -2,7 +2,7 @@ from cereal import car from common.params import Params from common.realtime import Priority, config_realtime_process -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog from selfdrive.controls.lib.longitudinal_planner import Planner from selfdrive.controls.lib.lateral_planner import LateralPlanner import cereal.messaging as messaging diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index 0e514193dc..b2c9914457 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -10,7 +10,7 @@ from common.params import Params from common.realtime import Ratekeeper, Priority, config_realtime_process from selfdrive.controls.lib.cluster.fastcluster_py import cluster_points_centroid from selfdrive.controls.lib.radar_helpers import Cluster, Track, RADAR_TO_CAMERA -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog class KalmanParams(): diff --git a/selfdrive/debug/disable_ecu.py b/selfdrive/debug/disable_ecu.py index f0faf40017..af007207eb 100644 --- a/selfdrive/debug/disable_ecu.py +++ b/selfdrive/debug/disable_ecu.py @@ -3,7 +3,7 @@ import traceback import cereal.messaging as messaging from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog EXT_DIAG_REQUEST = b'\x10\x03' EXT_DIAG_RESPONSE = b'\x50\x03' diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index d7bf36fb26..e092c939ae 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -20,7 +20,7 @@ from common.realtime import set_realtime_priority from common.transformations.model import model_height from common.transformations.camera import get_view_frame_from_road_frame from common.transformations.orientation import rot_from_euler, euler_from_rot -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog MIN_SPEED_FILTER = 15 * CV.MPH_TO_MS MAX_VEL_ANGLE_STD = np.radians(0.25) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 4ec159cd25..01457f4681 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -17,7 +17,7 @@ from selfdrive.locationd.models.constants import GENERATED_DIR, ObservationKind from selfdrive.locationd.models.gnss_kf import GNSSKalman from selfdrive.locationd.models.gnss_kf import States as GStates import common.transformations.coordinates as coord -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog MAX_TIME_GAP = 10 diff --git a/selfdrive/locationd/models/car_kf.py b/selfdrive/locationd/models/car_kf.py index 75534efa5a..fe7d2e650b 100755 --- a/selfdrive/locationd/models/car_kf.py +++ b/selfdrive/locationd/models/car_kf.py @@ -7,7 +7,7 @@ import numpy as np from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY from selfdrive.locationd.models.constants import ObservationKind -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog from rednose.helpers.kalmanfilter import KalmanFilter diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py index 0e83728e5c..ae67dc28ab 100755 --- a/selfdrive/locationd/paramsd.py +++ b/selfdrive/locationd/paramsd.py @@ -10,7 +10,7 @@ from common.realtime import config_realtime_process, DT_MDL from common.numpy_fast import clip from selfdrive.locationd.models.car_kf import CarKalman, ObservationKind, States from selfdrive.locationd.models.constants import GENERATED_DIR -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog MAX_ANGLE_OFFSET_DELTA = 20 * DT_MDL # Max 20 deg/s diff --git a/selfdrive/loggerd/deleter.py b/selfdrive/loggerd/deleter.py index d745e91fb5..5606288024 100644 --- a/selfdrive/loggerd/deleter.py +++ b/selfdrive/loggerd/deleter.py @@ -2,7 +2,7 @@ import os import shutil import threading -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog from selfdrive.loggerd.config import ROOT, get_available_bytes, get_available_percent from selfdrive.loggerd.uploader import listdir_by_creation diff --git a/selfdrive/loggerd/tests/test_loggerd.py b/selfdrive/loggerd/tests/test_loggerd.py index 54f7aaaa2b..9dbc7ac332 100755 --- a/selfdrive/loggerd/tests/test_loggerd.py +++ b/selfdrive/loggerd/tests/test_loggerd.py @@ -17,7 +17,7 @@ from common.params import Params from common.timeout import Timeout from selfdrive.loggerd.config import ROOT from selfdrive.manager.process_config import managed_processes -from selfdrive.version import get_version +from system.version import get_version from tools.lib.logreader import LogReader from cereal.visionipc import VisionIpcServer, VisionStreamType from common.transformations.camera import tici_f_frame_size, tici_d_frame_size, tici_e_frame_size diff --git a/selfdrive/loggerd/tests/test_uploader.py b/selfdrive/loggerd/tests/test_uploader.py index b8c01776ae..6090bbe2aa 100755 --- a/selfdrive/loggerd/tests/test_uploader.py +++ b/selfdrive/loggerd/tests/test_uploader.py @@ -6,7 +6,7 @@ import unittest import logging import json -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog import selfdrive.loggerd.uploader as uploader from selfdrive.loggerd.tests.loggerd_tests_common import UploaderTestCase diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index 9de1c421bd..f97bafecb9 100644 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -18,7 +18,7 @@ from common.realtime import set_core_affinity from system.hardware import TICI from selfdrive.loggerd.xattr_cache import getxattr, setxattr from selfdrive.loggerd.config import ROOT -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog NetworkType = log.DeviceState.NetworkType UPLOAD_ATTR_NAME = 'user.upload' diff --git a/selfdrive/manager/build.py b/selfdrive/manager/build.py index f0a5aec927..10b4c0a4b8 100755 --- a/selfdrive/manager/build.py +++ b/selfdrive/manager/build.py @@ -11,8 +11,8 @@ from common.basedir import BASEDIR from common.spinner import Spinner from common.text_window import TextWindow from system.hardware import AGNOS -from selfdrive.swaglog import cloudlog, add_file_handler -from selfdrive.version import is_dirty +from system.swaglog import cloudlog, add_file_handler +from system.version import is_dirty MAX_CACHE_SIZE = 4e9 if "CI" in os.environ else 2e9 CACHE_DIR = Path("/data/scons_cache" if AGNOS else "/tmp/scons_cache") diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index 94af397c7d..140c7f1d44 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -18,8 +18,8 @@ from selfdrive.manager.helpers import unblock_stdout from selfdrive.manager.process import ensure_running from selfdrive.manager.process_config import managed_processes from selfdrive.athena.registration import register, UNREGISTERED_DONGLE_ID -from selfdrive.swaglog import cloudlog, add_file_handler -from selfdrive.version import is_dirty, get_commit, get_version, get_origin, get_short_branch, \ +from system.swaglog import cloudlog, add_file_handler +from system.version import is_dirty, get_commit, get_version, get_origin, get_short_branch, \ terms_version, training_version diff --git a/selfdrive/manager/process.py b/selfdrive/manager/process.py index 22f55f3b36..dabfbe4ee0 100644 --- a/selfdrive/manager/process.py +++ b/selfdrive/manager/process.py @@ -16,7 +16,7 @@ from cereal import car from common.basedir import BASEDIR from common.params import Params from common.realtime import sec_since_boot -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog from system.hardware import HARDWARE from cereal import log diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index 443ebbb419..b3efe7e2de 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -18,16 +18,19 @@ def logging(started, params, CP: car.CarParams) -> bool: return started and run procs = [ + NativeProcess("clocksd", "system/clocksd", ["./clocksd"]), + NativeProcess("logcatd", "system/logcatd", ["./logcatd"]), + NativeProcess("proclogd", "system/proclogd", ["./proclogd"]), + PythonProcess("logmessaged", "system.logmessaged", offroad=True), + PythonProcess("timezoned", "system.timezoned", enabled=not PC, offroad=True), + DaemonProcess("manage_athenad", "selfdrive.athena.manage_athenad", "AthenadPid"), # due to qualcomm kernel bugs SIGKILLing camerad sometimes causes page table corruption NativeProcess("camerad", "selfdrive/camerad", ["./camerad"], unkillable=True, callback=driverview), - NativeProcess("clocksd", "system/clocksd", ["./clocksd"]), NativeProcess("dmonitoringmodeld", "selfdrive/modeld", ["./dmonitoringmodeld"], enabled=(not PC or WEBCAM), callback=driverview), - NativeProcess("logcatd", "system/logcatd", ["./logcatd"]), NativeProcess("encoderd", "selfdrive/loggerd", ["./encoderd"]), NativeProcess("loggerd", "selfdrive/loggerd", ["./loggerd"], onroad=False, callback=logging), NativeProcess("modeld", "selfdrive/modeld", ["./modeld"]), - NativeProcess("proclogd", "system/proclogd", ["./proclogd"]), NativeProcess("sensord", "selfdrive/sensord", ["./sensord"], enabled=not PC), NativeProcess("ubloxd", "selfdrive/locationd", ["./ubloxd"], enabled=(not PC or WEBCAM)), NativeProcess("ui", "selfdrive/ui", ["./ui"], offroad=True, watchdog_max_dt=(5 if not PC else None)), @@ -38,14 +41,12 @@ procs = [ PythonProcess("controlsd", "selfdrive.controls.controlsd"), PythonProcess("deleter", "selfdrive.loggerd.deleter", offroad=True), PythonProcess("dmonitoringd", "selfdrive.monitoring.dmonitoringd", enabled=(not PC or WEBCAM), callback=driverview), - PythonProcess("logmessaged", "selfdrive.logmessaged", offroad=True), PythonProcess("navd", "selfdrive.navd.navd"), PythonProcess("pandad", "selfdrive.boardd.pandad", offroad=True), PythonProcess("paramsd", "selfdrive.locationd.paramsd"), PythonProcess("plannerd", "selfdrive.controls.plannerd"), PythonProcess("radard", "selfdrive.controls.radard"), PythonProcess("thermald", "selfdrive.thermald.thermald", offroad=True), - PythonProcess("timezoned", "selfdrive.timezoned", enabled=not PC, offroad=True), PythonProcess("tombstoned", "selfdrive.tombstoned", enabled=not PC, offroad=True), PythonProcess("updated", "selfdrive.updated", enabled=not PC, onroad=False, offroad=True), PythonProcess("uploader", "selfdrive.loggerd.uploader", offroad=True), diff --git a/selfdrive/navd/navd.py b/selfdrive/navd/navd.py index 52db9b1d08..fcd53d8b60 100755 --- a/selfdrive/navd/navd.py +++ b/selfdrive/navd/navd.py @@ -14,7 +14,7 @@ from selfdrive.navd.helpers import (Coordinate, coordinate_from_param, distance_along_geometry, maxspeed_to_ms, minimum_distance, parse_banner_instructions) -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog REROUTE_DISTANCE = 25 MANEUVER_TRANSITION_THRESHOLD = 10 diff --git a/selfdrive/sensord/rawgps/rawgpsd.py b/selfdrive/sensord/rawgps/rawgpsd.py index e0861c0d9a..3aa6d4b072 100755 --- a/selfdrive/sensord/rawgps/rawgpsd.py +++ b/selfdrive/sensord/rawgps/rawgpsd.py @@ -10,7 +10,7 @@ from struct import unpack_from, calcsize, pack import cereal.messaging as messaging from cereal import log -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog from selfdrive.sensord.rawgps.modemdiag import ModemDiag, DIAG_LOG_F, setup_logs, send_recv from selfdrive.sensord.rawgps.structs import dict_unpacker diff --git a/selfdrive/sentry.py b/selfdrive/sentry.py index 10e43ee03c..aa409ea394 100644 --- a/selfdrive/sentry.py +++ b/selfdrive/sentry.py @@ -6,8 +6,8 @@ from sentry_sdk.integrations.threading import ThreadingIntegration from common.params import Params from selfdrive.athena.registration import is_registered_device from system.hardware import HARDWARE, PC -from selfdrive.swaglog import cloudlog -from selfdrive.version import get_branch, get_commit, get_origin, get_version, \ +from system.swaglog import cloudlog +from system.version import get_branch, get_commit, get_origin, get_version, \ is_comma_remote, is_dirty, is_tested_branch diff --git a/selfdrive/statsd.py b/selfdrive/statsd.py index a48ba56003..7dc002727e 100755 --- a/selfdrive/statsd.py +++ b/selfdrive/statsd.py @@ -9,10 +9,10 @@ from typing import NoReturn, Union, List, Dict from common.params import Params from cereal.messaging import SubMaster -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog from system.hardware import HARDWARE from common.file_helpers import atomic_write_in_dir -from selfdrive.version import get_normalized_origin, get_short_branch, get_short_version, is_dirty +from system.version import get_normalized_origin, get_short_branch, get_short_version, is_dirty from selfdrive.loggerd.config import STATS_DIR, STATS_DIR_FILE_LIMIT, STATS_SOCKET, STATS_FLUSH_TIME_S diff --git a/selfdrive/test/helpers.py b/selfdrive/test/helpers.py index cc8efd6e46..8cc996c28d 100644 --- a/selfdrive/test/helpers.py +++ b/selfdrive/test/helpers.py @@ -4,7 +4,7 @@ from functools import wraps from system.hardware import PC from selfdrive.manager.process_config import managed_processes -from selfdrive.version import training_version, terms_version +from system.version import training_version, terms_version def set_params_enabled(): diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index b466aa8193..f3bb286635 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -16,7 +16,7 @@ from selfdrive.manager.process_config import managed_processes from selfdrive.test.openpilotci import BASE_URL, get_url from selfdrive.test.process_replay.compare_logs import compare_logs, save_log from selfdrive.test.process_replay.test_processes import format_diff -from selfdrive.version import get_commit +from system.version import get_commit from tools.lib.framereader import FrameReader from tools.lib.logreader import LogReader diff --git a/selfdrive/test/process_replay/test_debayer.py b/selfdrive/test/process_replay/test_debayer.py index cf939e3672..eff77fc479 100755 --- a/selfdrive/test/process_replay/test_debayer.py +++ b/selfdrive/test/process_replay/test_debayer.py @@ -9,7 +9,7 @@ import pyopencl as cl # install with `PYOPENCL_CL_PRETEND_VERSION=2.0 pip insta from system.hardware import PC, TICI from common.basedir import BASEDIR from selfdrive.test.openpilotci import BASE_URL, get_url -from selfdrive.version import get_commit +from system.version import get_commit from selfdrive.camerad.snapshot.snapshot import yuv_to_rgb from tools.lib.logreader import LogReader from tools.lib.filereader import FileReader diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index c1b5b85391..9f83a08e23 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -11,7 +11,7 @@ from selfdrive.car.car_helpers import interface_names from selfdrive.test.openpilotci import get_url, upload_file from selfdrive.test.process_replay.compare_logs import compare_logs, save_log from selfdrive.test.process_replay.process_replay import CONFIGS, PROC_REPLAY_DIR, FAKEDATA, check_enabled, replay_process -from selfdrive.version import get_commit +from system.version import get_commit from tools.lib.filereader import FileReader from tools.lib.logreader import LogReader diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 6cf53a046e..79c3a2ebc0 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -39,7 +39,7 @@ PROCS = { "./_soundd": 1.0, "selfdrive.monitoring.dmonitoringd": 1.90, "./proclogd": 1.54, - "selfdrive.logmessaged": 0.2, + "system.logmessaged": 0.2, "./clocksd": 0.02, "./ubloxd": 0.02, "selfdrive.tombstoned": 0, diff --git a/selfdrive/thermald/fan_controller.py b/selfdrive/thermald/fan_controller.py index b1c7013297..2094faeaa7 100644 --- a/selfdrive/thermald/fan_controller.py +++ b/selfdrive/thermald/fan_controller.py @@ -3,7 +3,7 @@ from abc import ABC, abstractmethod from common.realtime import DT_TRML from common.numpy_fast import interp -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog from selfdrive.controls.lib.pid import PIDController class BaseFanController(ABC): diff --git a/selfdrive/thermald/power_monitoring.py b/selfdrive/thermald/power_monitoring.py index acc2fd90bc..9f009d3265 100644 --- a/selfdrive/thermald/power_monitoring.py +++ b/selfdrive/thermald/power_monitoring.py @@ -5,7 +5,7 @@ from cereal import log from common.params import Params, put_nonblocking from common.realtime import sec_since_boot from system.hardware import HARDWARE -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog from selfdrive.statsd import statlog CAR_VOLTAGE_LOW_PASS_K = 0.091 # LPF gain for 5s tau (dt/tau / (dt/tau + 1)) diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 84663e8eb0..403e9cb232 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -20,10 +20,10 @@ from selfdrive.controls.lib.alertmanager import set_offroad_alert from system.hardware import HARDWARE, TICI, AGNOS from selfdrive.loggerd.config import get_available_percent from selfdrive.statsd import statlog -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog from selfdrive.thermald.power_monitoring import PowerMonitoring from selfdrive.thermald.fan_controller import TiciFanController -from selfdrive.version import terms_version, training_version +from system.version import terms_version, training_version ThermalStatus = log.DeviceState.ThermalStatus NetworkType = log.DeviceState.NetworkType diff --git a/selfdrive/tombstoned.py b/selfdrive/tombstoned.py index 1d0f8532db..0045e0766c 100755 --- a/selfdrive/tombstoned.py +++ b/selfdrive/tombstoned.py @@ -12,8 +12,8 @@ from typing import NoReturn from common.file_helpers import mkdirs_exists_ok from selfdrive.loggerd.config import ROOT import selfdrive.sentry as sentry -from selfdrive.swaglog import cloudlog -from selfdrive.version import get_commit +from system.swaglog import cloudlog +from system.version import get_commit MAX_SIZE = 1_000_000 * 100 # allow up to 100M MAX_TOMBSTONE_FN_LEN = 62 # 85 - 23 ("/crash/") diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 33e2d5d418..bdec383f52 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -38,9 +38,9 @@ from markdown_it import MarkdownIt from common.basedir import BASEDIR from common.params import Params from system.hardware import AGNOS, HARDWARE -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog from selfdrive.controls.lib.alertmanager import set_offroad_alert -from selfdrive.version import is_tested_branch +from system.version import is_tested_branch LOCK_FILE = os.getenv("UPDATER_LOCK_FILE", "/tmp/safe_staging_overlay.lock") STAGING_ROOT = os.getenv("UPDATER_STAGING_ROOT", "/data/safe_staging") diff --git a/selfdrive/logmessaged.py b/system/logmessaged.py similarity index 95% rename from selfdrive/logmessaged.py rename to system/logmessaged.py index 1d1fab5162..280a23cf1d 100755 --- a/selfdrive/logmessaged.py +++ b/system/logmessaged.py @@ -4,7 +4,7 @@ from typing import NoReturn import cereal.messaging as messaging from common.logging_extra import SwagLogFileFormatter -from selfdrive.swaglog import get_file_handler +from system.swaglog import get_file_handler def main() -> NoReturn: diff --git a/selfdrive/swaglog.py b/system/swaglog.py similarity index 100% rename from selfdrive/swaglog.py rename to system/swaglog.py diff --git a/selfdrive/timezoned.py b/system/timezoned.py similarity index 98% rename from selfdrive/timezoned.py rename to system/timezoned.py index c1d5676db6..884a5c3812 100755 --- a/selfdrive/timezoned.py +++ b/system/timezoned.py @@ -10,7 +10,7 @@ from timezonefinder import TimezoneFinder from common.params import Params from system.hardware import AGNOS -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog def set_timezone(valid_timezones, timezone): diff --git a/selfdrive/version.py b/system/version.py similarity index 99% rename from selfdrive/version.py rename to system/version.py index 08ab097344..f0817b3a9f 100644 --- a/selfdrive/version.py +++ b/system/version.py @@ -5,7 +5,7 @@ from typing import List, Optional from functools import lru_cache from common.basedir import BASEDIR -from selfdrive.swaglog import cloudlog +from system.swaglog import cloudlog TESTED_BRANCHES = ['devel', 'release3-staging', 'dashcam3-staging', 'release3', 'dashcam3'] From 1dd52ba27b6ec2121c5054c80f1820aeade40cb2 Mon Sep 17 00:00:00 2001 From: Andrew Date: Sat, 11 Jun 2022 23:38:32 -0700 Subject: [PATCH 020/302] acados build script improvements for mac (#24634) * add Darwin build w/ universal2 libs * add rust for acados rebuilds * just build script fixes Co-authored-by: Adeeb Shihadeh --- third_party/acados/build.sh | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/third_party/acados/build.sh b/third_party/acados/build.sh index 0b14a4cec9..a4246fbda6 100755 --- a/third_party/acados/build.sh +++ b/third_party/acados/build.sh @@ -1,4 +1,5 @@ -#!/usr/bin/bash -e +#!/usr/bin/env bash +set -e DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" @@ -9,6 +10,13 @@ if [ -f /TICI ]; then BLAS_TARGET="ARMV8A_ARM_CORTEX_A57" fi +ACADOS_FLAGS="-DACADOS_WITH_QPOASES=ON -UBLASFEO_TARGET -DBLASFEO_TARGET=$BLAS_TARGET" + +if [[ "$OSTYPE" == "darwin"* ]]; then + ACADOS_FLAGS="$ACADOS_FLAGS -DCMAKE_OSX_ARCHITECTURES=arm64;x86_64" + ARCHNAME="Darwin" +fi + if [ ! -d acados_repo/ ]; then git clone https://github.com/acados/acados.git $DIR/acados_repo # git clone https://github.com/commaai/acados.git $DIR/acados_repo @@ -21,7 +29,7 @@ git submodule update --recursive --init # build mkdir -p build cd build -cmake -DACADOS_WITH_QPOASES=ON -UBLASFEO_TARGET -DBLASFEO_TARGET=$BLAS_TARGET .. +cmake $ACADOS_FLAGS .. make -j20 install INSTALL_DIR="$DIR/$ARCHNAME" From 3f60088f432f0bf8e7805cdb2223817c249ec7fa Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Sun, 12 Jun 2022 17:27:46 +0100 Subject: [PATCH 021/302] Ford: disable radar for now (#24832) The newer Ford vehicles require a different radar parser. --- selfdrive/car/ford/radar_interface.py | 6 ++++++ selfdrive/car/ford/values.py | 4 ++-- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py index 1dfc27e672..866602cf09 100644 --- a/selfdrive/car/ford/radar_interface.py +++ b/selfdrive/car/ford/radar_interface.py @@ -9,6 +9,9 @@ RADAR_MSGS = list(range(0x500, 0x540)) def _create_radar_can_parser(car_fingerprint): + if DBC[car_fingerprint]['radar'] is None: + return None + msg_n = len(RADAR_MSGS) signals = list(zip(['X_Rel'] * msg_n + ['Angle'] * msg_n + ['V_Rel'] * msg_n, RADAR_MSGS * 3)) @@ -27,6 +30,9 @@ class RadarInterface(RadarInterfaceBase): self.updated_messages = set() def update(self, can_strings): + if self.rcp is None: + return super().update(None) + vls = self.rcp.update_strings(can_strings) self.updated_messages.update(vls) diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index 96ec87d757..aae011ad3d 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -79,6 +79,6 @@ FW_VERSIONS = { DBC = { - CAR.ESCAPE_MK4: dbc_dict('ford_lincoln_base_pt', 'ford_fusion_2018_adas'), - CAR.FOCUS_MK4: dbc_dict('ford_lincoln_base_pt', 'ford_fusion_2018_adas'), + CAR.ESCAPE_MK4: dbc_dict('ford_lincoln_base_pt', None), + CAR.FOCUS_MK4: dbc_dict('ford_lincoln_base_pt', None), } From 1c29b20e72141c2beae6e32cf87dabded3095fda Mon Sep 17 00:00:00 2001 From: Jeroen <33349469+jeroenlammersma@users.noreply.github.com> Date: Sun, 12 Jun 2022 18:32:18 +0200 Subject: [PATCH 022/302] Updated CARLA to v0.9.13 (#24575) * Updated CARLA to v0.9.13 * pipenv lock Co-authored-by: Adeeb Shihadeh --- Pipfile | 2 +- Pipfile.lock | 24 ++++++++++++------------ tools/sim/start_carla.sh | 4 ++-- 3 files changed, 15 insertions(+), 15 deletions(-) diff --git a/Pipfile b/Pipfile index 3958c890fe..2ffe60e0fe 100644 --- a/Pipfile +++ b/Pipfile @@ -39,7 +39,7 @@ breathe = "*" subprocess32 = "*" tenacity = "*" mpld3 = "*" -carla = {version = "==0.9.12", markers="platform_system != 'Darwin'"} +carla = {version = "==0.9.13", markers="platform_system != 'Darwin'"} [packages] atomicwrites = "*" diff --git a/Pipfile.lock b/Pipfile.lock index df2b3bb853..25a97890d3 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "4dbfaf9d7a532e0e9a126f828512a5383a817722a1580ef64b99e2427f366a72" + "sha256": "eb1eeeaabf1266fab353532d10e4d9ae36306a7577f248513909c2d6096ab1c9" }, "pipfile-spec": 6, "requires": { @@ -1155,11 +1155,11 @@ }, "setuptools": { "hashes": [ - "sha256:d1746e7fd520e83bbe210d02fff1aa1a425ad671c7a9da7d246ec2401a087198", - "sha256:e7d11f3db616cda0751372244c2ba798e8e56a28e096ec4529010b803485f3fe" + "sha256:1f5d3a1502812025cdb2e5609b6af2d207332e3f50febe6db10ed3a59b2f155f", + "sha256:30b6b0fbacc459c90d27a63e6173facfc8b8c99a48fb24b5044f459ba63cd6cf" ], "markers": "python_version >= '3.7'", - "version": "==62.3.3" + "version": "==62.3.4" }, "six": { "hashes": [ @@ -1452,17 +1452,17 @@ }, "carla": { "hashes": [ - "sha256:1ed11b56c781cd15cbd540cacfb59ad348e0a021d898cfd0ff89a585f144da0b", - "sha256:20c1e1b72034175824d89b2d86b09ae72b4aca09ea25874dc6251f239297251d", - "sha256:6d1122c24af4f6375dc6858fbb0309b61c219b101d8c5a540def4c36c4563fe1", - "sha256:9c19ebf6cbbc535bde4baf9e18c72ab349657b34c4202b9751541e4c0d20b3cc", - "sha256:a69f6d84b59e2f805b2a417de98f977fe9efe0cfa733da8d75e20d28892da915", - "sha256:c3ae0dce3f1354b6311fee21a365947b0ff169249993a913904f676046d2d69f", - "sha256:dd392a267e14b785a8f65dafef86e05a92201253e9fb4a01e1e262834f20bed2" + "sha256:1210cce213e968a644effd4e2e48458a072481459d073424b05725056ba3d77d", + "sha256:339fcb1e392f3ade1be82b7258de19c533e2efae111e954a6eb174efb296903d", + "sha256:5f065825ce812343bf27a80a19d647b3200b31b44a9e80cea0340e3bd20cdf81", + "sha256:954ca34d5bdd4516ceca353db907fee8cec6630d6b31a732b17dd1554e0f0f94", + "sha256:a64ee78fe91137fa7d4828c7fc06d5824bd7312e29e4ea4f31a5d74dd28bff40", + "sha256:a95d2d4218ea388c863c66b7c2ab3fe49ffefe53999305cfcb6a8107042f79af", + "sha256:d2bfaea2d6824a2d758cbe813856c69420494f5c97d2a2dfb45653ccf976f1ce" ], "index": "pypi", "markers": "platform_system != 'Darwin'", - "version": "==0.9.12" + "version": "==0.9.13" }, "certifi": { "hashes": [ diff --git a/tools/sim/start_carla.sh b/tools/sim/start_carla.sh index abdaee4ea8..67ced7eb21 100755 --- a/tools/sim/start_carla.sh +++ b/tools/sim/start_carla.sh @@ -15,7 +15,7 @@ if ! $(apt list --installed | grep -q nvidia-container-toolkit); then fi fi -docker pull carlasim/carla:0.9.12 +docker pull carlasim/carla:0.9.13 EXTRA_ARGS="-it" if [[ "$DETACH" ]]; then @@ -29,5 +29,5 @@ docker run \ --net=host \ -v /tmp/.X11-unix:/tmp/.X11-unix:rw \ $EXTRA_ARGS \ - carlasim/carla:0.9.12 \ + carlasim/carla:0.9.13 \ /bin/bash ./CarlaUE4.sh -opengl -nosound -RenderOffScreen -benchmark -fps=20 -quality-level=Low From 39da6912ea0b8db16d3f96f289f723452e540ab7 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 12 Jun 2022 18:00:00 -0700 Subject: [PATCH 023/302] misc jenkins fixups (#24840) * bump cereal * remove that * pull cl image * lil docker cleanup --- Dockerfile.openpilot | 7 +------ cereal | 2 +- selfdrive/manager/test/test_manager.py | 8 ++------ tools/sim/Dockerfile.sim | 10 +++++----- tools/sim/build_container.sh | 2 +- 5 files changed, 10 insertions(+), 19 deletions(-) diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index 66b9f18a11..102da78d7d 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -8,11 +8,6 @@ ENV PYTHONPATH ${OPENPILOT_PATH}:${PYTHONPATH} RUN mkdir -p ${OPENPILOT_PATH} WORKDIR ${OPENPILOT_PATH} -COPY Pipfile Pipfile.lock $OPENPILOT_PATH -RUN pip install --no-cache-dir pipenv==2021.5.29 pip==21.3.1 && \ - pipenv install --system --deploy --dev --clear && \ - pip uninstall -y pipenv - COPY SConstruct ${OPENPILOT_PATH} COPY ./pyextra ${OPENPILOT_PATH}/pyextra @@ -30,4 +25,4 @@ COPY ./panda ${OPENPILOT_PATH}/panda COPY ./selfdrive ${OPENPILOT_PATH}/selfdrive COPY ./system ${OPENPILOT_PATH}/system -RUN scons -j$(nproc) +RUN scons --cache-readonly -j$(nproc) diff --git a/cereal b/cereal index 78870ba056..98f795fd73 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 78870ba056174352218988610e5010fde4eca956 +Subproject commit 98f795fd73356198f1fc8d5ea5a8f25e6f7c57e0 diff --git a/selfdrive/manager/test/test_manager.py b/selfdrive/manager/test/test_manager.py index e4c3ef7c4c..a84ff264d2 100755 --- a/selfdrive/manager/test/test_manager.py +++ b/selfdrive/manager/test/test_manager.py @@ -5,14 +5,13 @@ import time import unittest import selfdrive.manager.manager as manager -from system.hardware import AGNOS, HARDWARE from selfdrive.manager.process import DaemonProcess from selfdrive.manager.process_config import managed_processes +from system.hardware import AGNOS, HARDWARE os.environ['FAKEUPLOAD'] = "1" -# TODO: make eon fast -MAX_STARTUP_TIME = 15 +MAX_STARTUP_TIME = 3 ALL_PROCESSES = [p.name for p in managed_processes.values() if (type(p) is not DaemonProcess) and p.enabled and (p.name not in ['updated', 'pandad'])] @@ -54,9 +53,6 @@ class TestManager(unittest.TestCase): # TODO: make Qt UI exit gracefully continue - # Make sure the process is actually dead - managed_processes[p].stop() - # TODO: interrupted blocking read exits with 1 in cereal. use a more unique return code exit_codes = [0, 1] if managed_processes[p].sigkill: diff --git a/tools/sim/Dockerfile.sim b/tools/sim/Dockerfile.sim index d838efed13..0d6e8e584c 100644 --- a/tools/sim/Dockerfile.sim +++ b/tools/sim/Dockerfile.sim @@ -1,9 +1,9 @@ FROM ghcr.io/commaai/openpilot-base-cl:latest -RUN apt-get update && apt-get install -y --no-install-recommends\ - tmux \ - vim \ - && rm -rf /var/lib/apt/lists/* +RUN apt-get update && apt-get install -y --no-install-recommends \ + tmux \ + vim \ + && rm -rf /var/lib/apt/lists/* # get same tmux config used on NEOS for debugging RUN cd $HOME && \ @@ -27,6 +27,6 @@ COPY ./system $HOME/openpilot/system COPY ./tools $HOME/openpilot/tools WORKDIR $HOME/openpilot -RUN scons -j12 +RUN scons --cache-readonly -j12 RUN python -c "from selfdrive.test.helpers import set_params_enabled; set_params_enabled()" diff --git a/tools/sim/build_container.sh b/tools/sim/build_container.sh index 451277d590..81afb82d83 100755 --- a/tools/sim/build_container.sh +++ b/tools/sim/build_container.sh @@ -3,7 +3,7 @@ DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" cd $DIR/../../ -docker pull ghcr.io/commaai/openpilot-base:latest +docker pull ghcr.io/commaai/openpilot-base-cl:latest docker build \ --cache-from ghcr.io/commaai/openpilot-sim:latest \ -t ghcr.io/commaai/openpilot-sim:latest \ From e7cad559a659d47466645290e00ee6205bb938c6 Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Mon, 13 Jun 2022 05:39:36 +0100 Subject: [PATCH 024/302] Ford: remove Fusion DBC from release (#24841) --- release/files_common | 1 - 1 file changed, 1 deletion(-) diff --git a/release/files_common b/release/files_common index 76d440c402..6731ae4a12 100644 --- a/release/files_common +++ b/release/files_common @@ -473,7 +473,6 @@ opendbc/gm_global_a_powertrain_generated.dbc opendbc/gm_global_a_object.dbc opendbc/gm_global_a_chassis.dbc -opendbc/ford_fusion_2018_adas.dbc opendbc/ford_lincoln_base_pt.dbc opendbc/honda_accord_2018_can_generated.dbc From 3db36a1958b24023a8af2a10419c0c7e4112bef7 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 12 Jun 2022 21:59:58 -0700 Subject: [PATCH 025/302] jenkins: lock simulator --- Jenkinsfile | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 9d1ab33761..ebc26a5920 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -89,8 +89,10 @@ pipeline { sh "git config --global --add safe.directory ${WORKSPACE}" sh "git lfs pull" sh "${WORKSPACE}/tools/sim/build_container.sh" - sh "DETACH=1 ${WORKSPACE}/tools/sim/start_carla.sh" - sh "${WORKSPACE}/tools/sim/start_openpilot_docker.sh" + lock(resource: "", label: "simulator", inversePrecedence: true, quantity: 1) { + sh "DETACH=1 ${WORKSPACE}/tools/sim/start_carla.sh" + sh "${WORKSPACE}/tools/sim/start_openpilot_docker.sh" + } } post { From 84c741ecf6ac0727a29aeebb5f2a6539c2d76dd2 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 13 Jun 2022 09:37:12 +0200 Subject: [PATCH 026/302] SConstruct: set AGNOS from /AGNOS --- SConstruct | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/SConstruct b/SConstruct index 0aeb382c23..edf14b4725 100644 --- a/SConstruct +++ b/SConstruct @@ -6,7 +6,7 @@ import platform import numpy as np TICI = os.path.isfile('/TICI') -AGNOS = TICI +AGNOS = os.path.isfile('/AGNOS') Decider('MD5-timestamp') From d71295e0451260acdcfdfb14477c0e21bc4ed311 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 13 Jun 2022 09:50:40 +0200 Subject: [PATCH 027/302] Revert "SConstruct: set AGNOS from /AGNOS" until Jenkins devices are updated This reverts commit 84c741ecf6ac0727a29aeebb5f2a6539c2d76dd2. --- SConstruct | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/SConstruct b/SConstruct index edf14b4725..0aeb382c23 100644 --- a/SConstruct +++ b/SConstruct @@ -6,7 +6,7 @@ import platform import numpy as np TICI = os.path.isfile('/TICI') -AGNOS = os.path.isfile('/AGNOS') +AGNOS = TICI Decider('MD5-timestamp') From 724b322909152d58f626b6e76fd34d7d03d67250 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Mon, 13 Jun 2022 11:45:35 +0200 Subject: [PATCH 028/302] Laikad: Use filter for correcting measurements (#24824) * Update laikad. * Update log error --- SConstruct | 2 +- selfdrive/locationd/laikad.py | 65 ++++++++++++++++++++++------------- 2 files changed, 42 insertions(+), 25 deletions(-) diff --git a/SConstruct b/SConstruct index 0aeb382c23..b5c4edc99b 100644 --- a/SConstruct +++ b/SConstruct @@ -359,6 +359,7 @@ Export('cereal', 'messaging', 'visionipc') rednose_config = { 'generated_folder': '#selfdrive/locationd/models/generated', 'to_build': { + 'gnss': ('#selfdrive/locationd/models/gnss_kf.py', True, []), 'live': ('#selfdrive/locationd/models/live_kf.py', True, ['live_kf_constants.h']), 'car': ('#selfdrive/locationd/models/car_kf.py', True, []), }, @@ -366,7 +367,6 @@ rednose_config = { if arch != "larch64": rednose_config['to_build'].update({ - 'gnss': ('#selfdrive/locationd/models/gnss_kf.py', True, []), 'loc_4': ('#selfdrive/locationd/models/loc_kf.py', True, []), 'pos_computer_4': ('#rednose/helpers/lst_sq_computer.py', False, []), 'pos_computer_5': ('#rednose/helpers/lst_sq_computer.py', False, []), diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 01457f4681..42c4156795 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -6,6 +6,8 @@ from typing import List, Optional import numpy as np from collections import defaultdict +from numpy.linalg import linalg + from cereal import log, messaging from laika import AstroDog from laika.constants import SECS_IN_MIN @@ -37,24 +39,33 @@ class Laikad: latest_msg_t = GPSTime(report.gpsWeek, report.rcvTow) self.fetch_orbits(latest_msg_t + SECS_IN_MIN, block) new_meas = read_raw_ublox(report) + processed_measurements = process_measurements(new_meas, self.astro_dog) + pos_fix = calc_pos_fix(processed_measurements, min_measurements=4) - measurements = process_measurements(new_meas, self.astro_dog) - pos_fix = calc_pos_fix(measurements, min_measurements=4) - # To get a position fix a minimum of 5 measurements are needed. - # Each report can contain less and some measurements can't be processed. + t = ublox_mono_time * 1e-9 + kf_pos_std = None + if all(self.kf_valid(t)): + self.gnss_kf.predict(t) + kf_pos_std = np.sqrt(abs(self.gnss_kf.P[GStates.ECEF_POS].diagonal())) + # If localizer is valid use its position to correct measurements + if kf_pos_std is not None and linalg.norm(kf_pos_std) < 100: + est_pos = self.gnss_kf.x[GStates.ECEF_POS] + elif len(pos_fix) > 0 and abs(np.array(pos_fix[1])).mean() < 1000: + est_pos = pos_fix[0][:3] + else: + est_pos = None corrected_measurements = [] - if len(pos_fix) > 0 and abs(np.array(pos_fix[1])).mean() < 1000: - corrected_measurements = correct_measurements(measurements, pos_fix[0][:3], self.astro_dog) + if est_pos is not None: + corrected_measurements = correct_measurements(processed_measurements, est_pos, self.astro_dog) - t = ublox_mono_time * 1e-9 self.update_localizer(pos_fix, t, corrected_measurements) - localizer_valid = self.localizer_valid(t) + kf_valid = all(self.kf_valid(t)) ecef_pos = self.gnss_kf.x[GStates.ECEF_POS].tolist() ecef_vel = self.gnss_kf.x[GStates.ECEF_VELOCITY].tolist() - pos_std = self.gnss_kf.P[GStates.ECEF_POS].flatten().tolist() - vel_std = self.gnss_kf.P[GStates.ECEF_VELOCITY].flatten().tolist() + pos_std = np.sqrt(abs(self.gnss_kf.P[GStates.ECEF_POS].diagonal())).tolist() + vel_std = np.sqrt(abs(self.gnss_kf.P[GStates.ECEF_VELOCITY].diagonal())).tolist() bearing_deg, bearing_std = get_bearing_from_gnss(ecef_pos, ecef_vel, vel_std) @@ -62,9 +73,9 @@ class Laikad: dat = messaging.new_message("gnssMeasurements") measurement_msg = log.LiveLocationKalman.Measurement.new_message dat.gnssMeasurements = { - "positionECEF": measurement_msg(value=ecef_pos, std=pos_std, valid=localizer_valid), - "velocityECEF": measurement_msg(value=ecef_vel, std=vel_std, valid=localizer_valid), - "bearingDeg": measurement_msg(value=[bearing_deg], std=[bearing_std], valid=localizer_valid), + "positionECEF": measurement_msg(value=ecef_pos, std=pos_std, valid=kf_valid), + "velocityECEF": measurement_msg(value=ecef_vel, std=vel_std, valid=kf_valid), + "bearingDeg": measurement_msg(value=[bearing_deg], std=[bearing_std], valid=kf_valid), "ubloxMonoTime": ublox_mono_time, "correctedMeasurements": meas_msgs } @@ -77,18 +88,21 @@ class Laikad: def update_localizer(self, pos_fix, t: float, measurements: List[GNSSMeasurement]): # Check time and outputs are valid - if not self.localizer_valid(t): - # A position fix is needed when resetting the kalman filter. - if len(pos_fix) == 0: - return - post_est = pos_fix[0][:3].tolist() - filter_time = self.gnss_kf.filter.filter_time - if filter_time is None: + valid = self.kf_valid(t) + if not all(valid): + if not valid[0]: cloudlog.info("Init gnss kalman filter") - elif abs(t - filter_time) > MAX_TIME_GAP: + elif not valid[1]: cloudlog.error("Time gap of over 10s detected, gnss kalman reset") - else: + elif not valid[2]: cloudlog.error("Gnss kalman filter state is nan") + else: + cloudlog.error("Gnss kalman std too far") + + if len(pos_fix) == 0: + cloudlog.error("Position fix not available when resetting kalman filter") + return + post_est = pos_fix[0][:3].tolist() self.init_gnss_localizer(post_est) if len(measurements) > 0: kf_add_observations(self.gnss_kf, t, measurements) @@ -96,9 +110,12 @@ class Laikad: # Ensure gnss filter is updated even with no new measurements self.gnss_kf.predict(t) - def localizer_valid(self, t: float): + def kf_valid(self, t: float): filter_time = self.gnss_kf.filter.filter_time - return filter_time is not None and (t - filter_time) < MAX_TIME_GAP and all(np.isfinite(self.gnss_kf.x[GStates.ECEF_POS])) + return [filter_time is not None, + filter_time is not None and abs(t - filter_time) < MAX_TIME_GAP, + all(np.isfinite(self.gnss_kf.x[GStates.ECEF_POS])), + linalg.norm(self.gnss_kf.P[GStates.ECEF_POS]) < 1e5] def init_gnss_localizer(self, est_pos): x_initial, p_initial_diag = np.copy(GNSSKalman.x_initial), np.copy(np.diagonal(GNSSKalman.P_initial)) From 1221aef233180a7d290ff813d2e2e53dbf87d586 Mon Sep 17 00:00:00 2001 From: Joost Wooning Date: Mon, 13 Jun 2022 12:27:47 +0200 Subject: [PATCH 029/302] ui: skip texture frame copy (#24700) * ui_blit working * simpler and working * more believable that it's real * working on device * build on pc * use hardware pc * reduce cpu usage * yuv conversion to EGL * move everything to cameraview * some cleanup * more cleanup * init array * init images with std::map * dont destroy images * do destroy images Co-authored-by: Comma Device --- selfdrive/test/test_onroad.py | 2 +- selfdrive/ui/SConscript | 3 ++ selfdrive/ui/qt/widgets/cameraview.cc | 72 ++++++++++++++++++++++++--- selfdrive/ui/qt/widgets/cameraview.h | 17 ++++++- 4 files changed, 84 insertions(+), 10 deletions(-) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 79c3a2ebc0..3586f86f12 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -27,7 +27,7 @@ PROCS = { "./camerad": 16.5, "./locationd": 9.1, "selfdrive.controls.plannerd": 11.7, - "./_ui": 26.4, + "./_ui": 19.2, "selfdrive.locationd.paramsd": 9.0, "./_sensord": 6.17, "selfdrive.controls.radard": 4.5, diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 47c4ac2a51..28fcc5f56f 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -5,6 +5,9 @@ Import('qt_env', 'arch', 'common', 'messaging', 'visionipc', base_libs = [common, messaging, cereal, visionipc, transformations, 'zmq', 'capnp', 'kj', 'm', 'OpenCL', 'ssl', 'crypto', 'pthread'] + qt_env["LIBS"] +if arch == 'larch64': + base_libs.append('EGL') + maps = arch in ['larch64', 'x86_64'] if maps and arch == 'x86_64': diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index f16e8e4e0d..000ac48475 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -26,6 +26,18 @@ const char frame_vertex_shader[] = " vTexCoord = aTexCoord;\n" "}\n"; +#ifdef QCOM2 +const char frame_fragment_shader[] = + "#version 300 es\n" + "#extension GL_OES_EGL_image_external_essl3 : enable\n" + "precision mediump float;\n" + "uniform samplerExternalOES uTexture;\n" + "in vec2 vTexCoord;\n" + "out vec4 colorOut;\n" + "void main() {\n" + " colorOut = texture(uTexture, vTexCoord);\n" + "}\n"; +#else const char frame_fragment_shader[] = #ifdef __APPLE__ "#version 330 core\n" @@ -45,6 +57,7 @@ const char frame_fragment_shader[] = " float b = y + 1.772 * uv.x;\n" " colorOut = vec4(r, g, b, 1.0);\n" "}\n"; +#endif const mat4 device_transform = {{ 1.0, 0.0, 0.0, 0.0, @@ -99,7 +112,7 @@ CameraViewWidget::~CameraViewWidget() { glDeleteVertexArrays(1, &frame_vao); glDeleteBuffers(1, &frame_vbo); glDeleteBuffers(1, &frame_ibo); - glDeleteBuffers(3, textures); + glDeleteBuffers(2, textures); } doneCurrent(); } @@ -143,10 +156,15 @@ void CameraViewWidget::initializeGL() { glBindBuffer(GL_ARRAY_BUFFER, 0); glBindVertexArray(0); - glGenTextures(3, textures); glUseProgram(program->programId()); + +#ifdef QCOM2 + glUniform1i(program->uniformLocation("uTexture"), 0); +#else + glGenTextures(2, textures); glUniform1i(program->uniformLocation("uTextureY"), 0); glUniform1i(program->uniformLocation("uTextureUV"), 1); +#endif } void CameraViewWidget::showEvent(QShowEvent *event) { @@ -207,29 +225,33 @@ void CameraViewWidget::paintGL() { for (frame_idx = 0; frame_idx < frames.size() - 1; frame_idx++) { if (frames[frame_idx].first == draw_frame_id) break; } - VisionBuf *frame = frames[frame_idx].second; - glPixelStorei(GL_UNPACK_ALIGNMENT, 1); - glPixelStorei(GL_UNPACK_ROW_LENGTH, stream_stride); glViewport(0, 0, width(), height()); glBindVertexArray(frame_vao); - glUseProgram(program->programId()); + glPixelStorei(GL_UNPACK_ALIGNMENT, 1); + VisionBuf *frame = frames[frame_idx].second; + +#ifdef QCOM2 + glActiveTexture(GL_TEXTURE0); + glEGLImageTargetTexture2DOES(GL_TEXTURE_EXTERNAL_OES, egl_images[frame->idx]); + assert(glGetError() == GL_NO_ERROR); +#else + glPixelStorei(GL_UNPACK_ROW_LENGTH, stream_stride); glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, textures[0]); glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, stream_width, stream_height, GL_RED, GL_UNSIGNED_BYTE, frame->y); assert(glGetError() == GL_NO_ERROR); glPixelStorei(GL_UNPACK_ROW_LENGTH, stream_stride/2); - glActiveTexture(GL_TEXTURE0 + 1); glBindTexture(GL_TEXTURE_2D, textures[1]); glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, stream_width/2, stream_height/2, GL_RG, GL_UNSIGNED_BYTE, frame->uv); assert(glGetError() == GL_NO_ERROR); +#endif glUniformMatrix4fv(program->uniformLocation("uTransform"), 1, GL_TRUE, frame_mat.v); - assert(glGetError() == GL_NO_ERROR); glEnableVertexAttribArray(0); glDrawElements(GL_TRIANGLES, 6, GL_UNSIGNED_BYTE, (const void *)0); glDisableVertexAttribArray(0); @@ -247,6 +269,32 @@ void CameraViewWidget::vipcConnected(VisionIpcClient *vipc_client) { stream_height = vipc_client->buffers[0].height; stream_stride = vipc_client->buffers[0].stride; +#ifdef QCOM2 + egl_display = eglGetCurrentDisplay(); + + for (auto &pair : egl_images) { + eglDestroyImageKHR(egl_display, pair.second); + } + egl_images.clear(); + + for (int i = 0; i < vipc_client->num_buffers; i++) { // import buffers into OpenGL + int fd = dup(vipc_client->buffers[i].fd); // eglDestroyImageKHR will close, so duplicate + EGLint img_attrs[] = { + EGL_WIDTH, (int)vipc_client->buffers[i].width, + EGL_HEIGHT, (int)vipc_client->buffers[i].height, + EGL_LINUX_DRM_FOURCC_EXT, DRM_FORMAT_NV12, + EGL_DMA_BUF_PLANE0_FD_EXT, fd, + EGL_DMA_BUF_PLANE0_OFFSET_EXT, 0, + EGL_DMA_BUF_PLANE0_PITCH_EXT, (int)vipc_client->buffers[i].stride, + EGL_DMA_BUF_PLANE1_FD_EXT, fd, + EGL_DMA_BUF_PLANE1_OFFSET_EXT, (int)vipc_client->buffers[i].uv_offset, + EGL_DMA_BUF_PLANE1_PITCH_EXT, (int)vipc_client->buffers[i].stride, + EGL_NONE + }; + egl_images[i] = eglCreateImageKHR(egl_display, EGL_NO_CONTEXT, EGL_LINUX_DMA_BUF_EXT, 0, img_attrs); + assert(eglGetError() == EGL_SUCCESS); + } +#else glBindTexture(GL_TEXTURE_2D, textures[0]); glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); @@ -262,6 +310,7 @@ void CameraViewWidget::vipcConnected(VisionIpcClient *vipc_client) { glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); glTexImage2D(GL_TEXTURE_2D, 0, GL_RG8, stream_width/2, stream_height/2, 0, GL_RG, GL_UNSIGNED_BYTE, nullptr); assert(glGetError() == GL_NO_ERROR); +#endif updateFrameMat(width(), height()); } @@ -297,4 +346,11 @@ void CameraViewWidget::vipcThread() { emit vipcThreadFrameReceived(buf, meta_main.frame_id); } } + +#ifdef QCOM2 + for (auto &pair : egl_images) { + eglDestroyImageKHR(egl_display, pair.second); + } + egl_images.clear(); +#endif } diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index 953cbed00b..ddc3fc253b 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -6,6 +6,16 @@ #include #include #include + +#ifdef QCOM2 +#define EGL_EGLEXT_PROTOTYPES +#define EGL_NO_X11 +#define GL_TEXTURE_EXTERNAL_OES 0x8D65 +#include +#include +#include +#endif + #include "cereal/visionipc/visionipc_client.h" #include "selfdrive/camerad/cameras/camera_common.h" #include "selfdrive/ui/ui.h" @@ -41,11 +51,16 @@ protected: bool zoomed_view; GLuint frame_vao, frame_vbo, frame_ibo; - GLuint textures[3]; + GLuint textures[2]; mat4 frame_mat; std::unique_ptr program; QColor bg = QColor("#000000"); +#ifdef QCOM2 + EGLDisplay egl_display; + std::map egl_images; +#endif + std::string stream_name; int stream_width = 0; int stream_height = 0; From a2d2378ee147f2db59aecd3401677cb2427d1ced Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Mon, 13 Jun 2022 14:02:31 +0200 Subject: [PATCH 030/302] Laikad: process executor to fetch orbits (#24843) * Use ProcessPoolExecutor to fetch orbits * update laika repo * Minor --- laika_repo | 2 +- selfdrive/locationd/laikad.py | 64 ++++++++++++------------- selfdrive/locationd/test/test_laikad.py | 33 +++++++++---- 3 files changed, 57 insertions(+), 42 deletions(-) diff --git a/laika_repo b/laika_repo index d871946134..36f2621fc5 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit d87194613455b42af19ff2b5a3f7d1cae5852885 +Subproject commit 36f2621fc5348487bb2cd606c37c8c15de0e32cd diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 42c4156795..33e41398a0 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 import time -from multiprocessing import Process, Queue +from concurrent.futures import Future, ProcessPoolExecutor from typing import List, Optional import numpy as np @@ -10,7 +10,7 @@ from numpy.linalg import linalg from cereal import log, messaging from laika import AstroDog -from laika.constants import SECS_IN_MIN +from laika.constants import SECS_IN_HR, SECS_IN_MIN from laika.ephemeris import EphemerisType, convert_ublox_ephem from laika.gps_time import GPSTime from laika.helpers import ConstellationId @@ -29,8 +29,9 @@ class Laikad: def __init__(self, valid_const=("GPS", "GLONASS"), auto_update=False, valid_ephem_types=(EphemerisType.ULTRA_RAPID_ORBIT, EphemerisType.NAV)): self.astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types) self.gnss_kf = GNSSKalman(GENERATED_DIR) - self.orbit_p: Optional[Process] = None - self.orbit_q = Queue() + self.orbit_fetch_executor = ProcessPoolExecutor() + self.orbit_fetch_future: Optional[Future] = None + self.last_fetch_orbits_t = None def process_ublox_msg(self, ublox_msg, ublox_mono_time: int, block=False): if ublox_msg.which == 'measurementReport': @@ -82,7 +83,7 @@ class Laikad: return dat elif ublox_msg.which == 'ephemeris': ephem = convert_ublox_ephem(ublox_msg.ephemeris) - self.astro_dog.add_ephems([ephem], self.astro_dog.nav) + self.astro_dog.add_navs([ephem]) # elif ublox_msg.which == 'ionoData': # todo add this. Needed to better correct messages offline. First fix ublox_msg.cc to sent them. @@ -100,7 +101,7 @@ class Laikad: cloudlog.error("Gnss kalman std too far") if len(pos_fix) == 0: - cloudlog.error("Position fix not available when resetting kalman filter") + cloudlog.warning("Position fix not available when resetting kalman filter") return post_est = pos_fix[0][:3].tolist() self.init_gnss_localizer(post_est) @@ -124,36 +125,33 @@ class Laikad: self.gnss_kf.init_state(x_initial, covs_diag=p_initial_diag) - def get_orbit_data(self, t: GPSTime, queue): - cloudlog.info(f"Start to download/parse orbits for time {t.as_datetime()}") - start_time = time.monotonic() - try: - self.astro_dog.get_orbit_data(t, only_predictions=True) - except RuntimeError as e: - cloudlog.info(f"No orbit data found. {e}") - return - cloudlog.info(f"Done parsing orbits. Took {time.monotonic() - start_time:.2f}s") - if queue is not None: - queue.put((self.astro_dog.orbits, self.astro_dog.orbit_fetched_times)) - def fetch_orbits(self, t: GPSTime, block): - if t not in self.astro_dog.orbit_fetched_times: - if block: - self.get_orbit_data(t, None) - return - if self.orbit_p is None: - self.orbit_p = Process(target=self.get_orbit_data, args=(t, self.orbit_q)) - self.orbit_p.start() - if not self.orbit_q.empty(): - ret = self.orbit_q.get() + if t not in self.astro_dog.orbit_fetched_times and (self.last_fetch_orbits_t is None or t - self.last_fetch_orbits_t > SECS_IN_HR): + astro_dog_vars = self.astro_dog.valid_const, self.astro_dog.auto_update, self.astro_dog.valid_ephem_types + if self.orbit_fetch_future is None: + self.orbit_fetch_future = self.orbit_fetch_executor.submit(get_orbit_data, t, *astro_dog_vars) + if block: + self.orbit_fetch_future.result() + if self.orbit_fetch_future.done(): + ret = self.orbit_fetch_future.result() if ret: self.astro_dog.orbits, self.astro_dog.orbit_fetched_times = ret - self.orbit_p.join() - self.orbit_p = None - - def __del__(self): - if self.orbit_p is not None: - self.orbit_p.kill() + self.orbit_fetch_future = None + self.last_fetch_orbits_t = t + + +def get_orbit_data(t: GPSTime, valid_const, auto_update, valid_ephem_types): + astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types) + cloudlog.info(f"Start to download/parse orbits for time {t.as_datetime()}") + start_time = time.monotonic() + data = None + try: + astro_dog.get_orbit_data(t, only_predictions=True) + data = (astro_dog.orbits, astro_dog.orbit_fetched_times) + except RuntimeError as e: + cloudlog.info(f"No orbit data found. {e}") + cloudlog.info(f"Done parsing orbits. Took {time.monotonic() - start_time:.1f}s") + return data def create_measurement_msg(meas: GNSSMeasurement): diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py index 7a8c1ecb13..7dc803d799 100755 --- a/selfdrive/locationd/test/test_laikad.py +++ b/selfdrive/locationd/test/test_laikad.py @@ -69,29 +69,46 @@ class TestLaikad(unittest.TestCase): self.assertEqual(256, len(correct_msgs)) self.assertEqual(256, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid])) - def test_laika_get_orbits(self): - laikad = Laikad(auto_update=False) - first_gps_time = None + def get_first_gps_time(self): for m in self.logs: if m.ubloxGnss.which == 'measurementReport': new_meas = read_raw_ublox(m.ubloxGnss.measurementReport) if len(new_meas) != 0: - first_gps_time = new_meas[0].recv_time - break + return new_meas[0].recv_time + + def test_laika_get_orbits(self): + laikad = Laikad(auto_update=False) + first_gps_time = self.get_first_gps_time() # Pretend process has loaded the orbits on startup by using the time of the first gps message. laikad.fetch_orbits(first_gps_time, block=True) - self.assertEqual(29, len(laikad.astro_dog.orbits.keys())) + self.assertEqual(29, len(laikad.astro_dog.orbits.values())) + self.assertGreater(min([len(v) for v in laikad.astro_dog.orbits.values()]), 0) @unittest.skip("Use to debug live data") def test_laika_get_orbits_now(self): laikad = Laikad(auto_update=False) laikad.fetch_orbits(GPSTime.from_datetime(datetime.utcnow()), block=True) prn = "G01" - self.assertLess(0, len(laikad.astro_dog.orbits[prn])) + self.assertGreater(len(laikad.astro_dog.orbits[prn]), 0) prn = "R01" - self.assertLess(0, len(laikad.astro_dog.orbits[prn])) + self.assertGreater(len(laikad.astro_dog.orbits[prn]), 0) print(min(laikad.astro_dog.orbits[prn], key=lambda e: e.epoch).epoch.as_datetime()) + def test_get_orbits_in_process(self): + laikad = Laikad(auto_update=False) + has_orbits = False + for m in self.logs: + laikad.process_ublox_msg(m.ubloxGnss, m.logMonoTime, block=False) + if laikad.orbit_fetch_future is not None: + laikad.orbit_fetch_future.result() + vals = laikad.astro_dog.orbits.values() + has_orbits = len(vals) > 0 and max([len(v) for v in vals]) > 0 + if has_orbits: + break + self.assertTrue(has_orbits) + self.assertGreater(len(laikad.astro_dog.orbit_fetched_times._ranges), 0) + self.assertEqual(None, laikad.orbit_fetch_future) + if __name__ == "__main__": unittest.main() From fb068f04f50fcde6906072b4963114146852c51d Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 13 Jun 2022 16:43:50 +0200 Subject: [PATCH 031/302] camerad: remove unused SubMaster (#24844) --- selfdrive/camerad/cameras/camera_qcom2.cc | 7 ++----- selfdrive/camerad/cameras/camera_qcom2.h | 1 - selfdrive/camerad/test/camera_test.h | 1 - 3 files changed, 2 insertions(+), 7 deletions(-) diff --git a/selfdrive/camerad/cameras/camera_qcom2.cc b/selfdrive/camerad/cameras/camera_qcom2.cc index d43beb0921..c1ffc1275a 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.cc +++ b/selfdrive/camerad/cameras/camera_qcom2.cc @@ -837,7 +837,6 @@ void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_i s->road_cam.camera_init(s, v, CAMERA_ID_AR0231, 1, 20, device_id, ctx, VISION_STREAM_RGB_ROAD, VISION_STREAM_ROAD, !env_disable_road); s->wide_road_cam.camera_init(s, v, CAMERA_ID_AR0231, 0, 20, device_id, ctx, VISION_STREAM_RGB_WIDE_ROAD, VISION_STREAM_WIDE_ROAD, !env_disable_wide_road); - s->sm = new SubMaster({"driverState"}); s->pm = new PubMaster({"roadCameraState", "driverCameraState", "wideRoadCameraState", "thumbnail"}); } @@ -948,7 +947,6 @@ void cameras_close(MultiCameraState *s) { s->road_cam.camera_close(); s->wide_road_cam.camera_close(); - delete s->sm; delete s->pm; } @@ -1221,7 +1219,7 @@ static void ar0231_process_registers(MultiCameraState *s, CameraState *c, cereal framed.setTemperaturesC({temp_0, temp_1}); } -static void driver_cam_auto_exposure(CameraState *c, SubMaster &sm) { +static void driver_cam_auto_exposure(CameraState *c) { struct ExpRect {int x1, x2, x_skip, y1, y2, y_skip;}; const CameraBuf *b = &c->buf; static ExpRect rect = {96, 1832, 2, 242, 1148, 4}; @@ -1229,8 +1227,7 @@ static void driver_cam_auto_exposure(CameraState *c, SubMaster &sm) { } static void process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) { - s->sm->update(0); - driver_cam_auto_exposure(c, *(s->sm)); + driver_cam_auto_exposure(c); MessageBuilder msg; auto framed = msg.initEvent().initDriverCameraState(); diff --git a/selfdrive/camerad/cameras/camera_qcom2.h b/selfdrive/camerad/cameras/camera_qcom2.h index d869620e9a..88766a68e9 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.h +++ b/selfdrive/camerad/cameras/camera_qcom2.h @@ -106,6 +106,5 @@ typedef struct MultiCameraState { CameraState wide_road_cam; CameraState driver_cam; - SubMaster *sm; PubMaster *pm; } MultiCameraState; diff --git a/selfdrive/camerad/test/camera_test.h b/selfdrive/camerad/test/camera_test.h index cc521db397..a9f213c923 100644 --- a/selfdrive/camerad/test/camera_test.h +++ b/selfdrive/camerad/test/camera_test.h @@ -19,7 +19,6 @@ typedef struct MultiCameraState { CameraState road_cam; CameraState driver_cam; - SubMaster *sm = nullptr; PubMaster *pm = nullptr; } MultiCameraState; From 7bca95dbb89dc6b969871cc7f6bf4306d91f60cc Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 13 Jun 2022 16:44:38 +0200 Subject: [PATCH 032/302] navd: speed limits only when localizer is valid (#24845) --- selfdrive/navd/navd.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/selfdrive/navd/navd.py b/selfdrive/navd/navd.py index fcd53d8b60..509653a46d 100755 --- a/selfdrive/navd/navd.py +++ b/selfdrive/navd/navd.py @@ -32,6 +32,7 @@ class RouteEngine: self.last_bearing = None self.gps_ok = False + self.localizer_valid = False self.nav_destination = None self.step_idx = None @@ -73,9 +74,9 @@ class RouteEngine: location = self.sm['liveLocationKalman'] self.gps_ok = location.gpsOK - localizer_valid = (location.status == log.LiveLocationKalman.Status.valid) and location.positionGeodetic.valid + self.localizer_valid = (location.status == log.LiveLocationKalman.Status.valid) and location.positionGeodetic.valid - if localizer_valid: + if self.localizer_valid: self.last_bearing = math.degrees(location.calibratedOrientationNED.value[2]) self.last_position = Coordinate(location.positionGeodetic.value[0], location.positionGeodetic.value[1]) @@ -202,7 +203,7 @@ class RouteEngine: if along_geometry < distance_along_geometry(geometry, geometry[closest_idx]): closest = geometry[closest_idx - 1] - if 'maxspeed' in closest.annotations: + if ('maxspeed' in closest.annotations) and self.localizer_valid: msg.navInstruction.speedLimit = closest.annotations['maxspeed'] # Speed limit sign type From 566de12671f7fbf299306339c0ca901754f7f3ca Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 13 Jun 2022 09:29:28 -0700 Subject: [PATCH 033/302] Toyota Camry TSS2: update torque control params (#24819) Use updated accel and friction values for TSS2 Camry --- selfdrive/car/toyota/interface.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 83eed611c3..53accecfe0 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -31,6 +31,7 @@ class CarInterface(CarInterfaceBase): ret.stoppingControl = False # Toyota starts braking more when it thinks you want to stop stop_and_go = False + torque_params = CarInterfaceBase.get_torque_params(candidate) if candidate == CAR.PRIUS: stop_and_go = True @@ -91,8 +92,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.7933 ret.mass = 3400. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid if candidate in (CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2): - ret.maxLateralAccel = 2.4 - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=ret.maxLateralAccel, FRICTION=0.05) + set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION']) else: set_lat_tune(ret.lateralTuning, LatTunes.PID_C) From f05166ae26eb8165f35e8205b59c36e618d179b8 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 13 Jun 2022 13:58:22 -0700 Subject: [PATCH 034/302] ui.py: update for nv12 --- tools/replay/ui.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/replay/ui.py b/tools/replay/ui.py index 1807fb7747..bbcd49061e 100755 --- a/tools/replay/ui.py +++ b/tools/replay/ui.py @@ -118,7 +118,7 @@ def ui_thread(addr): imgff = np.frombuffer(yuv_img_raw, dtype=np.uint8).reshape((vipc_client.height * 3 // 2, vipc_client.width)) num_px = vipc_client.width * vipc_client.height - bgr = cv2.cvtColor(imgff, cv2.COLOR_YUV2RGB_I420) + bgr = cv2.cvtColor(imgff, cv2.COLOR_YUV2RGB_NV12) zoom_matrix = _BB_TO_FULL_FRAME[num_px] cv2.warpAffine(bgr, zoom_matrix[:2], (img.shape[1], img.shape[0]), dst=img, flags=cv2.WARP_INVERSE_MAP) From cbd404b954b5b80b65f1ad8363b0245c3c7c7911 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 13 Jun 2022 16:38:32 -0700 Subject: [PATCH 035/302] Revert "thermald: consider pmic in component temp management (#24708)" This reverts commit c8c21baf50865b0db2cc9345901bb98904cfbaaf. --- selfdrive/thermald/thermald.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 403e9cb232..b909d1198c 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -249,7 +249,7 @@ def thermald_thread(end_event, hw_queue): current_filter.update(msg.deviceState.batteryCurrent / 1e6) max_comp_temp = temp_filter.update( - max(max(msg.deviceState.cpuTempC), msg.deviceState.memoryTempC, max(msg.deviceState.gpuTempC), max(msg.deviceState.pmicTempC)) + max(max(msg.deviceState.cpuTempC), msg.deviceState.memoryTempC, max(msg.deviceState.gpuTempC)) ) if fan_controller is not None: From be13fc71f1237eb56a9d1cf2d7a0feb11b55d0b7 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Mon, 13 Jun 2022 16:54:32 -0700 Subject: [PATCH 036/302] Couple more cars to torque tune (#24848) * try sonata on torque tune * Couple known cars to torque control * fix * more fix --- selfdrive/car/hyundai/interface.py | 22 ++++++++-------------- 1 file changed, 8 insertions(+), 14 deletions(-) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 08af654996..6fd75ebfab 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -55,7 +55,7 @@ class CarInterface(CarInterfaceBase): ret.stopAccel = 0.0 ret.longitudinalActuatorDelayUpperBound = 1.0 # s - + torque_params = CarInterfaceBase.get_torque_params(candidate) if candidate in (CAR.SANTA_FE, CAR.SANTA_FE_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022): ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3982. * CV.LB_TO_KG + STD_CARGO_KG @@ -66,13 +66,11 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[9., 22.], [9., 22.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.35], [0.05, 0.09]] elif candidate in (CAR.SONATA, CAR.SONATA_HYBRID): - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 1513. + STD_CARGO_KG ret.wheelbase = 2.84 ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable tire_stiffness_factor = 0.65 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] + set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION']) elif candidate == CAR.SONATA_LF: ret.lateralTuning.pid.kf = 0.00005 ret.mass = 4497. * CV.LB_TO_KG @@ -98,21 +96,17 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.ELANTRA_2021: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = (2800. * CV.LB_TO_KG) + STD_CARGO_KG ret.wheelbase = 2.72 ret.steerRatio = 12.9 tire_stiffness_factor = 0.65 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] + set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION']) elif candidate == CAR.ELANTRA_HEV_2021: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = (3017. * CV.LB_TO_KG) + STD_CARGO_KG ret.wheelbase = 2.72 ret.steerRatio = 12.9 tire_stiffness_factor = 0.65 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] + set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION']) elif candidate == CAR.HYUNDAI_GENESIS: ret.lateralTuning.pid.kf = 0.00005 ret.mass = 2060. + STD_CARGO_KG @@ -210,13 +204,12 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.indi.actuatorEffectivenessBP = [0.] ret.lateralTuning.indi.actuatorEffectivenessV = [1.8] elif candidate in (CAR.KIA_OPTIMA, CAR.KIA_OPTIMA_H): - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3558. * CV.LB_TO_KG ret.wheelbase = 2.80 ret.steerRatio = 13.75 tire_stiffness_factor = 0.5 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] + torque_params = CarInterfaceBase.get_torque_params(CAR.KIA_OPTIMA) + set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION']) elif candidate == CAR.KIA_STINGER: ret.lateralTuning.pid.kf = 0.00005 ret.mass = 1825. + STD_CARGO_KG @@ -258,7 +251,8 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.65 ret.maxLateralAccel = 2. - set_torque_tune(ret.lateralTuning, ret.maxLateralAccel, 0.01) + # TODO override until there is more data + set_torque_tune(ret.lateralTuning, 2.0, 0.05) # Genesis elif candidate == CAR.GENESIS_G70: From 25eafa96264aa2f8851b2f0d633de0c7cce3e743 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 13 Jun 2022 18:42:47 -0700 Subject: [PATCH 037/302] Honda Bosch long: fix ACC fault (#24851) Fix Honda bosch long Co-authored-by: redacid95 Co-authored-by: redacid95 --- selfdrive/car/honda/hondacan.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py index 9c9e873e18..3d8c79c809 100644 --- a/selfdrive/car/honda/hondacan.py +++ b/selfdrive/car/honda/hondacan.py @@ -115,7 +115,7 @@ def create_ui_commands(packer, CP, enabled, pcm_speed, hud, is_metric, idx, stoc } if CP.carFingerprint in HONDA_BOSCH: - acc_hud_values['ACC_ON'] = hud.car != 0 + acc_hud_values['ACC_ON'] = int(enabled) acc_hud_values['FCM_OFF'] = 1 acc_hud_values['FCM_OFF_2'] = 1 else: From dbfe923ecc0e14a781a7f03646ccf885ab2fa47a Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Mon, 13 Jun 2022 19:08:09 -0700 Subject: [PATCH 038/302] Move couple toyotas to torque table values (#24849) * Move couple toyotas to torque table values * Dont set for all cars yet * Dont regress docs * update ref --- selfdrive/car/toyota/interface.py | 24 ++++++++++++------------ selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 53accecfe0..9ca9e4e11b 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -2,6 +2,7 @@ from cereal import car from common.conversions import Conversions as CV from panda import Panda +from selfdrive.controls.lib.latcontrol_torque import set_torque_tune from selfdrive.car.toyota.tunes import LatTunes, LongTunes, set_long_tune, set_lat_tune from selfdrive.car.toyota.values import Ecu, CAR, ToyotaFlags, TSS2_CAR, RADAR_ACC_CAR, NO_DSU_CAR, MIN_ACC_SPEED, EPS_SCALE, EV_HYBRID_CAR, CarControllerParams from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config @@ -32,6 +33,8 @@ class CarInterface(CarInterfaceBase): stop_and_go = False torque_params = CarInterfaceBase.get_torque_params(candidate) + steering_angle_deadzone_deg = 0.0 + set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION'], steering_angle_deadzone_deg) if candidate == CAR.PRIUS: stop_and_go = True @@ -39,8 +42,11 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 15.74 # unknown end-to-end spec tire_stiffness_factor = 0.6371 # hand-tune ret.mass = 3045. * CV.LB_TO_KG + STD_CARGO_KG - ret.maxLateralAccel = 1.7 - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=ret.maxLateralAccel, FRICTION=0.06, steering_angle_deadzone_deg=1.0) + # Only give steer angle deadzone to for bad angle sensor prius + for fw in car_fw: + if fw.ecu == "eps" and not fw.fwVersion == b'8965B47060\x00\x00\x00\x00\x00\x00': + steering_angle_deadzone_deg = 1.0 + set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION'], steering_angle_deadzone_deg) elif candidate == CAR.PRIUS_V: stop_and_go = True @@ -48,8 +54,10 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 17.4 tire_stiffness_factor = 0.5533 ret.mass = 3340. * CV.LB_TO_KG + STD_CARGO_KG + # TODO override until there is enough data ret.maxLateralAccel = 1.8 - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=ret.maxLateralAccel, FRICTION=0.06) + torque_params = CarInterfaceBase.get_torque_params(CAR.PRIUS) + set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION'], steering_angle_deadzone_deg) elif candidate in (CAR.RAV4, CAR.RAV4H): stop_and_go = True if (candidate in CAR.RAV4H) else False @@ -57,16 +65,12 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.88 # 14.5 is spec end-to-end tire_stiffness_factor = 0.5533 ret.mass = 3650. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid - ret.maxLateralAccel = 1.8 - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=ret.maxLateralAccel, FRICTION=0.06) elif candidate == CAR.COROLLA: ret.wheelbase = 2.70 ret.steerRatio = 18.27 tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 2860. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid - ret.maxLateralAccel = 2.8 - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=ret.maxLateralAccel, FRICTION=0.024) elif candidate in (CAR.LEXUS_RX, CAR.LEXUS_RXH, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2): stop_and_go = True @@ -91,9 +95,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.7 tire_stiffness_factor = 0.7933 ret.mass = 3400. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid - if candidate in (CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2): - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION']) - else: + if candidate not in (CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2): set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate in (CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2): @@ -143,8 +145,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.9 tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 3060. * CV.LB_TO_KG + STD_CARGO_KG - ret.maxLateralAccel = 2.0 - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=ret.maxLateralAccel, FRICTION=0.07) elif candidate in (CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.LEXUS_ESH): stop_and_go = True diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 613b7f26ae..61bbd5cdd1 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -123506cad1877e93bfe5c91ecdce654ef339959b +fe2da24194e3def1823681cc18e7879f24edfc6e From a78197ab1af40dcdc0fe5a8f764b476da3837e87 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 13 Jun 2022 21:49:50 -0700 Subject: [PATCH 039/302] Move RAV4 2022 out of bronze --- docs/CARS.md | 6 +++--- selfdrive/car/toyota/interface.py | 4 ++++ 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 479c519dab..9b3322ac8e 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -68,7 +68,7 @@ How We Rate The Cars |Toyota|RAV4 2019-21|All|||||| |Toyota|RAV4 Hybrid 2019-21|All|||||| -# Silver - 75 cars +# Silver - 76 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -130,6 +130,7 @@ How We Rate The Cars |Toyota|Highlander Hybrid 2017-19|All|[3](#footnotes)||||| |Toyota|Prius 2016-20|TSS-P|[3](#footnotes)||||| |Toyota|Prius Prime 2017-20|All|[3](#footnotes)||||| +|Toyota|RAV4 2022|All|||||| |Toyota|RAV4 Hybrid 2016-18|TSS-P|[3](#footnotes)||||| |Toyota|RAV4 Hybrid 2022|All|||||| |Toyota|Sienna 2018-20|All|[3](#footnotes)||||| @@ -148,7 +149,7 @@ How We Rate The Cars |Volkswagen|Taos 2022[7](#footnotes)|Driver Assistance|||||| |Volkswagen|Touran 2017|Driver Assistance|||||| -# Bronze - 70 cars +# Bronze - 69 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -214,7 +215,6 @@ How We Rate The Cars |Toyota|Corolla 2017-19|All|[3](#footnotes)||||| |Toyota|Prius v 2017|TSS-P|[3](#footnotes)||||| |Toyota|RAV4 2016-18|TSS-P|[3](#footnotes)||||| -|Toyota|RAV4 2022|All|||||| |Volkswagen|Arteon 2018, 2021[7](#footnotes)|Driver Assistance|||||| |Volkswagen|California 2021[7](#footnotes)|Driver Assistance|||||| |Volkswagen|Caravelle 2020[7](#footnotes)|Driver Assistance|||||| diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 9ca9e4e11b..7969775a89 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -132,6 +132,10 @@ class CarInterface(CarInterfaceBase): ret.mass = 3585. * CV.LB_TO_KG + STD_CARGO_KG # Average between ICE and Hybrid set_lat_tune(ret.lateralTuning, LatTunes.PID_D) + # TODO: remove once there's data + if candidate == CAR.RAV4_TSS2_2022: + ret.maxLateralAccel = CarInterfaceBase.get_torque_params(CAR.RAV4H_TSS2_2022)['MAX_LAT_ACCEL_MEASURED'] + # 2019+ RAV4 TSS2 uses two different steering racks and specific tuning seems to be necessary. # See https://github.com/commaai/openpilot/pull/21429#issuecomment-873652891 for fw in car_fw: From 1ba8022c184a7e643c2714aaad1aa45e5e68501c Mon Sep 17 00:00:00 2001 From: YassineYousfi Date: Mon, 13 Jun 2022 22:26:31 -0700 Subject: [PATCH 040/302] pin protobuf and hypothesis versions (#24852) pin hypothesis and protobuf --- Pipfile | 3 ++- Pipfile.lock | 58 +++++++++++++++++++++++++++++++++++++--------------- 2 files changed, 44 insertions(+), 17 deletions(-) diff --git a/Pipfile b/Pipfile index 2ffe60e0fe..672692fe40 100644 --- a/Pipfile +++ b/Pipfile @@ -11,7 +11,7 @@ coverage = "*" dictdiffer = "*" fastcluster = "*" hexdump = "*" -hypothesis = "*" +hypothesis = "==6.46.7" inputs = "*" lru-dict = "*" markdown-it-py = "*" @@ -58,6 +58,7 @@ json-rpc = "*" libusb1 = "*" nose = "*" numpy = "*" +protobuf = "==3.20.1" onnx = "*" onnxruntime-gpu = {version = "*", markers="platform_system != 'Darwin'"} pillow = "*" diff --git a/Pipfile.lock b/Pipfile.lock index 25a97890d3..ee0fbc7e84 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "eb1eeeaabf1266fab353532d10e4d9ae36306a7577f248513909c2d6096ab1c9" + "sha256": "7af354a7ae976b12da1b5f15f0cebdc77595199c11b0bfeb8be9c2827f335c48" }, "pipfile-spec": 6, "requires": { @@ -18,11 +18,11 @@ "default": { "astroid": { "hashes": [ - "sha256:14ffbb4f6aa2cf474a0834014005487f7ecd8924996083ab411e7fa0b508ce0b", - "sha256:f4e4ec5294c4b07ac38bab9ca5ddd3914d4bf46f9006eb5c0ae755755061044e" + "sha256:4f933d0bf5e408b03a6feb5d23793740c27e07340605f236496cd6ce552043d6", + "sha256:ba33a82a9a9c06a5ceed98180c5aab16e29c285b828d94696bf32d6015ea82a9" ], "markers": "python_full_version >= '3.6.2'", - "version": "==2.11.5" + "version": "==2.11.6" }, "atomicwrites": { "hashes": [ @@ -371,7 +371,7 @@ "sha256:6f62d78e2f89b4500b080fe3a81690850cd254227f27f75c3a0c491a1f351ba7", "sha256:e8443a5e7a020e9d7f97f1d7d9cd17c88bcb3bc7e218bf9cf5095fe550be2951" ], - "markers": "python_version < '4' and python_full_version >= '3.6.1'", + "markers": "python_version < '4.0' and python_full_version >= '3.6.1'", "version": "==5.10.1" }, "itsdangerous": { @@ -687,23 +687,47 @@ }, "protobuf": { "hashes": [ + "sha256:06059eb6953ff01e56a25cd02cca1a9649a75a7e65397b5b9b4e929ed71d10cf", + "sha256:097c5d8a9808302fb0da7e20edf0b8d4703274d140fd25c5edabddcde43e081f", "sha256:0d4719e724472e296062ba8e82a36d64693fcfdb550d9dff98af70ca79eafe3d", + "sha256:284f86a6207c897542d7e956eb243a36bb8f9564c1742b253462386e96c6b78f", "sha256:2b35602cb65d53c168c104469e714bf68670335044c38eee3c899d6a8af03ffc", + "sha256:32ca378605b41fd180dfe4e14d3226386d8d1b002ab31c969c366549e66a2bb7", "sha256:32fff501b6df3050936d1839b80ea5899bf34db24792d223d7640611f67de15a", "sha256:34400fd76f85bdae9a2e9c1444ea4699c0280962423eff4418765deceebd81b5", "sha256:3767c64593a49c7ac0accd08ed39ce42744405f0989d468f0097a17496fdbe84", + "sha256:3cc797c9d15d7689ed507b165cd05913acb992d78b379f6014e013f9ecb20996", "sha256:3f2ed842e8ca43b790cb4a101bcf577226e0ded98a6a6ba2d5e12095a08dc4da", "sha256:52c1e44e25f2949be7ffa7c66acbfea940b0945dd416920231f7cb30ea5ac6db", "sha256:5d9b5c8270461706973c3871c6fbdd236b51dfe9dab652f1fb6a36aa88287e47", + "sha256:62f1b5c4cd6c5402b4e2d63804ba49a327e0c386c99b1675c8a0fefda23b2067", + "sha256:69ccfdf3657ba59569c64295b7d51325f91af586f8d5793b734260dfe2e94e2c", + "sha256:6f50601512a3d23625d8a85b1638d914a0970f17920ff39cec63aaef80a93fb7", "sha256:72d357cc4d834cc85bd957e8b8e1f4b64c2eac9ca1a942efeb8eb2e723fca852", + "sha256:7403941f6d0992d40161aa8bb23e12575637008a5a02283a930addc0508982f9", + "sha256:755f3aee41354ae395e104d62119cb223339a8f3276a0cd009ffabfcdd46bb0c", + "sha256:77053d28427a29987ca9caf7b72ccafee011257561259faba8dd308fda9a8739", "sha256:79cd8d0a269b714f6b32641f86928c718e8d234466919b3f552bfb069dbb159b", + "sha256:7e371f10abe57cee5021797126c93479f59fccc9693dafd6bd5633ab67808a91", + "sha256:9016d01c91e8e625141d24ec1b20fed584703e527d28512aa8c8707f105a683c", + "sha256:9be73ad47579abc26c12024239d3540e6b765182a91dbc88e23658ab71767153", "sha256:a4c0c6f2f95a559e59a0258d3e4b186f340cbdc5adec5ce1bc06d01972527c88", + "sha256:adc31566d027f45efe3f44eeb5b1f329da43891634d61c75a5944e9be6dd42c9", + "sha256:adfc6cf69c7f8c50fd24c793964eef18f0ac321315439d94945820612849c388", + "sha256:af0ebadc74e281a517141daad9d0f2c5d93ab78e9d455113719a45a49da9db4e", "sha256:b309fda192850ac4184ca1777aab9655564bc8d10a9cc98f10e1c8bf11295c22", "sha256:b3d7d4b4945fe3c001403b6c24442901a5e58c0a3059290f5a63523ed4435f82", - "sha256:c8829092c5aeb61619161269b2f8a2e36fd7cb26abbd9282d3bc453f02769146" + "sha256:c8829092c5aeb61619161269b2f8a2e36fd7cb26abbd9282d3bc453f02769146", + "sha256:cb29edb9eab15742d791e1025dd7b6a8f6fcb53802ad2f6e3adcb102051063ab", + "sha256:cd68be2559e2a3b84f517fb029ee611546f7812b1fdd0aa2ecc9bc6ec0e4fdde", + "sha256:cdee09140e1cd184ba9324ec1df410e7147242b94b5f8b0c64fc89e38a8ba531", + "sha256:db977c4ca738dd9ce508557d4fce0f5aebd105e158c725beec86feb1f6bc20d8", + "sha256:dd5789b2948ca702c17027c84c2accb552fc30f4622a98ab5c51fcfe8c50d3e7", + "sha256:e250a42f15bf9d5b09fe1b293bdba2801cd520a9f5ea2d7fb7536d4441811d20", + "sha256:ff8d8fa42675249bb456f5db06c00de6c2f4c27a065955917b28c4f15978b9c3" ], - "markers": "python_version >= '3.7'", - "version": "==4.21.1" + "index": "pypi", + "version": "==3.20.1" }, "psutil": { "hashes": [ @@ -1155,11 +1179,11 @@ }, "setuptools": { "hashes": [ - "sha256:1f5d3a1502812025cdb2e5609b6af2d207332e3f50febe6db10ed3a59b2f155f", - "sha256:30b6b0fbacc459c90d27a63e6173facfc8b8c99a48fb24b5044f459ba63cd6cf" + "sha256:5a844ad6e190dccc67d6d7411d119c5152ce01f7c76be4d8a1eaa314501bba77", + "sha256:bf8a748ac98b09d32c9a64a995a6b25921c96cc5743c1efa82763ba80ff54e91" ], "markers": "python_version >= '3.7'", - "version": "==62.3.4" + "version": "==62.4.0" }, "six": { "hashes": [ @@ -1206,7 +1230,7 @@ "sha256:0f4050db66fd445b885778900ce4dd9aea8c90c4721141fde0d6ade893820ef1", "sha256:71ceb10c0eefd8b8f11fe34e8a51ad07812cb1dc3de23247425fbc9ddc47b9dd" ], - "markers": "python_version >= '3.6' and python_version < '4'", + "markers": "python_version >= '3.6' and python_version < '4.0'", "version": "==0.11.0" }, "tqdm": { @@ -1222,7 +1246,7 @@ "sha256:6657594ee297170d19f67d55c05852a874e7eb634f4f753dbd667855e07c1708", "sha256:f1c24655a0da0d1b67f07e17a5e6b2a105894e6824b92096378bb3668ef02376" ], - "markers": "python_version < '3.10'", + "markers": "python_version >= '3.7'", "version": "==4.2.0" }, "urllib3": { @@ -1733,11 +1757,13 @@ }, "hypothesis": { "hashes": [ + "sha256:2696cdb9005946bf1d2b215cc91d3fc01625e3342eb8743ddd04b667b2f1882b", "sha256:4ad26c5d434171ffc02aba569dd52255573d615554c062bc30734dbe6f318c61", - "sha256:69978811f1d9c19710c7d2bf8233dc43c80efa964251b72efbe8274044e073b4" + "sha256:69978811f1d9c19710c7d2bf8233dc43c80efa964251b72efbe8274044e073b4", + "sha256:967009fa561b3a3f8363a73d71923357271c37dc7fa27b30c2d21a1b6092b240" ], "index": "pypi", - "version": "==6.47.1" + "version": "==6.46.7" }, "identify": { "hashes": [ @@ -2546,7 +2572,7 @@ "sha256:6657594ee297170d19f67d55c05852a874e7eb634f4f753dbd667855e07c1708", "sha256:f1c24655a0da0d1b67f07e17a5e6b2a105894e6824b92096378bb3668ef02376" ], - "markers": "python_version < '3.10'", + "markers": "python_version >= '3.7'", "version": "==4.2.0" }, "urllib3": { From a9038bc3fd0ed12b441804923c46927b5f6bbbfe Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 13 Jun 2022 22:27:44 -0700 Subject: [PATCH 041/302] bump opendbc (#24853) --- opendbc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc b/opendbc index 58a2c9b2fc..a7b391cce8 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 58a2c9b2fc5c60ca68d3dced09f6c4c72ca72415 +Subproject commit a7b391cce88908824f1417f0c7abd35e3ae16f96 From 170ed3d761a58222a626c86b9706f9be4900d058 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 14 Jun 2022 12:03:30 -0700 Subject: [PATCH 042/302] process replay: clean up common code (#24855) * regen and process replay clean up * test_fuzzy actually uses fingerprint hardcoding fix * revert * revert * this can be a url or path so just print full variable --- .../test/process_replay/process_replay.py | 35 ++++++++----------- selfdrive/test/process_replay/regen.py | 19 +--------- selfdrive/test/process_replay/regen_all.py | 14 ++++---- .../test/process_replay/test_processes.py | 3 +- 4 files changed, 24 insertions(+), 47 deletions(-) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 1eda9bc7f5..363035ab22 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -347,7 +347,7 @@ def replay_process(cfg, lr, fingerprint=None): else: return cpp_replay_process(cfg, lr, fingerprint) -def setup_env(simulation=False): +def setup_env(simulation=False, CP=None): params = Params() params.clear_all() params.put_bool("OpenpilotEnabledToggle", True) @@ -358,12 +358,22 @@ def setup_env(simulation=False): os.environ["NO_RADAR_SLEEP"] = "1" os.environ["REPLAY"] = "1" + os.environ['SKIP_FW_QUERY'] = "" + os.environ['FINGERPRINT'] = "" if simulation: os.environ["SIMULATION"] = "1" elif "SIMULATION" in os.environ: del os.environ["SIMULATION"] + # Regen or python process + if CP is not None: + if CP.fingerprintSource == "fw" and CP.carFingerprint in FW_VERSIONS: + params.put("CarParamsCache", CP.as_builder().to_bytes()) + else: + os.environ['SKIP_FW_QUERY'] = "1" + os.environ['FINGERPRINT'] = CP.carFingerprint + def python_replay_process(cfg, lr, fingerprint=None): sub_sockets = [s for _, sub in cfg.pub_sub.items() for s in sub] pub_sockets = [s for s in cfg.pub_sub.keys() if s != 'can'] @@ -378,30 +388,13 @@ def python_replay_process(cfg, lr, fingerprint=None): all_msgs = sorted(lr, key=lambda msg: msg.logMonoTime) pub_msgs = [msg for msg in all_msgs if msg.which() in list(cfg.pub_sub.keys())] - setup_env() - - # TODO: remove after getting new route for civic & accord - migration = { - "HONDA CIVIC 2016 TOURING": "HONDA CIVIC 2016", - "HONDA ACCORD 2018 SPORT 2T": "HONDA ACCORD 2018", - "HONDA ACCORD 2T 2018": "HONDA ACCORD 2018", - "Mazda CX-9 2021": "MAZDA CX-9 2021", - } - if fingerprint is not None: os.environ['SKIP_FW_QUERY'] = "1" os.environ['FINGERPRINT'] = fingerprint + setup_env() else: - os.environ['SKIP_FW_QUERY'] = "" - os.environ['FINGERPRINT'] = "" - for msg in lr: - if msg.which() == 'carParams': - car_fingerprint = migration.get(msg.carParams.carFingerprint, msg.carParams.carFingerprint) - if msg.carParams.fingerprintSource == "fw" and (car_fingerprint in FW_VERSIONS): - Params().put("CarParamsCache", msg.carParams.as_builder().to_bytes()) - else: - os.environ['SKIP_FW_QUERY'] = "1" - os.environ['FINGERPRINT'] = car_fingerprint + CP = [m for m in lr if m.which() == 'carParams'][0].carParams + setup_env(CP=CP) assert(type(managed_processes[cfg.proc_name]) is PythonProcess) managed_processes[cfg.proc_name].prepare() diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py index 653efaf32c..dfc62a4558 100755 --- a/selfdrive/test/process_replay/regen.py +++ b/selfdrive/test/process_replay/regen.py @@ -15,7 +15,6 @@ from cereal.visionipc import VisionIpcServer, VisionStreamType from common.params import Params from common.realtime import Ratekeeper, DT_MDL, DT_DMON, sec_since_boot from common.transformations.camera import eon_f_frame_size, eon_d_frame_size, tici_f_frame_size, tici_d_frame_size -from selfdrive.car.fingerprints import FW_VERSIONS from selfdrive.manager.process import ensure_running from selfdrive.manager.process_config import managed_processes from selfdrive.test.process_replay.process_replay import FAKEDATA, setup_env, check_enabled @@ -181,28 +180,12 @@ def regen_segment(lr, frs=None, outdir=FAKEDATA, disable_tqdm=False): if frs is None: frs = dict() - setup_env() params = Params() - os.environ["LOG_ROOT"] = outdir - os.environ['SKIP_FW_QUERY'] = "" - os.environ['FINGERPRINT'] = "" - - # TODO: remove after getting new route for Mazda - fp_migration = { - "Mazda CX-9 2021": "MAZDA CX-9 2021", - } - # TODO: remove after getting new route for Subaru - fingerprint_problem = ["SUBARU IMPREZA LIMITED 2019"] for msg in lr: if msg.which() == 'carParams': - car_fingerprint = fp_migration.get(msg.carParams.carFingerprint, msg.carParams.carFingerprint) - if len(msg.carParams.carFw) and (car_fingerprint in FW_VERSIONS) and (car_fingerprint not in fingerprint_problem): - params.put("CarParamsCache", msg.carParams.as_builder().to_bytes()) - else: - os.environ['SKIP_FW_QUERY'] = "1" - os.environ['FINGERPRINT'] = car_fingerprint + setup_env(CP=msg.carParams) elif msg.which() == 'liveCalibration': params.put("CalibrationParams", msg.as_builder().to_bytes()) diff --git a/selfdrive/test/process_replay/regen_all.py b/selfdrive/test/process_replay/regen_all.py index 765e5c3b68..c3ea1d41e1 100755 --- a/selfdrive/test/process_replay/regen_all.py +++ b/selfdrive/test/process_replay/regen_all.py @@ -8,26 +8,28 @@ from tqdm import tqdm from selfdrive.test.process_replay.helpers import OpenpilotPrefix from selfdrive.test.process_replay.regen import regen_and_save from selfdrive.test.process_replay.test_processes import FAKEDATA, original_segments as segments +from tools.lib.route import SegmentName -def regen_job(segment): + +def regen_job(segment, disable_tqdm): with OpenpilotPrefix(): - route = segment[1].rsplit('--', 1)[0] - sidx = int(segment[1].rsplit('--', 1)[1]) - fake_dongle_id = 'regen' + ''.join(random.choice('0123456789ABCDEF') for i in range(11)) + sn = SegmentName(segment[1]) + fake_dongle_id = 'regen' + ''.join(random.choice('0123456789ABCDEF') for _ in range(11)) try: - relr = regen_and_save(route, sidx, upload=True, use_route_meta=False, outdir=os.path.join(FAKEDATA, fake_dongle_id), disable_tqdm=True) + relr = regen_and_save(sn.route_name.canonical_name, sn.segment_num, upload=True, use_route_meta=False, outdir=os.path.join(FAKEDATA, fake_dongle_id), disable_tqdm=disable_tqdm) relr = '|'.join(relr.split('/')[-2:]) return f' ("{segment[0]}", "{relr}"), ' except Exception as e: return f" {segment} failed: {str(e)}" + if __name__ == "__main__": parser = argparse.ArgumentParser(description="Generate new segments from old ones") parser.add_argument("-j", "--jobs", type=int, default=1) args = parser.parse_args() with concurrent.futures.ProcessPoolExecutor(max_workers=args.jobs) as pool: - p = list(pool.map(regen_job, segments)) + p = list(pool.map(regen_job, segments, [args.jobs > 1] * args.jobs)) msg = "Copy these new segments into test_processes.py:" for seg in tqdm(p, desc="Generating segments"): msg += "\n" + str(seg) diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 9f83a08e23..25fbd210cc 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -93,8 +93,7 @@ def test_process(cfg, lr, ref_log_path, ignore_fields=None, ignore_msgs=None): # check to make sure openpilot is engaged in the route if cfg.proc_name == "controlsd": if not check_enabled(log_msgs): - segment = os.path.basename(ref_log_path).split("/")[-1].split("_")[0] - raise Exception(f"Route never enabled: {segment}") + raise Exception(f"Route never enabled: {ref_log_path}") try: return compare_logs(ref_log_msgs, log_msgs, ignore_fields + cfg.ignore, ignore_msgs, cfg.tolerance), log_msgs From 7a6f57a28e6efda72319fc0b2a4873bcf7e06829 Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Tue, 14 Jun 2022 15:46:03 -0700 Subject: [PATCH 043/302] remove weights fixup with new SNPE (#24254) * remove weights fixup with new SNPE * Update ref Co-authored-by: Comma Device Co-authored-by: Harald Schafer --- selfdrive/modeld/SConscript | 12 ++---------- .../test/process_replay/model_replay_ref_commit | 2 +- 2 files changed, 3 insertions(+), 11 deletions(-) diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index 1f1c661c8b..3e9738d864 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -65,22 +65,14 @@ common_model = lenv.Object(common_src) if use_thneed and arch == "larch64": fn = File("models/supercombo").abspath compiler = lenv.Program('thneed/compile', ["thneed/compile.cc"]+common_model, LIBS=libs) - cmd = f"cd {Dir('.').abspath} && {compiler[0].abspath} --in {fn}.dlc --out {fn}_badweights.thneed --binary --optimize" + cmd = f"cd {Dir('.').abspath} && {compiler[0].abspath} --in {fn}.dlc --out {fn}.thneed --binary --optimize" lib_paths = ':'.join(Dir(p).abspath for p in lenv["LIBPATH"]) kernel_path = os.path.join(Dir('.').abspath, "thneed", "kernels") cenv = Environment(ENV={'LD_LIBRARY_PATH': f"{lib_paths}:{lenv['ENV']['LD_LIBRARY_PATH']}", 'KERNEL_PATH': kernel_path}) kernels = [os.path.join(kernel_path, x) for x in os.listdir(kernel_path) if x.endswith(".cl")] - cenv.Command(fn + "_badweights.thneed", [fn + ".dlc", kernels, compiler], cmd) - - from selfdrive.modeld.thneed.weights_fixup import weights_fixup - def weights_fixup_action(target, source, env): - weights_fixup(target[0].abspath, source[0].abspath, source[1].abspath) - - env = Environment(BUILDERS = {'WeightFixup' : Builder(action = weights_fixup_action)}) - env.WeightFixup(target=fn + ".thneed", source=[fn+"_badweights.thneed", fn+".dlc"]) - + cenv.Command(fn + ".thneed", [fn + ".dlc", kernels, compiler], cmd) lenv.Program('_dmonitoringmodeld', [ "dmonitoringmodeld.cc", diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 90520f2619..a7a909d2a4 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -f74ab97371be93fdc28333e5ea12bbb78c3a32d0 +512a9d4596c8faba304d6f7ded2ce77837357b65 From f8f4337fb3c50d6c125f59a8f59c93818fe71994 Mon Sep 17 00:00:00 2001 From: Jason Shuler Date: Tue, 14 Jun 2022 20:28:15 -0400 Subject: [PATCH 044/302] GM: add support for vehicles with manual parking brakes (#24766) Switch to general park brake signal --- selfdrive/car/gm/carstate.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index e6a1c08dda..48b9f25444 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -64,7 +64,7 @@ class CarState(CarStateBase): ret.leftBlinker = pt_cp.vl["BCMTurnSignals"]["TurnSignals"] == 1 ret.rightBlinker = pt_cp.vl["BCMTurnSignals"]["TurnSignals"] == 2 - ret.parkingBrake = pt_cp.vl["EPBStatus"]["EPBClosed"] == 1 + ret.parkingBrake = pt_cp.vl["VehicleIgnitionAlt"]["ParkBrake"] == 1 ret.cruiseState.available = pt_cp.vl["ECMEngineStatus"]["CruiseMainOn"] != 0 ret.espDisabled = pt_cp.vl["ESPStatus"]["TractionControlOn"] != 1 ret.accFaulted = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.FAULTED @@ -100,7 +100,7 @@ class CarState(CarStateBase): ("LKATorqueDelivered", "PSCMStatus"), ("LKATorqueDeliveredStatus", "PSCMStatus"), ("TractionControlOn", "ESPStatus"), - ("EPBClosed", "EPBStatus"), + ("ParkBrake", "VehicleIgnitionAlt"), ("CruiseMainOn", "ECMEngineStatus"), ] @@ -110,7 +110,7 @@ class CarState(CarStateBase): ("PSCMStatus", 10), ("ESPStatus", 10), ("BCMDoorBeltStatus", 10), - ("EPBStatus", 20), + ("VehicleIgnitionAlt", 10), ("EBCMWheelSpdFront", 20), ("EBCMWheelSpdRear", 20), ("AcceleratorPedal2", 33), From 6757e235f92b72741f2f4375548fde883ede324d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 14 Jun 2022 20:38:25 -0700 Subject: [PATCH 045/302] little zookeeper fixes (#24861) * little zookeeper fixes * bump that up --- Pipfile | 1 + Pipfile.lock | 135 ++++++++++++++++++------------- tools/zookeeper/__init__.py | 7 +- tools/zookeeper/power_monitor.py | 28 +++---- tools/zookeeper/requirements.txt | 1 - 5 files changed, 98 insertions(+), 74 deletions(-) mode change 100755 => 100644 tools/zookeeper/__init__.py delete mode 100644 tools/zookeeper/requirements.txt diff --git a/Pipfile b/Pipfile index 672692fe40..b8545b1a21 100644 --- a/Pipfile +++ b/Pipfile @@ -40,6 +40,7 @@ subprocess32 = "*" tenacity = "*" mpld3 = "*" carla = {version = "==0.9.13", markers="platform_system != 'Darwin'"} +ft4222 = "*" [packages] atomicwrites = "*" diff --git a/Pipfile.lock b/Pipfile.lock index ee0fbc7e84..cc347a60f4 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "7af354a7ae976b12da1b5f15f0cebdc77595199c11b0bfeb8be9c2827f335c48" + "sha256": "d2629168f477b3a14f68f26e3b63ea9797b20599c066b2aa23a027bcee2ca40a" }, "pipfile-spec": 6, "requires": { @@ -146,7 +146,7 @@ "sha256:2857e29ff0d34db842cd7ca3230549d1a697f96ee6d3fb071cfa6c7393832597", "sha256:6881edbebdb17b39b4eaaa821b438bf6eddffb4468cf344f09f89def34a8b1df" ], - "markers": "python_version >= '3.5'", + "markers": "python_full_version >= '3.5.0'", "version": "==2.0.12" }, "click": { @@ -347,7 +347,7 @@ "sha256:84d9dd047ffa80596e0f246e2eab0b391788b0503584e8945f2368256d2735ff", "sha256:9d643ff0a55b762d5cdb124b8eaa99c66322e2157b69160bc32796e824360e6d" ], - "markers": "python_version >= '3.5'", + "markers": "python_full_version >= '3.5.0'", "version": "==3.3" }, "importlib-metadata": { @@ -1246,7 +1246,7 @@ "sha256:6657594ee297170d19f67d55c05852a874e7eb634f4f753dbd667855e07c1708", "sha256:f1c24655a0da0d1b67f07e17a5e6b2a105894e6824b92096378bb3668ef02376" ], - "markers": "python_version >= '3.7'", + "markers": "python_version < '3.10'", "version": "==4.2.0" }, "urllib3": { @@ -1443,11 +1443,11 @@ }, "babel": { "hashes": [ - "sha256:3f349e85ad3154559ac4930c3918247d319f21910d5ce4b25d439ed8693b98d2", - "sha256:98aeaca086133efb3e1e2aad0396987490c8425929ddbcfe0550184fdc54cd13" + "sha256:7aed055f0c04c9e7f51a2f75261e41e1c804efa724cb65b60a970dd4448d469d", + "sha256:81a3beca4d0cd40a9cfb9e2adb2cf39261c2f959b92e7a74750befe5d79afd7b" ], "markers": "python_version >= '3.6'", - "version": "==2.10.1" + "version": "==2.10.2" }, "bcrypt": { "hashes": [ @@ -1565,7 +1565,7 @@ "sha256:2857e29ff0d34db842cd7ca3230549d1a697f96ee6d3fb071cfa6c7393832597", "sha256:6881edbebdb17b39b4eaaa821b438bf6eddffb4468cf344f09f89def34a8b1df" ], - "markers": "python_version >= '3.5'", + "markers": "python_full_version >= '3.5.0'", "version": "==2.0.12" }, "control": { @@ -1748,6 +1748,33 @@ "markers": "python_version >= '3.7'", "version": "==4.33.3" }, + "ft4222": { + "hashes": [ + "sha256:1489b08e4042cb2b24894495c1c8514fa115122e9f8a739f665f0e4d8c53d3f4", + "sha256:1c71913f9fb862634fb77eb6efeea38b2b839e09f739aee5864b9549bcf1c4a9", + "sha256:1f9be0961bd7f3e0c1729c9692f602244e93898610611602ce1fa16059ac5bfa", + "sha256:208cde748fc2bf4a753e217ee2844e75d7d1b6d370a8937a2055f9de8906f933", + "sha256:372be3d7d04c0f6dfa62ff66b3d4be5c39d57c258ab562d9eb0d7cdd3a90ed0f", + "sha256:3ebf9380315c6af8f9f3bc5c5c7a5ae06498349c14a7b2e65d5067b20462d21b", + "sha256:422740efac86f3fdd971bb9a94d9974e56cfe062284a2be1a85db96dd0e77e5e", + "sha256:4414ef82a6321c5205ab0e3dab2bf072f14b4dd3262e5f392560adf107210d41", + "sha256:459894dcca7db71a0d58e6f3abb4c9dd67654c92ad9d934f1e32dc08bed87645", + "sha256:4b7e4c8b5e4a8fe769127d3db99b7b410468ffe2718a07f7b317e7dc1ad9ca4f", + "sha256:68e6b357ea2287fe0e8dac287efbac2f0ce9632d65e828d422d3a0604555c174", + "sha256:800a26a4a8fc854f41e4de41e45b6deafdeb78ae5eff48818f710bb2d94a8c11", + "sha256:8790e96b4c3f8d1fb768f689f1c437a59b20889e4726ed7457ff3d188f0a3274", + "sha256:9369b55393b2e1f58f8b8516bcf9cd6fd34c05e77377c4cc48be39a49cad7be5", + "sha256:a6236f05b8948cd9c113c7159e3fdde202a0f73dce6440da078fd2fc9e411123", + "sha256:b7f58cd16213a5c92503c530b301f071d67283c80c1e8cb43d6f3ec5c186df35", + "sha256:cc368b06b92529a11add37d14196d2e2aaae19c6ffc51b9457513a0d05ceae1a", + "sha256:d479c037b417ff289727112f1d4725563b78448d3765f457c8bf6884e4d83abd", + "sha256:dce00d513be811f738954c5593c52b533a02331e8a26983280dea3f4d864962f", + "sha256:eadcbc1dd20ed6d7d07dc53354ea137bcea30fb0889d74bedcd189cdb4f61c84", + "sha256:ec984bd7e9300e5f2e50823dcd5874d54aa3e7503e69afe7eb3b4cea77071084" + ], + "index": "pypi", + "version": "==1.4.1" + }, "hexdump": { "hashes": [ "sha256:d781a43b0c16ace3f9366aade73e8ad3a7bd5137d58f0b45ab2d3f54876f20db" @@ -1778,7 +1805,7 @@ "sha256:84d9dd047ffa80596e0f246e2eab0b391788b0503584e8945f2368256d2735ff", "sha256:9d643ff0a55b762d5cdb124b8eaa99c66322e2157b69160bc32796e824360e6d" ], - "markers": "python_version >= '3.5'", + "markers": "python_full_version >= '3.5.0'", "version": "==3.3" }, "imagesize": { @@ -1822,52 +1849,52 @@ }, "kiwisolver": { "hashes": [ - "sha256:0b7f50a1a25361da3440f07c58cd1d79957c2244209e4f166990e770256b6b0b", - "sha256:0c380bb5ae20d829c1a5473cfcae64267b73aaa4060adc091f6df1743784aae0", - "sha256:0d98dca86f77b851350c250f0149aa5852b36572514d20feeadd3c6b1efe38d0", - "sha256:0e45e780a74416ef2f173189ef4387e44b5494f45e290bcb1f03735faa6779bf", - "sha256:0e8afdf533b613122e4bbaf3c1e42c2a5e9e2d1dd3a0a017749a7658757cb377", - "sha256:1008346a7741620ab9cc6c96e8ad9b46f7a74ce839dbb8805ddf6b119d5fc6c2", - "sha256:1d1078ba770d6165abed3d9a1be1f9e79b61515de1dd00d942fa53bba79f01ae", - "sha256:1dcade8f6fe12a2bb4efe2cbe22116556e3b6899728d3b2a0d3b367db323eacc", - "sha256:240009fdf4fa87844f805e23f48995537a8cb8f8c361e35fda6b5ac97fcb906f", - "sha256:240c2d51d098395c012ddbcb9bd7b3ba5de412a1d11840698859f51d0e643c4f", - "sha256:262c248c60f22c2b547683ad521e8a3db5909c71f679b93876921549107a0c24", - "sha256:2e6cda72db409eefad6b021e8a4f964965a629f577812afc7860c69df7bdb84a", - "sha256:3c032c41ae4c3a321b43a3650e6ecc7406b99ff3e5279f24c9b310f41bc98479", - "sha256:42f6ef9b640deb6f7d438e0a371aedd8bef6ddfde30683491b2e6f568b4e884e", - "sha256:484f2a5f0307bc944bc79db235f41048bae4106ffa764168a068d88b644b305d", - "sha256:69b2d6c12f2ad5f55104a36a356192cfb680c049fe5e7c1f6620fc37f119cdc2", - "sha256:6e395ece147f0692ca7cdb05a028d31b83b72c369f7b4a2c1798f4b96af1e3d8", - "sha256:6ece2e12e4b57bc5646b354f436416cd2a6f090c1dadcd92b0ca4542190d7190", - "sha256:71469b5845b9876b8d3d252e201bef6f47bf7456804d2fbe9a1d6e19e78a1e65", - "sha256:7f606d91b8a8816be476513a77fd30abe66227039bd6f8b406c348cb0247dcc9", - "sha256:7f88c4b8e449908eeddb3bbd4242bd4dc2c7a15a7aa44bb33df893203f02dc2d", - "sha256:81237957b15469ea9151ec8ca08ce05656090ffabc476a752ef5ad7e2644c526", - "sha256:89b57c2984f4464840e4b768affeff6b6809c6150d1166938ade3e22fbe22db8", - "sha256:8a830a03970c462d1a2311c90e05679da56d3bd8e78a4ba9985cb78ef7836c9f", - "sha256:8ae5a071185f1a93777c79a9a1e67ac46544d4607f18d07131eece08d415083a", - "sha256:8b6086aa6936865962b2cee0e7aaecf01ab6778ce099288354a7229b4d9f1408", - "sha256:8ec2e55bf31b43aabe32089125dca3b46fdfe9f50afbf0756ae11e14c97b80ca", - "sha256:8ff3033e43e7ca1389ee59fb7ecb8303abb8713c008a1da49b00869e92e3dd7c", - "sha256:91eb4916271655dfe3a952249cb37a5c00b6ba68b4417ee15af9ba549b5ba61d", - "sha256:9d2bb56309fb75a811d81ed55fbe2208aa77a3a09ff5f546ca95e7bb5fac6eff", - "sha256:a4e8f072db1d6fb7a7cc05a6dbef8442c93001f4bb604f1081d8c2db3ca97159", - "sha256:b1605c7c38cc6a85212dfd6a641f3905a33412e49f7c003f35f9ac6d71f67720", - "sha256:b3e251e5c38ac623c5d786adb21477f018712f8c6fa54781bd38aa1c60b60fc2", - "sha256:b978afdb913ca953cf128d57181da2e8798e8b6153be866ae2a9c446c6162f40", - "sha256:be9a650890fb60393e60aacb65878c4a38bb334720aa5ecb1c13d0dac54dd73b", - "sha256:c222f91a45da9e01a9bc4f760727ae49050f8e8345c4ff6525495f7a164c8973", - "sha256:c839bf28e45d7ddad4ae8f986928dbf5a6d42ff79760d54ec8ada8fb263e097c", - "sha256:cbb5eb4a2ea1ffec26268d49766cafa8f957fe5c1b41ad00733763fae77f9436", - "sha256:e348f1904a4fab4153407f7ccc27e43b2a139752e8acf12e6640ba683093dd96", - "sha256:e677cc3626287f343de751e11b1e8a5b915a6ac897e8aecdbc996cd34de753a0", - "sha256:f74f2a13af201559e3d32b9ddfc303c94ae63d63d7f4326d06ce6fe67e7a8255", - "sha256:fa4d97d7d2b2c082e67907c0b8d9f31b85aa5d3ba0d33096b7116f03f8061261", - "sha256:ffbdb9a96c536f0405895b5e21ee39ec579cb0ed97bdbd169ae2b55f41d73219" + "sha256:007799c7fa934646318fc128b033bb6e6baabe7fbad521bfb2279aac26225cd7", + "sha256:130c6c35eded399d3967cf8a542c20b671f5ba85bd6f210f8b939f868360e9eb", + "sha256:1858ad3cb686eccc7c6b7c5eac846a1cfd45aacb5811b2cf575e80b208f5622a", + "sha256:1ae7aa0784aeadfbd693c27993727792fbe1455b84d49970bad5886b42976b18", + "sha256:1d2c744aeedce22c122bb42d176b4aa6d063202a05a4abdacb3e413c214b3694", + "sha256:21a3a98f0a21fc602663ca9bce2b12a4114891bdeba2dea1e9ad84db59892fca", + "sha256:22ccba48abae827a0f952a78a7b1a7ff01866131e5bbe1f826ce9bda406bf051", + "sha256:26b5a70bdab09e6a2f40babc4f8f992e3771751e144bda1938084c70d3001c09", + "sha256:2d76780d9c65c7529cedd49fa4802d713e60798d8dc3b0d5b12a0a8f38cca51c", + "sha256:325fa1b15098e44fe4590a6c5c09a212ca10c6ebb5d96f7447d675f6c8340e4e", + "sha256:3a297d77b3d6979693f5948df02b89431ae3645ec95865e351fb45578031bdae", + "sha256:3b1dcbc49923ac3c973184a82832e1f018dec643b1e054867d04a3a22255ec6a", + "sha256:40240da438c0ebfe2aa76dd04b844effac6679423df61adbe3437d32f23468d9", + "sha256:46c6e5018ba31d5ee7582f323d8661498a154dea1117486a571db4c244531f24", + "sha256:46fb56fde006b7ef5f8eaa3698299b0ea47444238b869ff3ced1426aa9fedcb5", + "sha256:4dc350cb65fe4e3f737d50f0465fa6ea0dcae0e5722b7edf5d5b0a0e3cd2c3c7", + "sha256:51078855a16b7a4984ed2067b54e35803d18bca9861cb60c60f6234b50869a56", + "sha256:547111ef7cf13d73546c2de97ce434935626c897bdec96a578ca100b5fcd694b", + "sha256:5fb73cc8a34baba1dfa546ae83b9c248ef6150c238b06fc53d2773685b67ec67", + "sha256:654280c5f41831ddcc5a331c0e3ce2e480bbc3d7c93c18ecf6236313aae2d61a", + "sha256:6b3136eecf7e1b4a4d23e4b19d6c4e7a8e0b42d55f30444e3c529700cdacaa0d", + "sha256:7118ca592d25b2957ff7b662bc0fe4f4c2b5d5b27814b9b1bc9f2fb249a970e7", + "sha256:71af5b43e4fa286a35110fc5bb740fdeae2b36ca79fbcf0a54237485baeee8be", + "sha256:747190fcdadc377263223f8f72b038381b3b549a8a3df5baf4d067da4749b046", + "sha256:8395064d63b26947fa2c9faeea9c3eee35e52148c5339c37987e1d96fbf009b3", + "sha256:84f85adfebd7d3c3db649efdf73659e1677a2cf3fa6e2556a3f373578af14bf7", + "sha256:86bcf0009f2012847a688f2f4f9b16203ca4c835979a02549aa0595d9f457cc8", + "sha256:ab8a15c2750ae8d53e31f77a94f846d0a00772240f1c12817411fa2344351f86", + "sha256:af24b21c2283ca69c416a8a42cde9764dc36c63d3389645d28c69b0e93db3cd7", + "sha256:afe173ac2646c2636305ab820cc0380b22a00a7bca4290452e7166b4f4fa49d0", + "sha256:b9eb88593159a53a5ee0b0159daee531ff7dd9c87fa78f5d807ca059c7eb1b2b", + "sha256:c16635f8dddbeb1b827977d0b00d07b644b040aeb9ff8607a9fc0997afa3e567", + "sha256:ca3eefb02ef17257fae8b8555c85e7c1efdfd777f671384b0e4ef27409b02720", + "sha256:caa59e2cae0e23b1e225447d7a9ddb0f982f42a6a22d497a484dfe62a06f7c0e", + "sha256:cb55258931448d61e2d50187de4ee66fc9d9f34908b524949b8b2b93d0c57136", + "sha256:d248c46c0aa406695bda2abf99632db991f8b3a6d46018721a2892312a99f069", + "sha256:d2578e5149ff49878934debfacf5c743fab49eca5ecdb983d0b218e1e554c498", + "sha256:dd22085446f3eca990d12a0878eeb5199dc9553b2e71716bfe7bed9915a472ab", + "sha256:e7cf940af5fee00a92e281eb157abe8770227a5255207818ea9a34e54a29f5b2", + "sha256:f70f3d028794e31cf9d1a822914efc935aadb2438ec4e8d4871d95eb1ce032d6", + "sha256:fd2842a0faed9ab9aba0922c951906132d9384be89690570f0ed18cd4f20e658", + "sha256:fd628e63ffdba0112e3ddf1b1e9f3db29dd8262345138e08f4938acbc6d0805a", + "sha256:ffd7cf165ff71afb202b3f36daafbf298932bee325aac9f58e1c9cd55838bef0" ], "markers": "python_version >= '3.7'", - "version": "==1.4.2" + "version": "==1.4.3" }, "lru-dict": { "hashes": [ @@ -2572,7 +2599,7 @@ "sha256:6657594ee297170d19f67d55c05852a874e7eb634f4f753dbd667855e07c1708", "sha256:f1c24655a0da0d1b67f07e17a5e6b2a105894e6824b92096378bb3668ef02376" ], - "markers": "python_version >= '3.7'", + "markers": "python_version < '3.10'", "version": "==4.2.0" }, "urllib3": { diff --git a/tools/zookeeper/__init__.py b/tools/zookeeper/__init__.py old mode 100755 new mode 100644 index cd64d3a1fb..42438cb209 --- a/tools/zookeeper/__init__.py +++ b/tools/zookeeper/__init__.py @@ -1,9 +1,6 @@ #!/usr/bin/env python3 - -# Python library to control Zookeeper - -import ft4222 # pylint: disable=import-error -import ft4222.I2CMaster # pylint: disable=import-error +import ft4222 +import ft4222.I2CMaster DEBUG = False diff --git a/tools/zookeeper/power_monitor.py b/tools/zookeeper/power_monitor.py index f2796bad31..d3bdd6679f 100755 --- a/tools/zookeeper/power_monitor.py +++ b/tools/zookeeper/power_monitor.py @@ -1,30 +1,30 @@ -#!/usr/bin/env python - +#!/usr/bin/env python3 import sys import time -from tools.zookeeper import Zookeeper -# Usage: check_consumption.py -# Exit code: 0 -> passed -# 1 -> failed +from common.realtime import Ratekeeper +from common.filter_simple import FirstOrderFilter +from tools.zookeeper import Zookeeper if __name__ == "__main__": z = Zookeeper() + z.set_device_power(True) + z.set_device_ignition(False) duration = None if len(sys.argv) > 1: duration = int(sys.argv[1]) + rate = 123 + rk = Ratekeeper(rate, print_delay_threshold=None) + fltr = FirstOrderFilter(0, 5, 1. / rate, initialized=False) + try: start_time = time.monotonic() - measurements = [] while duration is None or time.monotonic() - start_time < duration: - p = z.read_power() - print(round(p, 3), "W") - measurements.append(p) - time.sleep(0.25) + fltr.update(z.read_power()) + if rk.frame % rate == 0: + print(f"{fltr.x:.2f} W") + rk.keep_time() except KeyboardInterrupt: pass - finally: - average_power = sum(measurements)/len(measurements) - print(f"Average power: {round(average_power, 4)}W") diff --git a/tools/zookeeper/requirements.txt b/tools/zookeeper/requirements.txt deleted file mode 100644 index 6f70576caf..0000000000 --- a/tools/zookeeper/requirements.txt +++ /dev/null @@ -1 +0,0 @@ -ft4222==1.2.1 \ No newline at end of file From 0d0f5926a006ead1709b78fe69c1186b5a607c66 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 14 Jun 2022 21:12:49 -0700 Subject: [PATCH 046/302] bump up modeld power draw threshold --- system/hardware/tici/test_power_draw.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/hardware/tici/test_power_draw.py b/system/hardware/tici/test_power_draw.py index 31b8471328..b6b5c735fa 100755 --- a/system/hardware/tici/test_power_draw.py +++ b/system/hardware/tici/test_power_draw.py @@ -20,7 +20,7 @@ class Proc: PROCS = [ Proc('camerad', 2.15), - Proc('modeld', 1.0), + Proc('modeld', 1.0, atol=0.15), Proc('dmonitoringmodeld', 0.25), Proc('encoderd', 0.23), ] From a6652a539d8d4ba614b216900c472cc9e2e58a05 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Tue, 14 Jun 2022 22:29:08 -0700 Subject: [PATCH 047/302] Torque control: low speed boost (#24859) * Make very low speed more aggressive * Less extreme low speed boost * Update ref --- selfdrive/controls/lib/latcontrol_torque.py | 11 ++++++----- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index 12714082a6..f72ffc4b88 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -19,8 +19,7 @@ from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY # move it at all, this is compensated for too. -LOW_SPEED_FACTOR = 200 -JERK_THRESHOLD = 0.2 +FRICTION_THRESHOLD = 0.2 def set_torque_tune(tune, MAX_LAT_ACCEL=2.5, FRICTION=0.01, steering_angle_deadzone_deg=0.0): @@ -66,14 +65,16 @@ class LatControlTorque(LatControl): actual_lateral_accel = actual_curvature * CS.vEgo ** 2 lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2 - setpoint = desired_lateral_accel + LOW_SPEED_FACTOR * desired_curvature - measurement = actual_lateral_accel + LOW_SPEED_FACTOR * actual_curvature + + low_speed_factor = interp(CS.vEgo, [0, 15], [500, 0]) + setpoint = desired_lateral_accel + low_speed_factor * desired_curvature + measurement = actual_lateral_accel + low_speed_factor * actual_curvature error = apply_deadzone(setpoint - measurement, lateral_accel_deadzone) pid_log.error = error ff = desired_lateral_accel - params.roll * ACCELERATION_DUE_TO_GRAVITY # convert friction into lateral accel units for feedforward - friction_compensation = interp(error, [-JERK_THRESHOLD, JERK_THRESHOLD], [-self.friction, self.friction]) + friction_compensation = interp(error, [-FRICTION_THRESHOLD, FRICTION_THRESHOLD], [-self.friction, self.friction]) ff += friction_compensation / self.kf freeze_integrator = CS.steeringRateLimited or CS.steeringPressed or CS.vEgo < 5 output_torque = self.pid.update(error, diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 61bbd5cdd1..b8976e5f38 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -fe2da24194e3def1823681cc18e7879f24edfc6e +1d66eed104dbc124c4e5679f5dddf40197b86ce9 From b86ef0b70e81ef4e895d5102feb231dc3d43265f Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 14 Jun 2022 23:30:35 -0700 Subject: [PATCH 048/302] regen & process replay: support no disengage on accelerator (#24850) * ACC on if enabled != 0 * small regen clean up and add HONDA3 * fixes * revert unneeded changes * not used * just alt exp Co-authored-by: redacid95 --- selfdrive/test/process_replay/process_replay.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 363035ab22..b016eb1c9f 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -14,6 +14,7 @@ from cereal import car, log from cereal.services import service_list from common.params import Params from common.timeout import Timeout +from panda.python import ALTERNATIVE_EXPERIENCE from selfdrive.car.fingerprints import FW_VERSIONS from selfdrive.car.car_helpers import get_car, interfaces from selfdrive.test.process_replay.helpers import OpenpilotPrefix @@ -368,6 +369,9 @@ def setup_env(simulation=False, CP=None): # Regen or python process if CP is not None: + if CP.alternativeExperience == ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS: + params.put_bool("DisengageOnAccelerator", False) + if CP.fingerprintSource == "fw" and CP.carFingerprint in FW_VERSIONS: params.put("CarParamsCache", CP.as_builder().to_bytes()) else: From c3fa9151f39994984b60a19cdd7425dba73ec2fc Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Wed, 15 Jun 2022 11:32:07 +0200 Subject: [PATCH 049/302] Laikad: Cache orbit and nav data (#24831) * Cache orbit and nav data * Cleanup * Cleanup * Use ProcessPoolExecutor to fetch orbits * update laika repo * Minor * Create json de/serializers Save cache only 1 minute at max * Update laika repo * Speed up json by caching json in ephemeris class * Update laika * Fix test * Use constant --- common/params.cc | 1 + laika_repo | 2 +- selfdrive/locationd/laikad.py | 64 +++++++++++++++++++++--- selfdrive/locationd/test/test_laikad.py | 66 ++++++++++++++++++++++--- 4 files changed, 118 insertions(+), 15 deletions(-) diff --git a/common/params.cc b/common/params.cc index b740e5a71e..8cf1baa6c8 100644 --- a/common/params.cc +++ b/common/params.cc @@ -127,6 +127,7 @@ std::unordered_map keys = { {"IsTakingSnapshot", CLEAR_ON_MANAGER_START}, {"IsUpdateAvailable", CLEAR_ON_MANAGER_START}, {"JoystickDebugMode", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF}, + {"LaikadEphemeris", PERSISTENT}, {"LastAthenaPingTime", CLEAR_ON_MANAGER_START}, {"LastGPSPosition", PERSISTENT}, {"LastManagerExitReason", CLEAR_ON_MANAGER_START}, diff --git a/laika_repo b/laika_repo index 36f2621fc5..a3a80dc4f7 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 36f2621fc5348487bb2cd606c37c8c15de0e32cd +Subproject commit a3a80dc4f7977b2232946e56a16770e413190818 diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 33e41398a0..ddd57bdca9 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +import json import time from concurrent.futures import Future, ProcessPoolExecutor from typing import List, Optional @@ -9,9 +10,10 @@ from collections import defaultdict from numpy.linalg import linalg from cereal import log, messaging +from common.params import Params, put_nonblocking from laika import AstroDog from laika.constants import SECS_IN_HR, SECS_IN_MIN -from laika.ephemeris import EphemerisType, convert_ublox_ephem +from laika.ephemeris import Ephemeris, EphemerisType, convert_ublox_ephem from laika.gps_time import GPSTime from laika.helpers import ConstellationId from laika.raw_gnss import GNSSMeasurement, calc_pos_fix, correct_measurements, process_measurements, read_raw_ublox @@ -22,16 +24,40 @@ import common.transformations.coordinates as coord from system.swaglog import cloudlog MAX_TIME_GAP = 10 +EPHEMERIS_CACHE = 'LaikadEphemeris' +CACHE_VERSION = 0.1 class Laikad: - - def __init__(self, valid_const=("GPS", "GLONASS"), auto_update=False, valid_ephem_types=(EphemerisType.ULTRA_RAPID_ORBIT, EphemerisType.NAV)): - self.astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types) + def __init__(self, valid_const=("GPS", "GLONASS"), auto_update=False, valid_ephem_types=(EphemerisType.ULTRA_RAPID_ORBIT, EphemerisType.NAV), + save_ephemeris=False): + self.astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types, clear_old_ephemeris=True) self.gnss_kf = GNSSKalman(GENERATED_DIR) self.orbit_fetch_executor = ProcessPoolExecutor() self.orbit_fetch_future: Optional[Future] = None self.last_fetch_orbits_t = None + self.last_cached_t = None + self.save_ephemeris = save_ephemeris + self.load_cache() + + def load_cache(self): + cache = Params().get(EPHEMERIS_CACHE) + if not cache: + return + try: + cache = json.loads(cache, object_hook=deserialize_hook) + self.astro_dog.add_orbits(cache['orbits']) + self.astro_dog.add_navs(cache['nav']) + self.last_fetch_orbits_t = cache['last_fetch_orbits_t'] + except json.decoder.JSONDecodeError: + cloudlog.exception("Error parsing cache") + + def cache_ephemeris(self, t: GPSTime): + if self.save_ephemeris and (self.last_cached_t is None or t - self.last_cached_t > SECS_IN_MIN): + put_nonblocking(EPHEMERIS_CACHE, json.dumps( + {'version': CACHE_VERSION, 'last_fetch_orbits_t': self.last_fetch_orbits_t, 'orbits': self.astro_dog.orbits, 'nav': self.astro_dog.nav}, + cls=CacheSerializer)) + self.last_cached_t = t def process_ublox_msg(self, ublox_msg, ublox_mono_time: int, block=False): if ublox_msg.which == 'measurementReport': @@ -83,7 +109,8 @@ class Laikad: return dat elif ublox_msg.which == 'ephemeris': ephem = convert_ublox_ephem(ublox_msg.ephemeris) - self.astro_dog.add_navs([ephem]) + self.astro_dog.add_navs({ephem.prn: [ephem]}) + self.cache_ephemeris(t=ephem.epoch) # elif ublox_msg.which == 'ionoData': # todo add this. Needed to better correct messages offline. First fix ublox_msg.cc to sent them. @@ -101,7 +128,7 @@ class Laikad: cloudlog.error("Gnss kalman std too far") if len(pos_fix) == 0: - cloudlog.warning("Position fix not available when resetting kalman filter") + cloudlog.info("Position fix not available when resetting kalman filter") return post_est = pos_fix[0][:3].tolist() self.init_gnss_localizer(post_est) @@ -134,10 +161,11 @@ class Laikad: self.orbit_fetch_future.result() if self.orbit_fetch_future.done(): ret = self.orbit_fetch_future.result() + self.last_fetch_orbits_t = t if ret: self.astro_dog.orbits, self.astro_dog.orbit_fetched_times = ret + self.cache_ephemeris(t=t) self.orbit_fetch_future = None - self.last_fetch_orbits_t = t def get_orbit_data(t: GPSTime, valid_const, auto_update, valid_ephem_types): @@ -193,11 +221,31 @@ def get_bearing_from_gnss(ecef_pos, ecef_vel, vel_std): return float(np.rad2deg(bearing)), float(bearing_std) +class CacheSerializer(json.JSONEncoder): + + def default(self, o): + if isinstance(o, Ephemeris): + return o.to_json() + if isinstance(o, GPSTime): + return o.__dict__ + if isinstance(o, np.ndarray): + return o.tolist() + return json.JSONEncoder.default(self, o) + + +def deserialize_hook(dct): + if 'ephemeris' in dct: + return Ephemeris.from_json(dct) + if 'week' in dct: + return GPSTime(dct['week'], dct['tow']) + return dct + + def main(): sm = messaging.SubMaster(['ubloxGnss']) pm = messaging.PubMaster(['gnssMeasurements']) - laikad = Laikad() + laikad = Laikad(save_ephemeris=True) while True: sm.update() diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py index 7dc803d799..01ea8fee27 100755 --- a/selfdrive/locationd/test/test_laikad.py +++ b/selfdrive/locationd/test/test_laikad.py @@ -1,14 +1,16 @@ #!/usr/bin/env python3 +import time import unittest from datetime import datetime from unittest import mock -from unittest.mock import Mock +from unittest.mock import Mock, patch +from common.params import Params from laika.ephemeris import EphemerisType from laika.gps_time import GPSTime -from laika.helpers import ConstellationId +from laika.helpers import ConstellationId, TimeRangeHolder from laika.raw_gnss import GNSSMeasurement, read_raw_ublox -from selfdrive.locationd.laikad import Laikad, create_measurement_msg +from selfdrive.locationd.laikad import EPHEMERIS_CACHE, Laikad, create_measurement_msg from selfdrive.test.openpilotci import get_url from tools.lib.logreader import LogReader @@ -20,12 +22,14 @@ def get_log(segs=range(0)): return [m for m in logs if m.which() == 'ubloxGnss'] -def verify_messages(lr, laikad): +def verify_messages(lr, laikad, return_one_success=False): good_msgs = [] for m in lr: msg = laikad.process_ublox_msg(m.ubloxGnss, m.logMonoTime, block=True) if msg is not None and len(msg.gnssMeasurements.correctedMeasurements) > 0: good_msgs.append(msg) + if return_one_success: + return msg return good_msgs @@ -35,6 +39,9 @@ class TestLaikad(unittest.TestCase): def setUpClass(cls): cls.logs = get_log(range(1)) + def setUp(self): + Params().delete(EPHEMERIS_CACHE) + def test_create_msg_without_errors(self): gpstime = GPSTime.from_datetime(datetime.now()) meas = GNSSMeasurement(ConstellationId.GPS, 1, gpstime.week, gpstime.tow, {'C1C': 0., 'D1C': 0.}, {'C1C': 0., 'D1C': 0.}) @@ -81,8 +88,7 @@ class TestLaikad(unittest.TestCase): first_gps_time = self.get_first_gps_time() # Pretend process has loaded the orbits on startup by using the time of the first gps message. laikad.fetch_orbits(first_gps_time, block=True) - self.assertEqual(29, len(laikad.astro_dog.orbits.values())) - self.assertGreater(min([len(v) for v in laikad.astro_dog.orbits.values()]), 0) + self.dict_has_values(laikad.astro_dog.orbits) @unittest.skip("Use to debug live data") def test_laika_get_orbits_now(self): @@ -109,6 +115,54 @@ class TestLaikad(unittest.TestCase): self.assertGreater(len(laikad.astro_dog.orbit_fetched_times._ranges), 0) self.assertEqual(None, laikad.orbit_fetch_future) + def test_cache(self): + laikad = Laikad(auto_update=True, save_ephemeris=True) + first_gps_time = self.get_first_gps_time() + + def wait_for_cache(): + max_time = 2 + while Params().get(EPHEMERIS_CACHE) is None: + time.sleep(0.1) + max_time -= 0.1 + if max_time == 0: + self.fail("Cache has not been written after 2 seconds") + # Test cache with no ephemeris + laikad.cache_ephemeris(t=GPSTime(0, 0)) + wait_for_cache() + Params().delete(EPHEMERIS_CACHE) + + laikad.astro_dog.get_navs(first_gps_time) + laikad.fetch_orbits(first_gps_time, block=True) + + # Wait for cache to save + wait_for_cache() + + # Check both nav and orbits separate + laikad = Laikad(auto_update=False, valid_ephem_types=EphemerisType.NAV) + # Verify orbits and nav are loaded from cache + self.dict_has_values(laikad.astro_dog.orbits) + self.dict_has_values(laikad.astro_dog.nav) + # Verify cache is working for only nav by running a segment + msg = verify_messages(self.logs, laikad, return_one_success=True) + self.assertIsNotNone(msg) + + with patch('selfdrive.locationd.laikad.get_orbit_data', return_value=None) as mock_method: + # Verify no orbit downloads even if orbit fetch times is reset since the cache has recently been saved and we don't want to download high frequently + laikad.astro_dog.orbit_fetched_times = TimeRangeHolder() + laikad.fetch_orbits(first_gps_time, block=False) + mock_method.assert_not_called() + + # Verify cache is working for only orbits by running a segment + laikad = Laikad(auto_update=False, valid_ephem_types=EphemerisType.ULTRA_RAPID_ORBIT) + msg = verify_messages(self.logs, laikad, return_one_success=True) + self.assertIsNotNone(msg) + # Verify orbit data is not downloaded + mock_method.assert_not_called() + + def dict_has_values(self, dct): + self.assertGreater(len(dct), 0) + self.assertGreater(min([len(v) for v in dct.values()]), 0) + if __name__ == "__main__": unittest.main() From d528cd556848404891e28b3342d146498e3991cc Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 15 Jun 2022 13:06:46 +0200 Subject: [PATCH 050/302] UI: new set speed design, show speed limits (#24736) * basic US design * place based on center position * fix typo * eu sign without rounded box * same as steering wheel icon * proper rounded bottom for eu sign * add border * proper placement/sizes * needs to be semi bold * color changes * only when engaged * move helpers into util.h * Fix MAX placement * only change color when at least 5 over * implement override state * pixel perfect spacing around us sign --- selfdrive/ui/qt/onroad.cc | 162 ++++++++++++++++++++++++++++++++------ selfdrive/ui/qt/onroad.h | 15 +++- selfdrive/ui/qt/util.cc | 61 ++++++++++++++ selfdrive/ui/qt/util.h | 4 + 4 files changed, 216 insertions(+), 26 deletions(-) diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index ce61c094bd..12a579c573 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -174,17 +174,24 @@ void NvgWindow::updateState(const UIState &s) { const SubMaster &sm = *(s.sm); const auto cs = sm["controlsState"].getControlsState(); - float maxspeed = cs.getVCruise(); - bool cruise_set = maxspeed > 0 && (int)maxspeed != SET_SPEED_NA; + float set_speed = cs.getVCruise(); + bool cruise_set = set_speed > 0 && (int)set_speed != SET_SPEED_NA; if (cruise_set && !s.scene.is_metric) { - maxspeed *= KM_TO_MILE; + set_speed *= KM_TO_MILE; } - QString maxspeed_str = cruise_set ? QString::number(std::nearbyint(maxspeed)) : "N/A"; float cur_speed = std::max(0.0, sm["carState"].getCarState().getVEgo() * (s.scene.is_metric ? MS_TO_KPH : MS_TO_MPH)); + auto speed_limit_sign = sm["navInstruction"].getNavInstruction().getSpeedLimitSign(); + float speed_limit = sm["navInstruction"].getValid() ? sm["navInstruction"].getNavInstruction().getSpeedLimit() : 0.0; + speed_limit *= (s.scene.is_metric ? MS_TO_KPH : MS_TO_MPH); + + setProperty("speedLimit", speed_limit); + setProperty("has_us_speed_limit", speed_limit > 1 && speed_limit_sign == cereal::NavInstruction::SpeedLimitSign::MUTCD); + setProperty("has_eu_speed_limit", speed_limit > 1 && speed_limit_sign == cereal::NavInstruction::SpeedLimitSign::VIENNA); + setProperty("is_cruise_set", cruise_set); - setProperty("speed", QString::number(std::nearbyint(cur_speed))); - setProperty("maxSpeed", maxspeed_str); + setProperty("speed", cur_speed); + setProperty("setSpeed", set_speed); setProperty("speedUnit", s.scene.is_metric ? "km/h" : "mph"); setProperty("hideDM", cs.getAlertSize() != cereal::ControlsState::AlertSize::NONE); setProperty("status", s.status); @@ -205,26 +212,139 @@ void NvgWindow::drawHud(QPainter &p) { bg.setColorAt(1, QColor::fromRgbF(0, 0, 0, 0)); p.fillRect(0, 0, width(), header_h, bg); - // max speed - QRect rc(bdr_s * 2, bdr_s * 1.5, 184, 202); - p.setPen(QPen(QColor(0xff, 0xff, 0xff, 100), 10)); - p.setBrush(QColor(0, 0, 0, 100)); - p.drawRoundedRect(rc, 20, 20); - p.setPen(Qt::NoPen); + QString speedLimitStr = QString::number(std::nearbyint(speedLimit)); + QString speedStr = QString::number(std::nearbyint(speed)); + QString setSpeedStr = is_cruise_set ? QString::number(std::nearbyint(setSpeed)) : "–"; + + // Draw outer box + border to contain set speed and speed limit + int default_rect_width = 172; + int rect_width = default_rect_width; + if (has_us_speed_limit && speedLimitStr.size() >= 3) rect_width = 223; + else if (has_eu_speed_limit) rect_width = 200; + + int rect_height = 204; + if (has_us_speed_limit) rect_height = 402; + else if (has_eu_speed_limit) rect_height = 392; - configFont(p, "Open Sans", 48, "Regular"); - drawText(p, rc.center().x(), 118, "MAX", is_cruise_set ? 200 : 100); + int top_radius = 32; + int bottom_radius = has_eu_speed_limit ? 100 : 32; + + QRect set_speed_rect(60 + default_rect_width / 2 - rect_width / 2, 45, rect_width, rect_height); + p.setPen(QPen(QColor(255, 255, 255, 75), 6)); + p.setBrush(QColor(0, 0, 0, 166)); + drawRoundedRect(p, set_speed_rect, top_radius, top_radius, bottom_radius, bottom_radius); + + // Draw set speed if (is_cruise_set) { - configFont(p, "Open Sans", 88, "Bold"); - drawText(p, rc.center().x(), 212, maxSpeed, 255); + if (speedLimit > 0 && status != STATUS_DISENGAGED && status != STATUS_OVERRIDE) { + p.setPen(interpColor( + setSpeed, + {speedLimit + 5, speedLimit + 15, speedLimit + 25}, + {QColor(0xff, 0xff, 0xff, 0xff), QColor(0xff, 0x95, 0x00, 0xff), QColor(0xff, 0x00, 0x00, 0xff)} + )); + } else { + p.setPen(QColor(0xff, 0xff, 0xff, 0xff)); + } } else { - configFont(p, "Open Sans", 80, "SemiBold"); - drawText(p, rc.center().x(), 212, maxSpeed, 100); + p.setPen(QColor(0x72, 0x72, 0x72, 0xff)); + } + configFont(p, "Open Sans", 90, "Bold"); + QRect speed_rect = getTextRect(p, Qt::AlignCenter, setSpeedStr); + speed_rect.moveCenter({set_speed_rect.center().x(), 0}); + speed_rect.moveTop(set_speed_rect.top() + 8); + p.drawText(speed_rect, Qt::AlignCenter, setSpeedStr); + + // Draw MAX + if (is_cruise_set) { + if (status == STATUS_DISENGAGED) { + p.setPen(QColor(0xff, 0xff, 0xff, 0xff)); + } else if (status == STATUS_OVERRIDE) { + p.setPen(QColor(0x91, 0x9b, 0x95, 0xff)); + } else if (speedLimit > 0) { + p.setPen(interpColor( + setSpeed, + {speedLimit + 5, speedLimit + 15, speedLimit + 25}, + {QColor(0x80, 0xd8, 0xa6, 0xff), QColor(0xff, 0xe4, 0xbf, 0xff), QColor(0xff, 0xbf, 0xbf, 0xff)} + )); + } else { + p.setPen(QColor(0x80, 0xd8, 0xa6, 0xff)); + } + } else { + p.setPen(QColor(0xa6, 0xa6, 0xa6, 0xff)); + } + configFont(p, "Open Sans", 40, "SemiBold"); + QRect max_rect = getTextRect(p, Qt::AlignCenter, "MAX"); + max_rect.moveCenter({set_speed_rect.center().x(), 0}); + max_rect.moveTop(set_speed_rect.top() + 123); + p.drawText(max_rect, Qt::AlignCenter, "MAX"); + + // US/Canada (MUTCD style) sign + if (has_us_speed_limit) { + const int border_width = 6; + const int sign_width = (speedLimitStr.size() >= 3) ? 199 : 148; + const int sign_height = 186; + + // White outer square + QRect sign_rect_outer(set_speed_rect.left() + 12, set_speed_rect.bottom() - 11 - sign_height, sign_width, sign_height); + p.setPen(Qt::NoPen); + p.setBrush(QColor(255, 255, 255, 255)); + p.drawRoundedRect(sign_rect_outer, 24, 24); + + // Smaller white square with black border + QRect sign_rect(sign_rect_outer.left() + 1.5 * border_width, sign_rect_outer.top() + 1.5 * border_width, sign_width - 3 * border_width, sign_height - 3 * border_width); + p.setPen(QPen(QColor(0, 0, 0, 255), border_width)); + p.setBrush(QColor(255, 255, 255, 255)); + p.drawRoundedRect(sign_rect, 16, 16); + + // "SPEED" + configFont(p, "Open Sans", 28, "SemiBold"); + QRect text_speed_rect = getTextRect(p, Qt::AlignCenter, "SPEED"); + text_speed_rect.moveCenter({sign_rect.center().x(), 0}); + text_speed_rect.moveTop(sign_rect_outer.top() + 20); + p.drawText(text_speed_rect, Qt::AlignCenter, "SPEED"); + + // "LIMIT" + QRect text_limit_rect = getTextRect(p, Qt::AlignCenter, "LIMIT"); + text_limit_rect.moveCenter({sign_rect.center().x(), 0}); + text_limit_rect.moveTop(sign_rect_outer.top() + 48); + p.drawText(text_limit_rect, Qt::AlignCenter, "LIMIT"); + + // Speed limit value + configFont(p, "Open Sans", 70, "Bold"); + QRect speed_limit_rect = getTextRect(p, Qt::AlignCenter, speedLimitStr); + speed_limit_rect.moveCenter({sign_rect.center().x(), 0}); + speed_limit_rect.moveTop(sign_rect.top() + 70); + p.drawText(speed_limit_rect, Qt::AlignCenter, speedLimitStr); + } + + // EU (Vienna style) sign + if (has_eu_speed_limit) { + int outer_radius = 176 / 2; + int inner_radius_1 = outer_radius - 6; // White outer border + int inner_radius_2 = inner_radius_1 - 20; // Red circle + + // Draw white circle with red border + QPoint center(set_speed_rect.center().x() + 1, set_speed_rect.top() + 204 + outer_radius); + p.setPen(Qt::NoPen); + p.setBrush(QColor(255, 255, 255, 255)); + p.drawEllipse(center, outer_radius, outer_radius); + p.setBrush(QColor(255, 0, 0, 255)); + p.drawEllipse(center, inner_radius_1, inner_radius_1); + p.setBrush(QColor(255, 255, 255, 255)); + p.drawEllipse(center, inner_radius_2, inner_radius_2); + + // Speed limit value + int font_size = (speedLimitStr.size() >= 3) ? 62 : 70; + configFont(p, "Open Sans", font_size, "Bold"); + QRect speed_limit_rect = getTextRect(p, Qt::AlignCenter, speedLimitStr); + speed_limit_rect.moveCenter(center); + p.setPen(QColor(0, 0, 0, 255)); + p.drawText(speed_limit_rect, Qt::AlignCenter, speedLimitStr); } // current speed configFont(p, "Open Sans", 176, "Bold"); - drawText(p, rect().center().x(), 210, speed); + drawText(p, rect().center().x(), 210, speedStr); configFont(p, "Open Sans", 66, "Regular"); drawText(p, rect().center().x(), 290, speedUnit, 200); @@ -243,9 +363,7 @@ void NvgWindow::drawHud(QPainter &p) { } void NvgWindow::drawText(QPainter &p, int x, int y, const QString &text, int alpha) { - QFontMetrics fm(p.font()); - QRect init_rect = fm.boundingRect(text); - QRect real_rect = fm.boundingRect(init_rect, 0, text); + QRect real_rect = getTextRect(p, 0, text); real_rect.moveCenter({x, y - real_rect.height() / 2}); p.setPen(QColor(0xff, 0xff, 0xff, alpha)); diff --git a/selfdrive/ui/qt/onroad.h b/selfdrive/ui/qt/onroad.h index 6ca2b3c738..3d90a63d7c 100644 --- a/selfdrive/ui/qt/onroad.h +++ b/selfdrive/ui/qt/onroad.h @@ -27,10 +27,14 @@ private: // container window for the NVG UI class NvgWindow : public CameraViewWidget { Q_OBJECT - Q_PROPERTY(QString speed MEMBER speed); + Q_PROPERTY(float speed MEMBER speed); Q_PROPERTY(QString speedUnit MEMBER speedUnit); - Q_PROPERTY(QString maxSpeed MEMBER maxSpeed); + Q_PROPERTY(float setSpeed MEMBER setSpeed); + Q_PROPERTY(float speedLimit MEMBER speedLimit); Q_PROPERTY(bool is_cruise_set MEMBER is_cruise_set); + Q_PROPERTY(bool has_eu_speed_limit MEMBER has_eu_speed_limit); + Q_PROPERTY(bool has_us_speed_limit MEMBER has_us_speed_limit); + Q_PROPERTY(bool engageable MEMBER engageable); Q_PROPERTY(bool dmActive MEMBER dmActive); Q_PROPERTY(bool hideDM MEMBER hideDM); @@ -48,13 +52,16 @@ private: QPixmap dm_img; const int radius = 192; const int img_size = (radius / 2) * 1.5; - QString speed; + float speed; QString speedUnit; - QString maxSpeed; + float setSpeed; + float speedLimit; bool is_cruise_set = false; bool engageable = false; bool dmActive = false; bool hideDM = false; + bool has_us_speed_limit = false; + bool has_eu_speed_limit = false; int status = STATUS_DISENGAGED; protected: diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc index 600885fb37..408652a0b9 100644 --- a/selfdrive/ui/qt/util.cc +++ b/selfdrive/ui/qt/util.cc @@ -135,3 +135,64 @@ QPixmap loadPixmap(const QString &fileName, const QSize &size, Qt::AspectRatioMo return QPixmap(fileName).scaled(size, aspectRatioMode, Qt::SmoothTransformation); } } + +QRect getTextRect(QPainter &p, int flags, QString text) { + QFontMetrics fm(p.font()); + QRect init_rect = fm.boundingRect(text); + return fm.boundingRect(init_rect, flags, text); +} + +void drawRoundedRect(QPainter &painter, const QRectF &rect, qreal xRadiusTop, qreal yRadiusTop, qreal xRadiusBottom, qreal yRadiusBottom){ + qreal w_2 = rect.width() / 2; + qreal h_2 = rect.height() / 2; + + xRadiusTop = 100 * qMin(xRadiusTop, w_2) / w_2; + yRadiusTop = 100 * qMin(yRadiusTop, h_2) / h_2; + + xRadiusBottom = 100 * qMin(xRadiusBottom, w_2) / w_2; + yRadiusBottom = 100 * qMin(yRadiusBottom, h_2) / h_2; + + qreal x = rect.x(); + qreal y = rect.y(); + qreal w = rect.width(); + qreal h = rect.height(); + + qreal rxx2Top = w*xRadiusTop/100; + qreal ryy2Top = h*yRadiusTop/100; + + qreal rxx2Bottom = w*xRadiusBottom/100; + qreal ryy2Bottom = h*yRadiusBottom/100; + + QPainterPath path; + path.arcMoveTo(x, y, rxx2Top, ryy2Top, 180); + path.arcTo(x, y, rxx2Top, ryy2Top, 180, -90); + path.arcTo(x+w-rxx2Top, y, rxx2Top, ryy2Top, 90, -90); + path.arcTo(x+w-rxx2Bottom, y+h-ryy2Bottom, rxx2Bottom, ryy2Bottom, 0, -90); + path.arcTo(x, y+h-ryy2Bottom, rxx2Bottom, ryy2Bottom, 270, -90); + path.closeSubpath(); + + painter.drawPath(path); +} + +QColor interpColor(float xv, std::vector xp, std::vector fp) { + assert(xp.size() == fp.size()); + + int N = xp.size(); + int hi = 0; + + while (hi < N and xv > xp[hi]) hi++; + int low = hi - 1; + + if (hi == N && xv > xp[low]) { + return fp[fp.size() - 1]; + } else if (hi == 0){ + return fp[0]; + } else { + return QColor( + (xv - xp[low]) * (fp[hi].red() - fp[low].red()) / (xp[hi] - xp[low]) + fp[low].red(), + (xv - xp[low]) * (fp[hi].green() - fp[low].green()) / (xp[hi] - xp[low]) + fp[low].green(), + (xv - xp[low]) * (fp[hi].blue() - fp[low].blue()) / (xp[hi] - xp[low]) + fp[low].blue(), + (xv - xp[low]) * (fp[hi].alpha() - fp[low].alpha()) / (xp[hi] - xp[low]) + fp[low].alpha() + ); + } +} diff --git a/selfdrive/ui/qt/util.h b/selfdrive/ui/qt/util.h index 813777710a..9491c6798e 100644 --- a/selfdrive/ui/qt/util.h +++ b/selfdrive/ui/qt/util.h @@ -22,3 +22,7 @@ void swagLogMessageHandler(QtMsgType type, const QMessageLogContext &context, co void initApp(int argc, char *argv[]); QWidget* topWidget (QWidget* widget); QPixmap loadPixmap(const QString &fileName, const QSize &size = {}, Qt::AspectRatioMode aspectRatioMode = Qt::KeepAspectRatio); + +QRect getTextRect(QPainter &p, int flags, QString text); +void drawRoundedRect(QPainter &painter, const QRectF &rect, qreal xRadiusTop, qreal yRadiusTop, qreal xRadiusBottom, qreal yRadiusBottom); +QColor interpColor(float xv, std::vector xp, std::vector fp); From b046eb818e35f24d3b9b8a978fddb94dbfb85e59 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 15 Jun 2022 13:09:57 +0200 Subject: [PATCH 051/302] add speed limits to release notes --- RELEASES.md | 1 + 1 file changed, 1 insertion(+) diff --git a/RELEASES.md b/RELEASES.md index acbafd5f5b..7f365e5cef 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -10,6 +10,7 @@ Version 0.8.15 (2022-XX-XX) * takes a larger input frame * outputs a driver state for both driver and passenger * automatically determines which side the driver is on (soon) +* Display speed limit while navigating * Reduced power usage: device runs cooler and fan spins less * AGNOS 5 * Hyundai Tucson 2021 support thanks to bluesforte! From 9e3d0e3c9cea4dcf2da10801aad041b1dd65cccb Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Wed, 15 Jun 2022 14:00:27 +0200 Subject: [PATCH 052/302] Laikad: Remove bearingDeg from message (#24864) * Remove bearingDeg from message. * Push cereal * Commit cereal --- cereal | 2 +- selfdrive/locationd/laikad.py | 14 -------------- 2 files changed, 1 insertion(+), 15 deletions(-) diff --git a/cereal b/cereal index 98f795fd73..4b4d9aab03 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 98f795fd73356198f1fc8d5ea5a8f25e6f7c57e0 +Subproject commit 4b4d9aab03937f5a45677ff15efb275abf9c958b diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index ddd57bdca9..ebe7404e17 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -20,7 +20,6 @@ from laika.raw_gnss import GNSSMeasurement, calc_pos_fix, correct_measurements, from selfdrive.locationd.models.constants import GENERATED_DIR, ObservationKind from selfdrive.locationd.models.gnss_kf import GNSSKalman from selfdrive.locationd.models.gnss_kf import States as GStates -import common.transformations.coordinates as coord from system.swaglog import cloudlog MAX_TIME_GAP = 10 @@ -94,15 +93,12 @@ class Laikad: pos_std = np.sqrt(abs(self.gnss_kf.P[GStates.ECEF_POS].diagonal())).tolist() vel_std = np.sqrt(abs(self.gnss_kf.P[GStates.ECEF_VELOCITY].diagonal())).tolist() - bearing_deg, bearing_std = get_bearing_from_gnss(ecef_pos, ecef_vel, vel_std) - meas_msgs = [create_measurement_msg(m) for m in corrected_measurements] dat = messaging.new_message("gnssMeasurements") measurement_msg = log.LiveLocationKalman.Measurement.new_message dat.gnssMeasurements = { "positionECEF": measurement_msg(value=ecef_pos, std=pos_std, valid=kf_valid), "velocityECEF": measurement_msg(value=ecef_vel, std=vel_std, valid=kf_valid), - "bearingDeg": measurement_msg(value=[bearing_deg], std=[bearing_std], valid=kf_valid), "ubloxMonoTime": ublox_mono_time, "correctedMeasurements": meas_msgs } @@ -211,16 +207,6 @@ def kf_add_observations(gnss_kf: GNSSKalman, t: float, measurements: List[GNSSMe gnss_kf.predict_and_observe(t, kind, data) -def get_bearing_from_gnss(ecef_pos, ecef_vel, vel_std): - # init orientation with direction of velocity - converter = coord.LocalCoord.from_ecef(ecef_pos) - - ned_vel = np.einsum('ij,j ->i', converter.ned_from_ecef_matrix, ecef_vel) - bearing = np.arctan2(ned_vel[1], ned_vel[0]) - bearing_std = np.arctan2(np.linalg.norm(vel_std), np.linalg.norm(ned_vel)) - return float(np.rad2deg(bearing)), float(bearing_std) - - class CacheSerializer(json.JSONEncoder): def default(self, o): From 849ec17b20f8cae7f6fd6589456d7b00b07e794b Mon Sep 17 00:00:00 2001 From: Lee Jong Mun <43285072+crwusiz@users.noreply.github.com> Date: Wed, 15 Jun 2022 23:10:56 +0900 Subject: [PATCH 053/302] ui: add black color define (#24866) --- selfdrive/ui/qt/onroad.cc | 24 ++++++++++++------------ selfdrive/ui/qt/onroad.h | 1 + 2 files changed, 13 insertions(+), 12 deletions(-) diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 12a579c573..38541ef2d5 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -230,8 +230,8 @@ void NvgWindow::drawHud(QPainter &p) { int bottom_radius = has_eu_speed_limit ? 100 : 32; QRect set_speed_rect(60 + default_rect_width / 2 - rect_width / 2, 45, rect_width, rect_height); - p.setPen(QPen(QColor(255, 255, 255, 75), 6)); - p.setBrush(QColor(0, 0, 0, 166)); + p.setPen(QPen(whiteColor(75), 6)); + p.setBrush(blackColor(166)); drawRoundedRect(p, set_speed_rect, top_radius, top_radius, bottom_radius, bottom_radius); // Draw set speed @@ -240,10 +240,10 @@ void NvgWindow::drawHud(QPainter &p) { p.setPen(interpColor( setSpeed, {speedLimit + 5, speedLimit + 15, speedLimit + 25}, - {QColor(0xff, 0xff, 0xff, 0xff), QColor(0xff, 0x95, 0x00, 0xff), QColor(0xff, 0x00, 0x00, 0xff)} + {whiteColor(), QColor(0xff, 0x95, 0x00, 0xff), QColor(0xff, 0x00, 0x00, 0xff)} )); } else { - p.setPen(QColor(0xff, 0xff, 0xff, 0xff)); + p.setPen(whiteColor()); } } else { p.setPen(QColor(0x72, 0x72, 0x72, 0xff)); @@ -257,7 +257,7 @@ void NvgWindow::drawHud(QPainter &p) { // Draw MAX if (is_cruise_set) { if (status == STATUS_DISENGAGED) { - p.setPen(QColor(0xff, 0xff, 0xff, 0xff)); + p.setPen(whiteColor()); } else if (status == STATUS_OVERRIDE) { p.setPen(QColor(0x91, 0x9b, 0x95, 0xff)); } else if (speedLimit > 0) { @@ -287,13 +287,13 @@ void NvgWindow::drawHud(QPainter &p) { // White outer square QRect sign_rect_outer(set_speed_rect.left() + 12, set_speed_rect.bottom() - 11 - sign_height, sign_width, sign_height); p.setPen(Qt::NoPen); - p.setBrush(QColor(255, 255, 255, 255)); + p.setBrush(whiteColor()); p.drawRoundedRect(sign_rect_outer, 24, 24); // Smaller white square with black border QRect sign_rect(sign_rect_outer.left() + 1.5 * border_width, sign_rect_outer.top() + 1.5 * border_width, sign_width - 3 * border_width, sign_height - 3 * border_width); - p.setPen(QPen(QColor(0, 0, 0, 255), border_width)); - p.setBrush(QColor(255, 255, 255, 255)); + p.setPen(QPen(blackColor(), border_width)); + p.setBrush(whiteColor()); p.drawRoundedRect(sign_rect, 16, 16); // "SPEED" @@ -326,11 +326,11 @@ void NvgWindow::drawHud(QPainter &p) { // Draw white circle with red border QPoint center(set_speed_rect.center().x() + 1, set_speed_rect.top() + 204 + outer_radius); p.setPen(Qt::NoPen); - p.setBrush(QColor(255, 255, 255, 255)); + p.setBrush(whiteColor()); p.drawEllipse(center, outer_radius, outer_radius); p.setBrush(QColor(255, 0, 0, 255)); p.drawEllipse(center, inner_radius_1, inner_radius_1); - p.setBrush(QColor(255, 255, 255, 255)); + p.setBrush(whiteColor()); p.drawEllipse(center, inner_radius_2, inner_radius_2); // Speed limit value @@ -338,7 +338,7 @@ void NvgWindow::drawHud(QPainter &p) { configFont(p, "Open Sans", font_size, "Bold"); QRect speed_limit_rect = getTextRect(p, Qt::AlignCenter, speedLimitStr); speed_limit_rect.moveCenter(center); - p.setPen(QColor(0, 0, 0, 255)); + p.setPen(blackColor()); p.drawText(speed_limit_rect, Qt::AlignCenter, speedLimitStr); } @@ -357,7 +357,7 @@ void NvgWindow::drawHud(QPainter &p) { // dm icon if (!hideDM) { drawIcon(p, radius / 2 + (bdr_s * 2), rect().bottom() - footer_h / 2, - dm_img, QColor(0, 0, 0, 70), dmActive ? 1.0 : 0.2); + dm_img, blackColor(70), dmActive ? 1.0 : 0.2); } p.restore(); } diff --git a/selfdrive/ui/qt/onroad.h b/selfdrive/ui/qt/onroad.h index 3d90a63d7c..e58d7a7972 100644 --- a/selfdrive/ui/qt/onroad.h +++ b/selfdrive/ui/qt/onroad.h @@ -74,6 +74,7 @@ protected: void drawHud(QPainter &p); inline QColor redColor(int alpha = 255) { return QColor(201, 34, 49, alpha); } inline QColor whiteColor(int alpha = 255) { return QColor(255, 255, 255, alpha); } + inline QColor blackColor(int alpha = 255) { return QColor(0, 0, 0, alpha); } double prev_draw_t = 0; FirstOrderFilter fps_filter; From d2400150e51833678f8c216c0c605111cfa13018 Mon Sep 17 00:00:00 2001 From: Lee Jong Mun <43285072+crwusiz@users.noreply.github.com> Date: Wed, 15 Jun 2022 23:16:18 +0900 Subject: [PATCH 054/302] ui: advanced network settings fix button colors and sizes (#24846) * ui: button pressed color add * match colors from other buttons Co-authored-by: Willem Melching --- selfdrive/ui/qt/offroad/networking.cc | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/selfdrive/ui/qt/offroad/networking.cc b/selfdrive/ui/qt/offroad/networking.cc index 9c2088b1d7..80c7ad045b 100644 --- a/selfdrive/ui/qt/offroad/networking.cc +++ b/selfdrive/ui/qt/offroad/networking.cc @@ -28,9 +28,9 @@ Networking::Networking(QWidget* parent, bool show_advanced) : QFrame(parent) { vlayout->setContentsMargins(20, 20, 20, 20); if (show_advanced) { QPushButton* advancedSettings = new QPushButton("Advanced"); - advancedSettings->setObjectName("advancedBtn"); + advancedSettings->setObjectName("advanced_btn"); advancedSettings->setStyleSheet("margin-right: 30px;"); - advancedSettings->setFixedSize(350, 100); + advancedSettings->setFixedSize(400, 100); connect(advancedSettings, &QPushButton::clicked, [=]() { main_layout->setCurrentWidget(an); }); vlayout->addSpacing(10); vlayout->addWidget(advancedSettings, 0, Qt::AlignRight); @@ -57,14 +57,17 @@ Networking::Networking(QWidget* parent, bool show_advanced) : QFrame(parent) { // TODO: revisit pressed colors setStyleSheet(R"( - #wifiWidget > QPushButton, #back_btn, #advancedBtn { + #wifiWidget > QPushButton, #back_btn, #advanced_btn { font-size: 50px; margin: 0px; padding: 15px; border-width: 0; border-radius: 30px; color: #dddddd; - background-color: #444444; + background-color: #393939; + } + #back_btn:pressed, #advanced_btn:pressed { + background-color: #4a4a4a; } )"); main_layout->setCurrentWidget(wifiScreen); @@ -118,7 +121,7 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid // Back button QPushButton* back = new QPushButton("Back"); back->setObjectName("back_btn"); - back->setFixedSize(500, 100); + back->setFixedSize(400, 100); connect(back, &QPushButton::clicked, [=]() { emit backPress(); }); main_layout->addWidget(back, 0, Qt::AlignLeft); From bb02c1c5158b3403e7d2395611d2db1ab44aed5e Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 15 Jun 2022 16:19:04 +0200 Subject: [PATCH 055/302] networking.cc: remove resolved TODO --- selfdrive/ui/qt/offroad/networking.cc | 1 - 1 file changed, 1 deletion(-) diff --git a/selfdrive/ui/qt/offroad/networking.cc b/selfdrive/ui/qt/offroad/networking.cc index 80c7ad045b..418ccd3179 100644 --- a/selfdrive/ui/qt/offroad/networking.cc +++ b/selfdrive/ui/qt/offroad/networking.cc @@ -55,7 +55,6 @@ Networking::Networking(QWidget* parent, bool show_advanced) : QFrame(parent) { setAutoFillBackground(true); setPalette(pal); - // TODO: revisit pressed colors setStyleSheet(R"( #wifiWidget > QPushButton, #back_btn, #advanced_btn { font-size: 50px; From 41721917239e8eac314a2dc6c64cfb4695ff460e Mon Sep 17 00:00:00 2001 From: Lee Jong Mun <43285072+crwusiz@users.noreply.github.com> Date: Thu, 16 Jun 2022 00:35:46 +0900 Subject: [PATCH 056/302] selfdrive/ui/qt/util.cc: missing include (#24867) --- selfdrive/ui/qt/util.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc index 408652a0b9..366aa76f49 100644 --- a/selfdrive/ui/qt/util.cc +++ b/selfdrive/ui/qt/util.cc @@ -3,6 +3,7 @@ #include #include #include +#include #include "common/params.h" #include "common/swaglog.h" From fa4f017bbe6c117913ec2327e9129c70b3e47223 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 15 Jun 2022 18:03:15 +0200 Subject: [PATCH 057/302] laikad: calc_pos_fix numpy implementation (#24865) * Replace posfix with gauss newton method * Cleanup * Check if glonass is in the list * Fix * also return residual * Add residuals * Update selfdrive/locationd/laikad.py Co-authored-by: Willem Melching * Cleanup Co-authored-by: Gijs Koning --- selfdrive/locationd/laikad.py | 103 +++++++++++++++++++++++++++++++--- 1 file changed, 95 insertions(+), 8 deletions(-) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index ebe7404e17..8eb81345ff 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -7,16 +7,17 @@ from typing import List, Optional import numpy as np from collections import defaultdict +import sympy from numpy.linalg import linalg from cereal import log, messaging from common.params import Params, put_nonblocking from laika import AstroDog -from laika.constants import SECS_IN_HR, SECS_IN_MIN +from laika.constants import EARTH_ROTATION_RATE, SECS_IN_HR, SECS_IN_MIN, SPEED_OF_LIGHT from laika.ephemeris import Ephemeris, EphemerisType, convert_ublox_ephem from laika.gps_time import GPSTime from laika.helpers import ConstellationId -from laika.raw_gnss import GNSSMeasurement, calc_pos_fix, correct_measurements, process_measurements, read_raw_ublox +from laika.raw_gnss import GNSSMeasurement, correct_measurements, process_measurements, read_raw_ublox from selfdrive.locationd.models.constants import GENERATED_DIR, ObservationKind from selfdrive.locationd.models.gnss_kf import GNSSKalman from selfdrive.locationd.models.gnss_kf import States as GStates @@ -38,6 +39,7 @@ class Laikad: self.last_cached_t = None self.save_ephemeris = save_ephemeris self.load_cache() + self.posfix_functions = {constellation: get_posfix_sympy_fun(constellation) for constellation in (ConstellationId.GPS, ConstellationId.GLONASS)} def load_cache(self): cache = Params().get(EPHEMERIS_CACHE) @@ -66,7 +68,9 @@ class Laikad: self.fetch_orbits(latest_msg_t + SECS_IN_MIN, block) new_meas = read_raw_ublox(report) processed_measurements = process_measurements(new_meas, self.astro_dog) - pos_fix = calc_pos_fix(processed_measurements, min_measurements=4) + + min_measurements = 5 if any(p.constellation_id == ConstellationId.GLONASS for p in processed_measurements) else 4 + pos_fix = calc_pos_fix_gauss_newton(processed_measurements, self.posfix_functions, min_measurements=min_measurements) t = ublox_mono_time * 1e-9 kf_pos_std = None @@ -84,7 +88,7 @@ class Laikad: if est_pos is not None: corrected_measurements = correct_measurements(processed_measurements, est_pos, self.astro_dog) - self.update_localizer(pos_fix, t, corrected_measurements) + self.update_localizer(est_pos, t, corrected_measurements) kf_valid = all(self.kf_valid(t)) ecef_pos = self.gnss_kf.x[GStates.ECEF_POS].tolist() @@ -110,7 +114,7 @@ class Laikad: # elif ublox_msg.which == 'ionoData': # todo add this. Needed to better correct messages offline. First fix ublox_msg.cc to sent them. - def update_localizer(self, pos_fix, t: float, measurements: List[GNSSMeasurement]): + def update_localizer(self, est_pos, t: float, measurements: List[GNSSMeasurement]): # Check time and outputs are valid valid = self.kf_valid(t) if not all(valid): @@ -123,11 +127,10 @@ class Laikad: else: cloudlog.error("Gnss kalman std too far") - if len(pos_fix) == 0: + if est_pos is None: cloudlog.info("Position fix not available when resetting kalman filter") return - post_est = pos_fix[0][:3].tolist() - self.init_gnss_localizer(post_est) + self.init_gnss_localizer(est_pos.tolist()) if len(measurements) > 0: kf_add_observations(self.gnss_kf, t, measurements) else: @@ -227,6 +230,90 @@ def deserialize_hook(dct): return dct +def calc_pos_fix_gauss_newton(measurements, posfix_functions, x0=None, signal='C1C', min_measurements=6): + ''' + Calculates gps fix using gauss newton method + To solve the problem a minimal of 4 measurements are required. + If Glonass is included 5 are required to solve for the additional free variable. + returns: + 0 -> list with positions + ''' + if x0 is None: + x0 = [0, 0, 0, 0, 0] + n = len(measurements) + if n < min_measurements: + return [] + + Fx_pos = pr_residual(measurements, posfix_functions, signal=signal) + x = gauss_newton(Fx_pos, x0) + residual, _ = Fx_pos(x, weight=1.0) + return x, residual + + +def pr_residual(measurements, posfix_functions, signal='C1C'): + def Fx_pos(inp, weight=None): + vals, gradients = [], [] + + for meas in measurements: + pr = meas.observables[signal] + pr += meas.sat_clock_err * SPEED_OF_LIGHT + + w = (1 / meas.observables_std[signal]) if weight is None else weight + + val, *gradient = posfix_functions[meas.constellation_id](*inp, pr, *meas.sat_pos, w) + vals.append(val) + gradients.append(gradient) + return np.asarray(vals), np.asarray(gradients) + + return Fx_pos + + +def gauss_newton(fun, b, xtol=1e-8, max_n=25): + for _ in range(max_n): + # Compute function and jacobian on current estimate + r, J = fun(b) + + # Update estimate + delta = np.linalg.pinv(J) @ r + b -= delta + + # Check step size for stopping condition + if np.linalg.norm(delta) < xtol: + break + return b + + +def get_posfix_sympy_fun(constellation): + # Unknowns + x, y, z = sympy.Symbol('x'), sympy.Symbol('y'), sympy.Symbol('z') + bc = sympy.Symbol('bc') + bg = sympy.Symbol('bg') + var = [x, y, z, bc, bg] + + # Knowns + pr = sympy.Symbol('pr') + sat_x, sat_y, sat_z = sympy.Symbol('sat_x'), sympy.Symbol('sat_y'), sympy.Symbol('sat_z') + weight = sympy.Symbol('weight') + + theta = EARTH_ROTATION_RATE * (pr - bc) / SPEED_OF_LIGHT + val = sympy.sqrt( + (sat_x * sympy.cos(theta) + sat_y * sympy.sin(theta) - x) ** 2 + + (sat_y * sympy.cos(theta) - sat_x * sympy.sin(theta) - y) ** 2 + + (sat_z - z) ** 2 + ) + + if constellation == ConstellationId.GLONASS: + res = weight * (val - (pr - bc - bg)) + elif constellation == ConstellationId.GPS: + res = weight * (val - (pr - bc)) + else: + raise NotImplementedError(f"Constellation {constellation} not supported") + + res = [res] + [sympy.diff(res, v) for v in var] + + return sympy.lambdify([x, y, z, bc, bg, pr, sat_x, sat_y, sat_z, weight], res) + + def main(): sm = messaging.SubMaster(['ubloxGnss']) pm = messaging.PubMaster(['gnssMeasurements']) From efc8aa05b4573f9ac96d518fbf04b6d799e487d0 Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Wed, 15 Jun 2022 11:32:26 -0700 Subject: [PATCH 058/302] Update model ref --- selfdrive/test/process_replay/model_replay_ref_commit | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index a7a909d2a4..ec5ef11311 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -512a9d4596c8faba304d6f7ded2ce77837357b65 +6ec6db2f2a070ba1603bbe1d934509781cc4556a From c851cf737931cba16909b2fe20ffec4858acd374 Mon Sep 17 00:00:00 2001 From: Harald Schafer Date: Wed, 15 Jun 2022 11:33:59 -0700 Subject: [PATCH 059/302] Revert "Update model ref" This reverts commit efc8aa05b4573f9ac96d518fbf04b6d799e487d0. --- selfdrive/test/process_replay/model_replay_ref_commit | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index ec5ef11311..a7a909d2a4 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -6ec6db2f2a070ba1603bbe1d934509781cc4556a +512a9d4596c8faba304d6f7ded2ce77837357b65 From 9283040d847b120fdf7759d5bd12000863e12f73 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Wed, 15 Jun 2022 15:29:42 -0700 Subject: [PATCH 060/302] Rocket league model (#24869) * dd9a502d-c8e2-4831-b365-804b0ae0739d/600 80041070-d276-4fed-bdb9-0075e5442908/420 * no elementwise op * 9dabf0fe-2e60-44bf-8d3a-d20a74aca072/600 ae746590-0bb5-4a16-80db-15f02d314f03/300 c4663a12-b499-4c9b-90dd-b169e3948cb1/60 * explicit slice * some copies are useful * 1456d261-d232-4654-8885-4d9fde883894/440 c06eba55-1931-4e00-9d63-acad00161be0/700 af2eb6ba-1935-4318-aaf8-868db81a4932/425 * 154f663e-d3e9-4020-ad49-0e640588ebbe/399 badb5e69-504f-4544-a99e-ba75ed204b74/800 08330327-7663-4874-af7a-dcbd2c994ba7/800 * set steer rate cost to 1.0 * smaller temporal size * Update model reg * update model ref again * This did upload somehow * Update steer rate cost Co-authored-by: Yassine Yousfi --- selfdrive/car/body/interface.py | 1 - selfdrive/car/chrysler/interface.py | 1 - selfdrive/car/ford/interface.py | 1 - selfdrive/car/gm/interface.py | 1 - selfdrive/car/honda/interface.py | 1 - selfdrive/car/hyundai/interface.py | 1 - selfdrive/car/mazda/interface.py | 1 - selfdrive/car/nissan/interface.py | 1 - selfdrive/car/subaru/interface.py | 1 - selfdrive/car/tesla/interface.py | 1 - selfdrive/car/tests/test_car_interfaces.py | 1 - selfdrive/car/tests/test_models.py | 1 - selfdrive/car/toyota/interface.py | 1 - selfdrive/car/volkswagen/interface.py | 1 - selfdrive/controls/lib/lateral_planner.py | 9 ++++----- selfdrive/controls/plannerd.py | 2 +- selfdrive/modeld/models/driving.h | 2 +- selfdrive/modeld/models/supercombo.dlc | 4 ++-- selfdrive/modeld/models/supercombo.onnx | 4 ++-- selfdrive/modeld/thneed/compile.cc | 2 +- selfdrive/modeld/thneed/optimizer.cc | 8 ++++---- selfdrive/test/process_replay/model_replay_ref_commit | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 23 files changed, 17 insertions(+), 32 deletions(-) diff --git a/selfdrive/car/body/interface.py b/selfdrive/car/body/interface.py index 3d6bd5e22a..e85735b1a6 100644 --- a/selfdrive/car/body/interface.py +++ b/selfdrive/car/body/interface.py @@ -19,7 +19,6 @@ class CarInterface(CarInterfaceBase): ret.minSteerSpeed = -math.inf ret.maxLateralAccel = math.inf # TODO: set to a reasonable value ret.steerRatio = 0.5 - ret.steerRateCost = 0.5 ret.steerLimitTimer = 1.0 ret.steerActuatorDelay = 0. diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 55672dd4ab..817a5b387e 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -20,7 +20,6 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] ret.lateralTuning.pid.kf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594 ret.steerActuatorDelay = 0.1 - ret.steerRateCost = 0.7 ret.steerLimitTimer = 0.4 if candidate in (CAR.JEEP_CHEROKEE, CAR.JEEP_CHEROKEE_2019): diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py index ec7c723669..c608cc08d9 100644 --- a/selfdrive/car/ford/interface.py +++ b/selfdrive/car/ford/interface.py @@ -59,7 +59,6 @@ class CarInterface(CarInterfaceBase): # LCA can steer down to zero ret.minSteerSpeed = 0. - ret.steerRateCost = 1.0 ret.centerToFront = ret.wheelbase * 0.44 ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 498f4b3347..9c1744dfb4 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -63,7 +63,6 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.00]] ret.lateralTuning.pid.kf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594 - ret.steerRateCost = 1.0 ret.steerActuatorDelay = 0.1 # Default delay, not measured yet ret.longitudinalTuning.kpBP = [5., 35.] diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index ea7deab5d7..994152608e 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -319,7 +319,6 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor=tire_stiffness_factor) ret.steerActuatorDelay = 0.1 - ret.steerRateCost = 0.5 ret.steerLimitTimer = 0.8 return ret diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 6fd75ebfab..497d6b3f30 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -43,7 +43,6 @@ class CarInterface(CarInterfaceBase): ret.dashcamOnly = not os.path.exists('/data/enable-ev6') ret.steerActuatorDelay = 0.1 # Default delay - ret.steerRateCost = 0.5 ret.steerLimitTimer = 0.4 tire_stiffness_factor = 1. diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index 0ef573c6b6..cbeb910de2 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -25,7 +25,6 @@ class CarInterface(CarInterfaceBase): ret.dashcamOnly = candidate not in (CAR.CX5_2022, CAR.CX9_2021) ret.steerActuatorDelay = 0.1 - ret.steerRateCost = 1.0 ret.steerLimitTimer = 0.8 tire_stiffness_factor = 0.70 # not optimized yet diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index 3bf34e8266..436cef68bf 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -14,7 +14,6 @@ class CarInterface(CarInterfaceBase): ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.nissan)] ret.steerLimitTimer = 1.0 - ret.steerRateCost = 0.5 ret.steerActuatorDelay = 0.1 diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index d0d8e91ce1..8c5cab86e8 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -22,7 +22,6 @@ class CarInterface(CarInterfaceBase): ret.dashcamOnly = candidate in PREGLOBAL_CARS - ret.steerRateCost = 0.7 ret.steerLimitTimer = 0.4 if candidate == CAR.ASCENT: diff --git a/selfdrive/car/tesla/interface.py b/selfdrive/car/tesla/interface.py index 71594cecb6..d4eda38e64 100755 --- a/selfdrive/car/tesla/interface.py +++ b/selfdrive/car/tesla/interface.py @@ -42,7 +42,6 @@ class CarInterface(CarInterfaceBase): ret.steerLimitTimer = 1.0 ret.steerActuatorDelay = 0.25 - ret.steerRateCost = 0.5 if candidate in (CAR.AP2_MODELS, CAR.AP1_MODELS): ret.mass = 2100. + STD_CARGO_KG diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index 52c89440c7..15df1aafef 100755 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -33,7 +33,6 @@ class TestCarInterfaces(unittest.TestCase): assert car_interface self.assertGreater(car_params.mass, 1) - self.assertGreater(car_params.steerRateCost, 1e-3) if car_params.steerControlType != car.CarParams.SteerControlType.angle: tuning = car_params.lateralTuning.which() diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 9ab881279b..27dc4ba776 100755 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -121,7 +121,6 @@ class TestCarModelBase(unittest.TestCase): # make sure car params are within a valid range self.assertGreater(self.CP.mass, 1) - self.assertGreater(self.CP.steerRateCost, 1e-3) if self.CP.steerControlType != car.CarParams.SteerControlType.angle: tuning = self.CP.lateralTuning.which() diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 7969775a89..d0f4789775 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -213,7 +213,6 @@ class CarInterface(CarInterfaceBase): ret.mass = 4305. * CV.LB_TO_KG + STD_CARGO_KG set_lat_tune(ret.lateralTuning, LatTunes.PID_J) - ret.steerRateCost = 1. ret.centerToFront = ret.wheelbase * 0.44 # TODO: get actual value, for now starting with reasonable value for diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 3a0d7c8ce8..6782105c16 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -45,7 +45,6 @@ class CarInterface(CarInterfaceBase): # Global lateral tuning defaults, can be overridden per-vehicle ret.steerActuatorDelay = 0.1 - ret.steerRateCost = 1.0 ret.steerLimitTimer = 0.4 ret.steerRatio = 15.6 # Let the params learner figure this out tire_stiffness_factor = 1.0 # Let the params learner figure this out diff --git a/selfdrive/controls/lib/lateral_planner.py b/selfdrive/controls/lib/lateral_planner.py index ec21c16e91..019a19fb1d 100644 --- a/selfdrive/controls/lib/lateral_planner.py +++ b/selfdrive/controls/lib/lateral_planner.py @@ -11,13 +11,12 @@ from cereal import log class LateralPlanner: - def __init__(self, CP, use_lanelines=True, wide_camera=False): + def __init__(self, use_lanelines=True, wide_camera=False): self.use_lanelines = use_lanelines self.LP = LanePlanner(wide_camera) self.DH = DesireHelper() self.last_cloudlog_t = 0 - self.steer_rate_cost = CP.steerRateCost self.solution_invalid_cnt = 0 self.path_xyz = np.zeros((TRAJECTORY_SIZE, 3)) @@ -59,12 +58,12 @@ class LateralPlanner: # Calculate final driving path and set MPC costs if self.use_lanelines: d_path_xyz = self.LP.get_d_path(v_ego, self.t_idxs, self.path_xyz) - self.lat_mpc.set_weights(MPC_COST_LAT.PATH, MPC_COST_LAT.HEADING, self.steer_rate_cost) + self.lat_mpc.set_weights(MPC_COST_LAT.PATH, MPC_COST_LAT.HEADING, MPC_COST_LAT.STEER_RATE) else: d_path_xyz = self.path_xyz # Heading cost is useful at low speed, otherwise end of plan can be off-heading heading_cost = interp(v_ego, [5.0, 10.0], [MPC_COST_LAT.HEADING, 0.15]) - self.lat_mpc.set_weights(MPC_COST_LAT.PATH, heading_cost, self.steer_rate_cost) + self.lat_mpc.set_weights(MPC_COST_LAT.PATH, heading_cost, MPC_COST_LAT.STEER_RATE) y_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(d_path_xyz, axis=1), d_path_xyz[:, 1]) heading_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw) @@ -79,7 +78,7 @@ class LateralPlanner: y_pts, heading_pts) # init state for next - # mpc.u_sol is the desired curvature rate given x0 curv state. + # mpc.u_sol is the desired curvature rate given x0 curv state. # with x0[3] = measured_curvature, this would be the actual desired rate. # instead, interpolate x_sol so that x0[3] is the desired curvature for lat_control. self.x0[3] = interp(DT_MDL, self.t_idxs[:LAT_MPC_N + 1], self.lat_mpc.x_sol[:, 3]) diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py index 06807b2a5c..9356a55d84 100755 --- a/selfdrive/controls/plannerd.py +++ b/selfdrive/controls/plannerd.py @@ -22,7 +22,7 @@ def plannerd_thread(sm=None, pm=None): cloudlog.event("e2e mode", on=use_lanelines) longitudinal_planner = Planner(CP) - lateral_planner = LateralPlanner(CP, use_lanelines=use_lanelines, wide_camera=wide_camera) + lateral_planner = LateralPlanner(use_lanelines=use_lanelines, wide_camera=wide_camera) if sm is None: sm = messaging.SubMaster(['carState', 'controlsState', 'radarState', 'modelV2'], diff --git a/selfdrive/modeld/models/driving.h b/selfdrive/modeld/models/driving.h index 97e65fbc0e..a691051636 100644 --- a/selfdrive/modeld/models/driving.h +++ b/selfdrive/modeld/models/driving.h @@ -245,7 +245,7 @@ struct ModelOutput { constexpr int OUTPUT_SIZE = sizeof(ModelOutput) / sizeof(float); #ifdef TEMPORAL - constexpr int TEMPORAL_SIZE = 512; + constexpr int TEMPORAL_SIZE = 512+256; #else constexpr int TEMPORAL_SIZE = 0; #endif diff --git a/selfdrive/modeld/models/supercombo.dlc b/selfdrive/modeld/models/supercombo.dlc index 23f6d904fb..90f7a2e65b 100644 --- a/selfdrive/modeld/models/supercombo.dlc +++ b/selfdrive/modeld/models/supercombo.dlc @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:027cbb1fabae369878271cb0e3505071a8bdaa07473fad9a0b2e8d695c5dc1ff -size 76725611 +oid sha256:4c2cb3a3054f3292bbe538d6b793908dc2e234c200802d41b6766d3cb51b0b44 +size 101662751 diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index 9023c18dd7..0493398560 100644 --- a/selfdrive/modeld/models/supercombo.onnx +++ b/selfdrive/modeld/models/supercombo.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:484976ea5bd4ddcabc82e95faf30d7311a27802c1e337472558699fa2395a499 -size 77472267 +oid sha256:96b60d0bfd1386c93b4f79195aa1c5e77b23e0250578a308ee2c58857ed5eb49 +size 102570834 diff --git a/selfdrive/modeld/thneed/compile.cc b/selfdrive/modeld/thneed/compile.cc index f76c63b2b9..a2f55ffd97 100644 --- a/selfdrive/modeld/thneed/compile.cc +++ b/selfdrive/modeld/thneed/compile.cc @@ -5,7 +5,7 @@ #include "selfdrive/modeld/thneed/thneed.h" #include "system/hardware/hw.h" -#define TEMPORAL_SIZE 512 +#define TEMPORAL_SIZE 512+256 #define DESIRE_LEN 8 #define TRAFFIC_CONVENTION_LEN 2 diff --git a/selfdrive/modeld/thneed/optimizer.cc b/selfdrive/modeld/thneed/optimizer.cc index 03d20ff386..39737d3d76 100644 --- a/selfdrive/modeld/thneed/optimizer.cc +++ b/selfdrive/modeld/thneed/optimizer.cc @@ -9,7 +9,7 @@ extern map g_program_source; -static int is_same_size_image(cl_mem a, cl_mem b) { +/*static int is_same_size_image(cl_mem a, cl_mem b) { size_t a_width, a_height, a_depth, a_array_size, a_row_pitch, a_slice_pitch; clGetImageInfo(a, CL_IMAGE_WIDTH, sizeof(a_width), &a_width, NULL); clGetImageInfo(a, CL_IMAGE_HEIGHT, sizeof(a_height), &a_height, NULL); @@ -29,7 +29,7 @@ static int is_same_size_image(cl_mem a, cl_mem b) { return (a_width == b_width) && (a_height == b_height) && (a_depth == b_depth) && (a_array_size == b_array_size) && (a_row_pitch == b_row_pitch) && (a_slice_pitch == b_slice_pitch); -} +}*/ static cl_mem make_image_like(cl_context context, cl_mem val) { cl_image_format format; @@ -138,7 +138,7 @@ int Thneed::optimize() { // delete useless copy layers // saves ~0.7 ms - if (kq[i]->name == "concatenation" || kq[i]->name == "flatten") { + /*if (kq[i]->name == "concatenation" || kq[i]->name == "flatten") { string in = kq[i]->args[kq[i]->get_arg_num("input")]; string out = kq[i]->args[kq[i]->get_arg_num("output")]; if (is_same_size_image(*(cl_mem*)in.data(), *(cl_mem*)out.data())) { @@ -148,7 +148,7 @@ int Thneed::optimize() { kq.erase(kq.begin()+i); --i; } - } + }*/ // NOTE: if activations/accumulation are done in the wrong order, this will be wrong diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index a7a909d2a4..54c2ed54ad 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -512a9d4596c8faba304d6f7ded2ce77837357b65 +629eaa7b26d1721a71547f9de880f99732cb27f3 diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index b8976e5f38..8ed68d5bdd 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -1d66eed104dbc124c4e5679f5dddf40197b86ce9 +ed1dfb8b155ebcd8fdad4e06462b3bb7869fc67b From 725ccc01798c7f4b3278cc34525f99a6344e52aa Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 15 Jun 2022 18:01:02 -0700 Subject: [PATCH 061/302] HKG: simplify Kia K5 compatibility (#24810) LKAS/LFA is standard on the K5 --- docs/CARS.md | 2 +- selfdrive/car/hyundai/values.py | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 9b3322ac8e..c0bd62eb3f 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -95,7 +95,7 @@ How We Rate The Cars |Kia|Ceed 2019|SCC + LKAS|||||| |Kia|Forte 2018|SCC + LKAS|||||| |Kia|Forte 2019-21|SCC + LKAS|||||| -|Kia|K5 2021-22|SCC + LFA|||||| +|Kia|K5 2021-22|SCC|||||| |Kia|Niro Hybrid 2021|SCC + LKAS|||||| |Kia|Niro Hybrid 2022|SCC + LKAS|||||| |Kia|Optima 2019|SCC + LKAS|||||| diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 4ca81fdb40..df7ce1e6f4 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -80,6 +80,8 @@ class CAR: @dataclass class HyundaiCarInfo(CarInfo): + # TODO: we can probably remove LKAS. LKAS is standard on many + # HKG and for others, it's likely packaged together with SCC package: str = "SCC + LKAS" good_torque: bool = True @@ -121,7 +123,7 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { HyundaiCarInfo("Kia Forte 2018", harness=Harness.hyundai_b), HyundaiCarInfo("Kia Forte 2019-21", harness=Harness.hyundai_g), ], - CAR.KIA_K5_2021: HyundaiCarInfo("Kia K5 2021-22", "SCC + LFA", harness=Harness.hyundai_a), + CAR.KIA_K5_2021: HyundaiCarInfo("Kia K5 2021-22", "SCC", harness=Harness.hyundai_a), CAR.KIA_NIRO_EV: [ HyundaiCarInfo("Kia Niro Electric 2019-20", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_f), HyundaiCarInfo("Kia Niro Electric 2021", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_c), From e910ce87a44884a3f216fbced306e8d3124a04de Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 15 Jun 2022 21:42:54 -0700 Subject: [PATCH 062/302] thermald: fix panda dropout when we miss a pandaStates (#24870) immediate fix for "panda dropout" --- selfdrive/thermald/thermald.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index b909d1198c..6cf5c428a8 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -220,7 +220,7 @@ def thermald_thread(end_event, hw_queue): if TICI: fan_controller = TiciFanController() - elif (sec_since_boot() - sm.rcv_time['pandaStates']/1e9) > DISCONNECT_TIMEOUT: + elif (sec_since_boot() - sm.rcv_time['pandaStates']) > DISCONNECT_TIMEOUT: if onroad_conditions["ignition"]: onroad_conditions["ignition"] = False cloudlog.error("panda timed out onroad") From 76593b1da02cae7165aaa699fd7ea807558751b0 Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Wed, 15 Jun 2022 22:50:39 -0700 Subject: [PATCH 063/302] VW MQB: Populate stock ACC standstill flag (#24877) * VW MQB: Populate stock ACC standstill flag * it really do be like that sometimes --- selfdrive/car/volkswagen/carcontroller.py | 2 +- selfdrive/car/volkswagen/carstate.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py index aeb56c5d67..842eb6d139 100644 --- a/selfdrive/car/volkswagen/carcontroller.py +++ b/selfdrive/car/volkswagen/carcontroller.py @@ -93,7 +93,7 @@ class CarController(): # Cancel ACC if it's engaged with OP disengaged. self.graButtonStatesToSend = BUTTON_STATES.copy() self.graButtonStatesToSend["cancel"] = True - elif c.enabled and CS.esp_hold_confirmation: + elif c.enabled and CS.out.cruiseState.standstill: # Blip the Resume button if we're engaged at standstill. # FIXME: This is a naive implementation, improve with visiond or radar input. self.graButtonStatesToSend = BUTTON_STATES.copy() diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py index 4193030d87..9c4a111e4e 100644 --- a/selfdrive/car/volkswagen/carstate.py +++ b/selfdrive/car/volkswagen/carstate.py @@ -50,7 +50,6 @@ class CarState(CarStateBase): ret.brake = pt_cp.vl["ESP_05"]["ESP_Bremsdruck"] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects ret.brakePressed = bool(pt_cp.vl["ESP_05"]["ESP_Fahrer_bremst"]) ret.parkingBrake = bool(pt_cp.vl["Kombi_01"]["KBI_Handbremse"]) # FIXME: need to include an EPB check as well - self.esp_hold_confirmation = pt_cp.vl["ESP_21"]["ESP_Haltebestaetigung"] # Update gear and/or clutch position data. if trans_type == TransmissionType.automatic: @@ -105,6 +104,7 @@ class CarState(CarStateBase): # ACC okay but disabled (1), or a radar visibility or other fault/disruption (6 or 7) ret.cruiseState.available = False ret.cruiseState.enabled = False + ret.cruiseState.standstill = bool(pt_cp.vl["ESP_21"]["ESP_Haltebestaetigung"]) ret.accFaulted = pt_cp.vl["TSK_06"]["TSK_Status"] in (6, 7) # Update ACC setpoint. When the setpoint is zero or there's an error, the From 5aaf5be54c544a822483ad3e7c354fdb89cae45c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 16 Jun 2022 01:47:29 -0700 Subject: [PATCH 064/302] Mazda: fix resume spam at standstill (#24876) * Fix Mazda resume spam at standstill * one line * Revert "one line" This reverts commit 30c6504ed36adb92991acd6ebf42ffd6fe6c3b8c. --- selfdrive/car/mazda/carcontroller.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/mazda/carcontroller.py b/selfdrive/car/mazda/carcontroller.py index 68eebeaf71..d003079d63 100644 --- a/selfdrive/car/mazda/carcontroller.py +++ b/selfdrive/car/mazda/carcontroller.py @@ -27,6 +27,7 @@ class CarController(): CS.out.steeringTorque, CarControllerParams) self.steer_rate_limited = new_steer != apply_steer + if c.enabled: if CS.out.standstill and frame % 5 == 0: # Mazda Stop and Go requires a RES button (or gas) press if the car stops more than 3 seconds # Send Resume button at 20hz if we're engaged at standstill to support full stop and go! From 5958e78037e468795e0db8d42d5209e1e41aec18 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Thu, 16 Jun 2022 15:21:33 +0200 Subject: [PATCH 065/302] Laikad: More logging and use last_pos_fix for correcting (#24868) Use last available pos_fix for correcting measurements. Improve logging measurements --- cereal | 2 +- laika_repo | 2 +- selfdrive/locationd/laikad.py | 77 ++++++++++++++----------- selfdrive/locationd/test/test_laikad.py | 76 +++++++++++++++++------- 4 files changed, 100 insertions(+), 57 deletions(-) diff --git a/cereal b/cereal index 4b4d9aab03..3166178611 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 4b4d9aab03937f5a45677ff15efb275abf9c958b +Subproject commit 3166178611989ca555d7b254130375d1d8a55cc8 diff --git a/laika_repo b/laika_repo index a3a80dc4f7..951ab080b9 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit a3a80dc4f7977b2232946e56a16770e413190818 +Subproject commit 951ab080b998ee3edde6229654d1a4cb63cda6a9 diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 8eb81345ff..0e2838da6d 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -2,13 +2,13 @@ import json import time from concurrent.futures import Future, ProcessPoolExecutor +from enum import IntEnum from typing import List, Optional import numpy as np from collections import defaultdict import sympy -from numpy.linalg import linalg from cereal import log, messaging from common.params import Params, put_nonblocking @@ -30,7 +30,7 @@ CACHE_VERSION = 0.1 class Laikad: def __init__(self, valid_const=("GPS", "GLONASS"), auto_update=False, valid_ephem_types=(EphemerisType.ULTRA_RAPID_ORBIT, EphemerisType.NAV), - save_ephemeris=False): + save_ephemeris=False, last_known_position=None): self.astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types, clear_old_ephemeris=True) self.gnss_kf = GNSSKalman(GENERATED_DIR) self.orbit_fetch_executor = ProcessPoolExecutor() @@ -40,6 +40,7 @@ class Laikad: self.save_ephemeris = save_ephemeris self.load_cache() self.posfix_functions = {constellation: get_posfix_sympy_fun(constellation) for constellation in (ConstellationId.GPS, ConstellationId.GLONASS)} + self.last_pos_fix = last_known_position def load_cache(self): cache = Params().get(EPHEMERIS_CACHE) @@ -70,27 +71,16 @@ class Laikad: processed_measurements = process_measurements(new_meas, self.astro_dog) min_measurements = 5 if any(p.constellation_id == ConstellationId.GLONASS for p in processed_measurements) else 4 - pos_fix = calc_pos_fix_gauss_newton(processed_measurements, self.posfix_functions, min_measurements=min_measurements) + pos_fix, pos_fix_residual = calc_pos_fix_gauss_newton(processed_measurements, self.posfix_functions, min_measurements=min_measurements) + if len(pos_fix) > 0: + self.last_pos_fix = pos_fix[:3] + est_pos = self.last_pos_fix - t = ublox_mono_time * 1e-9 - kf_pos_std = None - if all(self.kf_valid(t)): - self.gnss_kf.predict(t) - kf_pos_std = np.sqrt(abs(self.gnss_kf.P[GStates.ECEF_POS].diagonal())) - # If localizer is valid use its position to correct measurements - if kf_pos_std is not None and linalg.norm(kf_pos_std) < 100: - est_pos = self.gnss_kf.x[GStates.ECEF_POS] - elif len(pos_fix) > 0 and abs(np.array(pos_fix[1])).mean() < 1000: - est_pos = pos_fix[0][:3] - else: - est_pos = None - corrected_measurements = [] - if est_pos is not None: - corrected_measurements = correct_measurements(processed_measurements, est_pos, self.astro_dog) + corrected_measurements = correct_measurements(processed_measurements, est_pos, self.astro_dog) if est_pos is not None else [] + t = ublox_mono_time * 1e-9 self.update_localizer(est_pos, t, corrected_measurements) kf_valid = all(self.kf_valid(t)) - ecef_pos = self.gnss_kf.x[GStates.ECEF_POS].tolist() ecef_vel = self.gnss_kf.x[GStates.ECEF_VELOCITY].tolist() @@ -103,6 +93,7 @@ class Laikad: dat.gnssMeasurements = { "positionECEF": measurement_msg(value=ecef_pos, std=pos_std, valid=kf_valid), "velocityECEF": measurement_msg(value=ecef_vel, std=vel_std, valid=kf_valid), + "positionFixECEF": measurement_msg(value=pos_fix, std=pos_fix_residual, valid=len(pos_fix) > 0), "ubloxMonoTime": ublox_mono_time, "correctedMeasurements": meas_msgs } @@ -124,13 +115,7 @@ class Laikad: cloudlog.error("Time gap of over 10s detected, gnss kalman reset") elif not valid[2]: cloudlog.error("Gnss kalman filter state is nan") - else: - cloudlog.error("Gnss kalman std too far") - - if est_pos is None: - cloudlog.info("Position fix not available when resetting kalman filter") - return - self.init_gnss_localizer(est_pos.tolist()) + self.init_gnss_localizer(est_pos) if len(measurements) > 0: kf_add_observations(self.gnss_kf, t, measurements) else: @@ -141,14 +126,13 @@ class Laikad: filter_time = self.gnss_kf.filter.filter_time return [filter_time is not None, filter_time is not None and abs(t - filter_time) < MAX_TIME_GAP, - all(np.isfinite(self.gnss_kf.x[GStates.ECEF_POS])), - linalg.norm(self.gnss_kf.P[GStates.ECEF_POS]) < 1e5] + all(np.isfinite(self.gnss_kf.x[GStates.ECEF_POS]))] def init_gnss_localizer(self, est_pos): x_initial, p_initial_diag = np.copy(GNSSKalman.x_initial), np.copy(np.diagonal(GNSSKalman.P_initial)) - x_initial[GStates.ECEF_POS] = est_pos + if est_pos is not None: + x_initial[GStates.ECEF_POS] = est_pos p_initial_diag[GStates.ECEF_POS] = 1000 ** 2 - self.gnss_kf.init_state(x_initial, covs_diag=p_initial_diag) def fetch_orbits(self, t: GPSTime, block): @@ -192,6 +176,27 @@ def create_measurement_msg(meas: GNSSMeasurement): c.pseudorangeRateStd = float(meas.observables_std['D1C']) c.satPos = meas.sat_pos_final.tolist() c.satVel = meas.sat_vel.tolist() + c.satVel = meas.sat_vel.tolist() + ephem = meas.sat_ephemeris + assert ephem is not None + if ephem.eph_type == EphemerisType.NAV: + source_type = EphemerisSourceType.nav + week, time_of_week = -1, -1 + else: + assert ephem.file_epoch is not None + week = ephem.file_epoch.week + time_of_week = ephem.file_epoch.tow + file_src = ephem.file_source + if file_src == 'igu': # example nasa: '2214/igu22144_00.sp3.Z' + source_type = EphemerisSourceType.nasaUltraRapid + elif file_src == 'Sta': # example nasa: '22166/ultra/Stark_1D_22061518.sp3' + source_type = EphemerisSourceType.glonassIacUltraRapid + else: + raise Exception(f"Didn't expect file source {file_src}") + + c.ephemerisSource.type = source_type.value + c.ephemerisSource.gpsWeek = week + c.ephemerisSource.gpsTimeOfWeek = time_of_week return c @@ -242,12 +247,12 @@ def calc_pos_fix_gauss_newton(measurements, posfix_functions, x0=None, signal='C x0 = [0, 0, 0, 0, 0] n = len(measurements) if n < min_measurements: - return [] + return [], [] Fx_pos = pr_residual(measurements, posfix_functions, signal=signal) x = gauss_newton(Fx_pos, x0) residual, _ = Fx_pos(x, weight=1.0) - return x, residual + return x.tolist(), residual.tolist() def pr_residual(measurements, posfix_functions, signal='C1C'): @@ -314,10 +319,16 @@ def get_posfix_sympy_fun(constellation): return sympy.lambdify([x, y, z, bc, bg, pr, sat_x, sat_y, sat_z, weight], res) +class EphemerisSourceType(IntEnum): + nav = 0 + nasaUltraRapid = 1 + glonassIacUltraRapid = 2 + + def main(): sm = messaging.SubMaster(['ubloxGnss']) pm = messaging.PubMaster(['gnssMeasurements']) - + # todo get last_known_position laikad = Laikad(save_ephemeris=True) while True: sm.update() diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py index 01ea8fee27..3a72303b0c 100755 --- a/selfdrive/locationd/test/test_laikad.py +++ b/selfdrive/locationd/test/test_laikad.py @@ -1,16 +1,17 @@ #!/usr/bin/env python3 import time import unittest +from collections import defaultdict from datetime import datetime from unittest import mock from unittest.mock import Mock, patch from common.params import Params -from laika.ephemeris import EphemerisType +from laika.ephemeris import EphemerisType, GPSEphemeris from laika.gps_time import GPSTime from laika.helpers import ConstellationId, TimeRangeHolder from laika.raw_gnss import GNSSMeasurement, read_raw_ublox -from selfdrive.locationd.laikad import EPHEMERIS_CACHE, Laikad, create_measurement_msg +from selfdrive.locationd.laikad import EPHEMERIS_CACHE, EphemerisSourceType, Laikad, create_measurement_msg from selfdrive.test.openpilotci import get_url from tools.lib.logreader import LogReader @@ -33,23 +34,62 @@ def verify_messages(lr, laikad, return_one_success=False): return good_msgs +def get_first_gps_time(logs): + for m in logs: + if m.ubloxGnss.which == 'measurementReport': + new_meas = read_raw_ublox(m.ubloxGnss.measurementReport) + if len(new_meas) > 0: + return new_meas[0].recv_time + + +def get_measurement_mock(gpstime, sat_ephemeris): + meas = GNSSMeasurement(ConstellationId.GPS, 1, gpstime.week, gpstime.tow, {'C1C': 0., 'D1C': 0.}, {'C1C': 0., 'D1C': 0.}) + # Fake measurement being processed + meas.observables_final = meas.observables + meas.sat_ephemeris = sat_ephemeris + return meas + + class TestLaikad(unittest.TestCase): @classmethod def setUpClass(cls): - cls.logs = get_log(range(1)) + logs = get_log(range(1)) + cls.logs = logs + first_gps_time = get_first_gps_time(logs) + cls.first_gps_time = first_gps_time def setUp(self): Params().delete(EPHEMERIS_CACHE) - def test_create_msg_without_errors(self): - gpstime = GPSTime.from_datetime(datetime.now()) - meas = GNSSMeasurement(ConstellationId.GPS, 1, gpstime.week, gpstime.tow, {'C1C': 0., 'D1C': 0.}, {'C1C': 0., 'D1C': 0.}) - # Fake observables_final to be correct - meas.observables_final = meas.observables + def test_ephemeris_source_in_msg(self): + data_mock = defaultdict(str) + data_mock['sv_id'] = 1 + + gpstime = GPSTime.from_datetime(datetime(2022, month=3, day=1)) + laikad = Laikad() + laikad.fetch_orbits(gpstime, block=True) + meas = get_measurement_mock(gpstime, laikad.astro_dog.orbits['R01'][0]) + msg = create_measurement_msg(meas) + self.assertEqual(msg.ephemerisSource.type.raw, EphemerisSourceType.glonassIacUltraRapid) + # Verify gps satellite returns same source + meas = get_measurement_mock(gpstime, laikad.astro_dog.orbits['R01'][0]) + msg = create_measurement_msg(meas) + self.assertEqual(msg.ephemerisSource.type.raw, EphemerisSourceType.glonassIacUltraRapid) + + # Test nasa source by using older date + gpstime = GPSTime.from_datetime(datetime(2021, month=3, day=1)) + laikad = Laikad() + laikad.fetch_orbits(gpstime, block=True) + meas = get_measurement_mock(gpstime, laikad.astro_dog.orbits['G01'][0]) msg = create_measurement_msg(meas) + self.assertEqual(msg.ephemerisSource.type.raw, EphemerisSourceType.nasaUltraRapid) - self.assertEqual(msg.constellationId, 'gps') + # Test nav source type + ephem = GPSEphemeris(data_mock, gpstime) + meas = get_measurement_mock(gpstime, ephem) + msg = create_measurement_msg(meas) + self.assertEqual(msg.ephemerisSource.type.raw, EphemerisSourceType.nav) def test_laika_online(self): laikad = Laikad(auto_update=True, valid_ephem_types=EphemerisType.ULTRA_RAPID_ORBIT) @@ -76,18 +116,10 @@ class TestLaikad(unittest.TestCase): self.assertEqual(256, len(correct_msgs)) self.assertEqual(256, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid])) - def get_first_gps_time(self): - for m in self.logs: - if m.ubloxGnss.which == 'measurementReport': - new_meas = read_raw_ublox(m.ubloxGnss.measurementReport) - if len(new_meas) != 0: - return new_meas[0].recv_time - def test_laika_get_orbits(self): laikad = Laikad(auto_update=False) - first_gps_time = self.get_first_gps_time() # Pretend process has loaded the orbits on startup by using the time of the first gps message. - laikad.fetch_orbits(first_gps_time, block=True) + laikad.fetch_orbits(self.first_gps_time, block=True) self.dict_has_values(laikad.astro_dog.orbits) @unittest.skip("Use to debug live data") @@ -117,7 +149,6 @@ class TestLaikad(unittest.TestCase): def test_cache(self): laikad = Laikad(auto_update=True, save_ephemeris=True) - first_gps_time = self.get_first_gps_time() def wait_for_cache(): max_time = 2 @@ -126,13 +157,14 @@ class TestLaikad(unittest.TestCase): max_time -= 0.1 if max_time == 0: self.fail("Cache has not been written after 2 seconds") + # Test cache with no ephemeris laikad.cache_ephemeris(t=GPSTime(0, 0)) wait_for_cache() Params().delete(EPHEMERIS_CACHE) - laikad.astro_dog.get_navs(first_gps_time) - laikad.fetch_orbits(first_gps_time, block=True) + laikad.astro_dog.get_navs(self.first_gps_time) + laikad.fetch_orbits(self.first_gps_time, block=True) # Wait for cache to save wait_for_cache() @@ -149,7 +181,7 @@ class TestLaikad(unittest.TestCase): with patch('selfdrive.locationd.laikad.get_orbit_data', return_value=None) as mock_method: # Verify no orbit downloads even if orbit fetch times is reset since the cache has recently been saved and we don't want to download high frequently laikad.astro_dog.orbit_fetched_times = TimeRangeHolder() - laikad.fetch_orbits(first_gps_time, block=False) + laikad.fetch_orbits(self.first_gps_time, block=False) mock_method.assert_not_called() # Verify cache is working for only orbits by running a segment From 2699bae778fa7d9a4d40cf169b1eb56c74cb22c8 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 16 Jun 2022 16:06:41 +0200 Subject: [PATCH 066/302] ui: disable controls unresponsive alert on PC --- selfdrive/ui/ui.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index 192a353ad1..cbf3921e4e 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -54,7 +54,7 @@ struct Alert { return {"openpilot Unavailable", "Waiting for controls to start", "controlsWaiting", cereal::ControlsState::AlertSize::MID, AudibleAlert::NONE}; - } else if (controls_missing > CONTROLS_TIMEOUT) { + } else if (controls_missing > CONTROLS_TIMEOUT && !Hardware::PC()) { // car is started, but controls is lagging or died if (cs.getEnabled() && (controls_missing - CONTROLS_TIMEOUT) < 10) { return {"TAKE CONTROL IMMEDIATELY", "Controls Unresponsive", From dc98511b7a7092e969237655b6e08e4fa857106d Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Thu, 16 Jun 2022 17:45:08 +0200 Subject: [PATCH 067/302] laikad: fixes to run on device (#24879) * Always run laikad on device! * Update laika * Update laika * Fix gps week and time of week in msg * Reset kalman filter if pos_fix or last_known_position * put behind file * move pr parsing into common file Co-authored-by: Willem Melching --- laika_repo | 2 +- release/files_common | 9 +- selfdrive/locationd/laikad.py | 103 +++------------------ selfdrive/locationd/laikad_helpers.py | 89 ++++++++++++++++++ selfdrive/locationd/models/gnss_helpers.py | 21 +++++ selfdrive/locationd/models/gnss_kf.py | 2 +- selfdrive/locationd/models/loc_kf.py | 25 +---- selfdrive/manager/process_config.py | 1 + 8 files changed, 135 insertions(+), 117 deletions(-) create mode 100644 selfdrive/locationd/laikad_helpers.py create mode 100644 selfdrive/locationd/models/gnss_helpers.py diff --git a/laika_repo b/laika_repo index 951ab080b9..44f048bc1f 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 951ab080b998ee3edde6229654d1a4cb63cda6a9 +Subproject commit 44f048bc1f58ae9e28dfdeb98e40aea3e0f2b699 diff --git a/release/files_common b/release/files_common index 6731ae4a12..b6cd4fa797 100644 --- a/release/files_common +++ b/release/files_common @@ -209,15 +209,20 @@ selfdrive/locationd/generated/ubx.h selfdrive/locationd/generated/gps.cpp selfdrive/locationd/generated/gps.h +selfdrive/locationd/laikad.py +selfdrive/locationd/laikad_helpers.py +selfdrive/locationd/locationd.cc selfdrive/locationd/locationd.h selfdrive/locationd/locationd.cc selfdrive/locationd/paramsd.py selfdrive/locationd/models/.gitignore -selfdrive/locationd/models/live_kf.py selfdrive/locationd/models/car_kf.py -selfdrive/locationd/models/constants.py +selfdrive/locationd/models/gnss_kf.py +selfdrive/locationd/models/live_kf.py selfdrive/locationd/models/live_kf.h selfdrive/locationd/models/live_kf.cc +selfdrive/locationd/models/constants.py +selfdrive/locationd/models/gnss_helpers.py selfdrive/locationd/calibrationd.py diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 0e2838da6d..8ec570e2be 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -1,23 +1,22 @@ #!/usr/bin/env python3 import json import time +from collections import defaultdict from concurrent.futures import Future, ProcessPoolExecutor from enum import IntEnum from typing import List, Optional import numpy as np -from collections import defaultdict - -import sympy from cereal import log, messaging from common.params import Params, put_nonblocking from laika import AstroDog -from laika.constants import EARTH_ROTATION_RATE, SECS_IN_HR, SECS_IN_MIN, SPEED_OF_LIGHT +from laika.constants import SECS_IN_HR, SECS_IN_MIN from laika.ephemeris import Ephemeris, EphemerisType, convert_ublox_ephem from laika.gps_time import GPSTime from laika.helpers import ConstellationId from laika.raw_gnss import GNSSMeasurement, correct_measurements, process_measurements, read_raw_ublox +from selfdrive.locationd.laikad_helpers import calc_pos_fix_gauss_newton, get_posfix_sympy_fun from selfdrive.locationd.models.constants import GENERATED_DIR, ObservationKind from selfdrive.locationd.models.gnss_kf import GNSSKalman from selfdrive.locationd.models.gnss_kf import States as GStates @@ -91,6 +90,8 @@ class Laikad: dat = messaging.new_message("gnssMeasurements") measurement_msg = log.LiveLocationKalman.Measurement.new_message dat.gnssMeasurements = { + "gpsWeek": report.gpsWeek, + "gpsTimeOfWeek": report.rcvTow, "positionECEF": measurement_msg(value=ecef_pos, std=pos_std, valid=kf_valid), "velocityECEF": measurement_msg(value=ecef_vel, std=vel_std, valid=kf_valid), "positionFixECEF": measurement_msg(value=pos_fix, std=pos_fix_residual, valid=len(pos_fix) > 0), @@ -115,7 +116,12 @@ class Laikad: cloudlog.error("Time gap of over 10s detected, gnss kalman reset") elif not valid[2]: cloudlog.error("Gnss kalman filter state is nan") - self.init_gnss_localizer(est_pos) + if est_pos is not None: + cloudlog.info(f"Reset kalman filter with {est_pos}") + self.init_gnss_localizer(est_pos) + else: + cloudlog.info("Could not reset kalman filter") + return if len(measurements) > 0: kf_add_observations(self.gnss_kf, t, measurements) else: @@ -130,8 +136,7 @@ class Laikad: def init_gnss_localizer(self, est_pos): x_initial, p_initial_diag = np.copy(GNSSKalman.x_initial), np.copy(np.diagonal(GNSSKalman.P_initial)) - if est_pos is not None: - x_initial[GStates.ECEF_POS] = est_pos + x_initial[GStates.ECEF_POS] = est_pos p_initial_diag[GStates.ECEF_POS] = 1000 ** 2 self.gnss_kf.init_state(x_initial, covs_diag=p_initial_diag) @@ -235,90 +240,6 @@ def deserialize_hook(dct): return dct -def calc_pos_fix_gauss_newton(measurements, posfix_functions, x0=None, signal='C1C', min_measurements=6): - ''' - Calculates gps fix using gauss newton method - To solve the problem a minimal of 4 measurements are required. - If Glonass is included 5 are required to solve for the additional free variable. - returns: - 0 -> list with positions - ''' - if x0 is None: - x0 = [0, 0, 0, 0, 0] - n = len(measurements) - if n < min_measurements: - return [], [] - - Fx_pos = pr_residual(measurements, posfix_functions, signal=signal) - x = gauss_newton(Fx_pos, x0) - residual, _ = Fx_pos(x, weight=1.0) - return x.tolist(), residual.tolist() - - -def pr_residual(measurements, posfix_functions, signal='C1C'): - def Fx_pos(inp, weight=None): - vals, gradients = [], [] - - for meas in measurements: - pr = meas.observables[signal] - pr += meas.sat_clock_err * SPEED_OF_LIGHT - - w = (1 / meas.observables_std[signal]) if weight is None else weight - - val, *gradient = posfix_functions[meas.constellation_id](*inp, pr, *meas.sat_pos, w) - vals.append(val) - gradients.append(gradient) - return np.asarray(vals), np.asarray(gradients) - - return Fx_pos - - -def gauss_newton(fun, b, xtol=1e-8, max_n=25): - for _ in range(max_n): - # Compute function and jacobian on current estimate - r, J = fun(b) - - # Update estimate - delta = np.linalg.pinv(J) @ r - b -= delta - - # Check step size for stopping condition - if np.linalg.norm(delta) < xtol: - break - return b - - -def get_posfix_sympy_fun(constellation): - # Unknowns - x, y, z = sympy.Symbol('x'), sympy.Symbol('y'), sympy.Symbol('z') - bc = sympy.Symbol('bc') - bg = sympy.Symbol('bg') - var = [x, y, z, bc, bg] - - # Knowns - pr = sympy.Symbol('pr') - sat_x, sat_y, sat_z = sympy.Symbol('sat_x'), sympy.Symbol('sat_y'), sympy.Symbol('sat_z') - weight = sympy.Symbol('weight') - - theta = EARTH_ROTATION_RATE * (pr - bc) / SPEED_OF_LIGHT - val = sympy.sqrt( - (sat_x * sympy.cos(theta) + sat_y * sympy.sin(theta) - x) ** 2 + - (sat_y * sympy.cos(theta) - sat_x * sympy.sin(theta) - y) ** 2 + - (sat_z - z) ** 2 - ) - - if constellation == ConstellationId.GLONASS: - res = weight * (val - (pr - bc - bg)) - elif constellation == ConstellationId.GPS: - res = weight * (val - (pr - bc)) - else: - raise NotImplementedError(f"Constellation {constellation} not supported") - - res = [res] + [sympy.diff(res, v) for v in var] - - return sympy.lambdify([x, y, z, bc, bg, pr, sat_x, sat_y, sat_z, weight], res) - - class EphemerisSourceType(IntEnum): nav = 0 nasaUltraRapid = 1 diff --git a/selfdrive/locationd/laikad_helpers.py b/selfdrive/locationd/laikad_helpers.py new file mode 100644 index 0000000000..81f5ac3dd6 --- /dev/null +++ b/selfdrive/locationd/laikad_helpers.py @@ -0,0 +1,89 @@ +import numpy as np +import sympy + +from laika.constants import EARTH_ROTATION_RATE, SPEED_OF_LIGHT +from laika.helpers import ConstellationId + + +def calc_pos_fix_gauss_newton(measurements, posfix_functions, x0=None, signal='C1C', min_measurements=6): + ''' + Calculates gps fix using gauss newton method + To solve the problem a minimal of 4 measurements are required. + If Glonass is included 5 are required to solve for the additional free variable. + returns: + 0 -> list with positions + ''' + if x0 is None: + x0 = [0, 0, 0, 0, 0] + n = len(measurements) + if n < min_measurements: + return [], [] + + Fx_pos = pr_residual(measurements, posfix_functions, signal=signal) + x = gauss_newton(Fx_pos, x0) + residual, _ = Fx_pos(x, weight=1.0) + return x.tolist(), residual.tolist() + + +def pr_residual(measurements, posfix_functions, signal='C1C'): + def Fx_pos(inp, weight=None): + vals, gradients = [], [] + + for meas in measurements: + pr = meas.observables[signal] + pr += meas.sat_clock_err * SPEED_OF_LIGHT + + w = (1 / meas.observables_std[signal]) if weight is None else weight + + val, *gradient = posfix_functions[meas.constellation_id](*inp, pr, *meas.sat_pos, w) + vals.append(val) + gradients.append(gradient) + return np.asarray(vals), np.asarray(gradients) + + return Fx_pos + + +def gauss_newton(fun, b, xtol=1e-8, max_n=25): + for _ in range(max_n): + # Compute function and jacobian on current estimate + r, J = fun(b) + + # Update estimate + delta = np.linalg.pinv(J) @ r + b -= delta + + # Check step size for stopping condition + if np.linalg.norm(delta) < xtol: + break + return b + + +def get_posfix_sympy_fun(constellation): + # Unknowns + x, y, z = sympy.Symbol('x'), sympy.Symbol('y'), sympy.Symbol('z') + bc = sympy.Symbol('bc') + bg = sympy.Symbol('bg') + var = [x, y, z, bc, bg] + + # Knowns + pr = sympy.Symbol('pr') + sat_x, sat_y, sat_z = sympy.Symbol('sat_x'), sympy.Symbol('sat_y'), sympy.Symbol('sat_z') + weight = sympy.Symbol('weight') + + theta = EARTH_ROTATION_RATE * (pr - bc) / SPEED_OF_LIGHT + val = sympy.sqrt( + (sat_x * sympy.cos(theta) + sat_y * sympy.sin(theta) - x) ** 2 + + (sat_y * sympy.cos(theta) - sat_x * sympy.sin(theta) - y) ** 2 + + (sat_z - z) ** 2 + ) + + if constellation == ConstellationId.GLONASS: + res = weight * (val - (pr - bc - bg)) + elif constellation == ConstellationId.GPS: + res = weight * (val - (pr - bc)) + else: + raise NotImplementedError(f"Constellation {constellation} not supported") + + res = [res] + [sympy.diff(res, v) for v in var] + + return sympy.lambdify([x, y, z, bc, bg, pr, sat_x, sat_y, sat_z, weight], res) diff --git a/selfdrive/locationd/models/gnss_helpers.py b/selfdrive/locationd/models/gnss_helpers.py new file mode 100644 index 0000000000..a3bcbc0002 --- /dev/null +++ b/selfdrive/locationd/models/gnss_helpers.py @@ -0,0 +1,21 @@ +import numpy as np + +def parse_prr(m): + from laika.raw_gnss import GNSSMeasurement + sat_pos_vel_i = np.concatenate((m[GNSSMeasurement.SAT_POS], + m[GNSSMeasurement.SAT_VEL])) + R_i = np.atleast_2d(m[GNSSMeasurement.PRR_STD]**2) + z_i = m[GNSSMeasurement.PRR] + return z_i, R_i, sat_pos_vel_i + + +def parse_pr(m): + from laika.raw_gnss import GNSSMeasurement + pseudorange = m[GNSSMeasurement.PR] + pseudorange_stdev = m[GNSSMeasurement.PR_STD] + sat_pos_freq_i = np.concatenate((m[GNSSMeasurement.SAT_POS], + np.array([m[GNSSMeasurement.GLONASS_FREQ]]))) + z_i = np.atleast_1d(pseudorange) + R_i = np.atleast_2d(pseudorange_stdev**2) + return z_i, R_i, sat_pos_freq_i + diff --git a/selfdrive/locationd/models/gnss_kf.py b/selfdrive/locationd/models/gnss_kf.py index 3f4baab7b5..ce0ff84dc2 100755 --- a/selfdrive/locationd/models/gnss_kf.py +++ b/selfdrive/locationd/models/gnss_kf.py @@ -7,7 +7,7 @@ import sympy as sp from rednose.helpers.ekf_sym import EKF_sym, gen_code from selfdrive.locationd.models.constants import ObservationKind -from selfdrive.locationd.models.loc_kf import parse_pr, parse_prr +from selfdrive.locationd.models.gnss_helpers import parse_pr, parse_prr class States(): diff --git a/selfdrive/locationd/models/loc_kf.py b/selfdrive/locationd/models/loc_kf.py index 8391426dd1..6b08828695 100755 --- a/selfdrive/locationd/models/loc_kf.py +++ b/selfdrive/locationd/models/loc_kf.py @@ -5,33 +5,14 @@ import sys import numpy as np import sympy as sp -from selfdrive.locationd.models.constants import ObservationKind from rednose.helpers.ekf_sym import EKF_sym, gen_code from rednose.helpers.lst_sq_computer import LstSqComputer from rednose.helpers.sympy_helpers import euler_rotate, quat_matrix_r, quat_rotate -EARTH_GM = 3.986005e14 # m^3/s^2 (gravitational constant * mass of earth) - - -def parse_prr(m): - from laika.raw_gnss import GNSSMeasurement - sat_pos_vel_i = np.concatenate((m[GNSSMeasurement.SAT_POS], - m[GNSSMeasurement.SAT_VEL])) - R_i = np.atleast_2d(m[GNSSMeasurement.PRR_STD]**2) - z_i = m[GNSSMeasurement.PRR] - return z_i, R_i, sat_pos_vel_i - - -def parse_pr(m): - from laika.raw_gnss import GNSSMeasurement - pseudorange = m[GNSSMeasurement.PR] - pseudorange_stdev = m[GNSSMeasurement.PR_STD] - sat_pos_freq_i = np.concatenate((m[GNSSMeasurement.SAT_POS], - np.array([m[GNSSMeasurement.GLONASS_FREQ]]))) - z_i = np.atleast_1d(pseudorange) - R_i = np.atleast_2d(pseudorange_stdev**2) - return z_i, R_i, sat_pos_freq_i +from selfdrive.locationd.models.constants import ObservationKind +from selfdrive.locationd.models.gnss_helpers import parse_pr, parse_prr +EARTH_GM = 3.986005e14 # m^3/s^2 (gravitational constant * mass of earth) class States(): ECEF_POS = slice(0, 3) # x, y and z in ECEF in meters diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index b3efe7e2de..a9a5c78a7f 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -57,6 +57,7 @@ procs = [ # Experimental PythonProcess("rawgpsd", "selfdrive.sensord.rawgps.rawgpsd", enabled=os.path.isfile("/persist/comma/use-quectel-rawgps")), + PythonProcess("laikad", "selfdrive.locationd.laikad", enabled=os.path.isfile("/persist/comma/use-laikad")), ] managed_processes = {p.name: p for p in procs} From 750daa6374e0f739b51df3e0fe4747407f023a73 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 16 Jun 2022 17:45:38 +0200 Subject: [PATCH 068/302] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 3166178611..6faf34064b 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 3166178611989ca555d7b254130375d1d8a55cc8 +Subproject commit 6faf34064b70ab98c241d4a1cd9006b09ecaadfc From a875afd5639d6e1ac24baa4de047cb8a2988a953 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 16 Jun 2022 18:18:03 +0200 Subject: [PATCH 069/302] navd: handle maxspeed being none (#24871) * navd: handle maxspeed being none * none is encoded like this --- selfdrive/navd/navd.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/selfdrive/navd/navd.py b/selfdrive/navd/navd.py index 509653a46d..f02de43c7b 100755 --- a/selfdrive/navd/navd.py +++ b/selfdrive/navd/navd.py @@ -143,8 +143,10 @@ class RouteEngine: coord = Coordinate.from_mapbox_tuple(c) # Last step does not have maxspeed - if (maxspeed_idx < len(maxspeeds)) and ('unknown' not in maxspeeds[maxspeed_idx]): - coord.annotations['maxspeed'] = maxspeed_to_ms(maxspeeds[maxspeed_idx]) + if (maxspeed_idx < len(maxspeeds)): + maxspeed = maxspeeds[maxspeed_idx] + if ('unknown' not in maxspeed) and ('none' not in maxspeed): + coord.annotations['maxspeed'] = maxspeed_to_ms(maxspeed) coords.append(coord) maxspeed_idx += 1 From d4886b2c2995db88d9bc9f7d7cf3f7cb9def5b12 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Thu, 16 Jun 2022 19:41:51 +0200 Subject: [PATCH 070/302] Cast gpstimeofweek to int --- selfdrive/locationd/laikad.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 8ec570e2be..6fd70875ac 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -201,7 +201,7 @@ def create_measurement_msg(meas: GNSSMeasurement): c.ephemerisSource.type = source_type.value c.ephemerisSource.gpsWeek = week - c.ephemerisSource.gpsTimeOfWeek = time_of_week + c.ephemerisSource.gpsTimeOfWeek = int(time_of_week) return c From b941b39c56db2d9d7f756cb0949ef6a7cf61774a Mon Sep 17 00:00:00 2001 From: grekiki <96022003+GregorKikelj@users.noreply.github.com> Date: Thu, 16 Jun 2022 19:47:53 +0200 Subject: [PATCH 071/302] More accurate jerk limits (#24755) * More accurate jerk limits * Min is not - max For example max_curvature_rate can be negative. * reduce diff --- selfdrive/controls/lib/drive_helpers.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index 1fecdd7c63..d79f94bbfd 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -122,7 +122,7 @@ def get_lag_adjusted_curvature(CP, v_ego, psis, curvatures, curvature_rates): # This is the "desired rate of the setpoint" not an actual desired rate desired_curvature_rate = curvature_rates[0] - max_curvature_rate = MAX_LATERAL_JERK / (v_ego**2) + max_curvature_rate = MAX_LATERAL_JERK / (v_ego**2) # inexact calculation, check https://github.com/commaai/openpilot/pull/24755 safe_desired_curvature_rate = clip(desired_curvature_rate, -max_curvature_rate, max_curvature_rate) From 88a80983a45e043e2d0fca2bc70c53beca256afe Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 16 Jun 2022 17:50:51 -0700 Subject: [PATCH 072/302] Chrysler: interface cleanup (#24884) * Chrysler: interface cleanup * little more --- selfdrive/car/chrysler/interface.py | 50 ++++++++++++++++++----------- selfdrive/car/chrysler/values.py | 3 ++ 2 files changed, 34 insertions(+), 19 deletions(-) diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 817a5b387e..8ebcb6b126 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -12,28 +12,38 @@ class CarInterface(CarInterfaceBase): ret.carName = "chrysler" ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.chrysler)] - # Speed conversion: 20, 45 mph - ret.wheelbase = 3.089 # in meters for Pacifica Hybrid 2017 - ret.steerRatio = 16.2 # Pacifica Hybrid 2017 - ret.mass = 2242. + STD_CARGO_KG # kg curb weight Pacifica Hybrid 2017 - ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] - ret.lateralTuning.pid.kf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594 ret.steerActuatorDelay = 0.1 ret.steerLimitTimer = 0.4 - if candidate in (CAR.JEEP_CHEROKEE, CAR.JEEP_CHEROKEE_2019): - ret.wheelbase = 2.91 # in meters - ret.steerRatio = 12.7 - ret.steerActuatorDelay = 0.2 # in seconds - - ret.centerToFront = ret.wheelbase * 0.44 - ret.minSteerSpeed = 3.8 # m/s if candidate in (CAR.PACIFICA_2019_HYBRID, CAR.PACIFICA_2020, CAR.JEEP_CHEROKEE_2019): - # TODO allow 2019 cars to steer down to 13 m/s if already engaged. + # TODO: allow 2019 cars to steer down to 13 m/s if already engaged. ret.minSteerSpeed = 17.5 # m/s 17 on the way up, 13 on the way down once engaged. + # Chrysler + if candidate in (CAR.PACIFICA_2017_HYBRID, CAR.PACIFICA_2018, CAR.PACIFICA_2018_HYBRID, CAR.PACIFICA_2019_HYBRID, CAR.PACIFICA_2020): + ret.mass = 2242. + STD_CARGO_KG + ret.wheelbase = 3.089 + ret.steerRatio = 16.2 # Pacifica Hybrid 2017 + ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] + ret.lateralTuning.pid.kf = 0.00006 + + # Jeep + elif candidate in (CAR.JEEP_CHEROKEE, CAR.JEEP_CHEROKEE_2019): + ret.mass = 1778 + STD_CARGO_KG + ret.wheelbase = 2.71 + ret.steerRatio = 16.7 + ret.steerActuatorDelay = 0.2 + ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] + ret.lateralTuning.pid.kf = 0.00006 + + else: + raise ValueError(f"Unsupported car: {candidate}") + + ret.centerToFront = ret.wheelbase * 0.44 + # starting with reasonable value for civic and scaling by mass and wheelbase ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) @@ -45,7 +55,6 @@ class CarInterface(CarInterfaceBase): return ret - # returns a car.CarState def _update(self, c): ret = self.CS.update(self.cp, self.cp_cam) @@ -54,14 +63,17 @@ class CarInterface(CarInterfaceBase): # events events = self.create_common_events(ret, extra_gears=[car.CarState.GearShifter.low]) - if ret.vEgo < self.CP.minSteerSpeed: + # Low speed steer alert hysteresis logic + if self.CP.minSteerSpeed > 0. and ret.vEgo < (self.CP.minSteerSpeed + 1.): + self.low_speed_alert = True + elif ret.vEgo > (self.CP.minSteerSpeed + 2.): + self.low_speed_alert = False + if self.low_speed_alert: events.add(car.CarEvent.EventName.belowSteerSpeed) ret.events = events.to_msg() return ret - # pass in a car.CarControl - # to be called @ 100hz def apply(self, c): return self.CC.update(c, self.CS) diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index b2757aafc2..a0d4225d9a 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -16,11 +16,14 @@ class CarControllerParams: class CAR: + # Chrysler PACIFICA_2017_HYBRID = "CHRYSLER PACIFICA HYBRID 2017" PACIFICA_2018_HYBRID = "CHRYSLER PACIFICA HYBRID 2018" PACIFICA_2019_HYBRID = "CHRYSLER PACIFICA HYBRID 2019" PACIFICA_2018 = "CHRYSLER PACIFICA 2018" # includes 2017 Pacifica PACIFICA_2020 = "CHRYSLER PACIFICA 2020" + + # Jeep JEEP_CHEROKEE = "JEEP GRAND CHEROKEE V6 2018" # includes 2017 Trailhawk JEEP_CHEROKEE_2019 = "JEEP GRAND CHEROKEE 2019" # includes 2020 Trailhawk From b85547ccf068d40f57dda467757301b069db0c80 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 16 Jun 2022 18:14:25 -0700 Subject: [PATCH 073/302] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index 42772b49e3..6c1738814b 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 42772b49e313688f8f96114806a72784f978e990 +Subproject commit 6c1738814b451d23797ab7d8fddd43c3b5296b45 From 6c02e554e7174745c7605f4e8f0e3c1aea637091 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 16 Jun 2022 20:23:25 -0700 Subject: [PATCH 074/302] VW FPv2: reduce number of ECU queries (#24706) * only send valid/needed queries * just do volkswagen * clean up * add parameter name clean up * add test for whitelist * rename * Update selfdrive/car/fw_versions.py Co-authored-by: Jason Young <46612682+jyoung8607@users.noreply.github.com> * fix test * log response addresses * bump cereal * handle response pending with IsoTpParallelQuery * remove response pending stuff * temporarily disregard cache for easier testing * revert this Co-authored-by: Jason Young <46612682+jyoung8607@users.noreply.github.com> --- selfdrive/car/fw_versions.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index c7253d794d..81883cecaa 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -146,12 +146,14 @@ REQUESTS: List[Request] = [ "volkswagen", [VOLKSWAGEN_VERSION_REQUEST_MULTI], [VOLKSWAGEN_VERSION_RESPONSE], + whitelist_ecus=[Ecu.srs, Ecu.eps, Ecu.fwdRadar], rx_offset=VOLKSWAGEN_RX_OFFSET, ), Request( "volkswagen", [VOLKSWAGEN_VERSION_REQUEST_MULTI], [VOLKSWAGEN_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.transmission], ), # Mazda Request( From 1b0167ce24afb037b36464c40f9c5e0d657e77d9 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 16 Jun 2022 22:34:07 -0700 Subject: [PATCH 075/302] Chrysler: use universal gas and brake signals (#24886) * Chrysler_Update * Update signal names * bump panda * bump submodules * bump panda to master Co-authored-by: Jonathan --- opendbc | 2 +- panda | 2 +- selfdrive/car/chrysler/carstate.py | 15 +++++++++------ 3 files changed, 11 insertions(+), 8 deletions(-) diff --git a/opendbc b/opendbc index a7b391cce8..5e2a820268 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit a7b391cce88908824f1417f0c7abd35e3ae16f96 +Subproject commit 5e2a82026842a7082e5e81e5823dab6b6616dbf4 diff --git a/panda b/panda index 6c1738814b..515df2bb72 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 6c1738814b451d23797ab7d8fddd43c3b5296b45 +Subproject commit 515df2bb727fe616869e5d460817e8898792e44f diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index 8ddf1c8684..e3ee4753cc 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -24,9 +24,12 @@ class CarState(CarStateBase): cp.vl["DOORS"]["DOOR_OPEN_RR"]]) ret.seatbeltUnlatched = cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_UNLATCHED"] == 1 - ret.brakePressed = cp.vl["BRAKE_2"]["BRAKE_PRESSED_2"] == 5 # human-only + # brake pedal ret.brake = 0 - ret.gas = cp.vl["ACCEL_GAS_134"]["ACCEL_134"] + ret.brakePressed = cp.vl["ESP_1"]['Brake_Pedal_State'] == 1 # Physical brake pedal switch + + # gas pedal + ret.gas = cp.vl["ECM_5"]["Accelerator_Position"] ret.gasPressed = ret.gas > 1e-5 ret.espDisabled = (cp.vl["TRACTION_BUTTON"]["TRACTION_OFF"] == 1) @@ -83,8 +86,8 @@ class CarState(CarStateBase): ("DOOR_OPEN_FR", "DOORS"), ("DOOR_OPEN_RL", "DOORS"), ("DOOR_OPEN_RR", "DOORS"), - ("BRAKE_PRESSED_2", "BRAKE_2"), - ("ACCEL_134", "ACCEL_GAS_134"), + ("Brake_Pedal_State", "ESP_1"), + ("Accelerator_Position", "ECM_5"), ("SPEED_LEFT", "SPEED_1"), ("SPEED_RIGHT", "SPEED_1"), ("WHEEL_SPEED_FL", "WHEEL_SPEEDS"), @@ -110,14 +113,14 @@ class CarState(CarStateBase): checks = [ # sig_address, frequency - ("BRAKE_2", 50), + ("ESP_1", 50), ("EPS_STATUS", 100), ("SPEED_1", 100), ("WHEEL_SPEEDS", 50), ("STEERING", 100), ("ACC_2", 50), ("GEAR", 50), - ("ACCEL_GAS_134", 50), + ("ECM_5", 50), ("WHEEL_BUTTONS", 50), ("DASHBOARD", 15), ("STEERING_LEVERS", 10), From 5dce006a82879f133ab69355b6c9b8c74d2b4d33 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 16 Jun 2022 22:41:13 -0700 Subject: [PATCH 076/302] regen: send wideRoadCameraState (#24863) * fix camera malfunction * revert * send in one process to fix frames out of sync * not used * revert * fix and add --no-upload for CI testing * fingerprint if source is fw * no FW versions --- .../test/process_replay/process_replay.py | 3 +-- selfdrive/test/process_replay/regen.py | 22 ++++++++++--------- selfdrive/test/process_replay/regen_all.py | 9 ++++---- 3 files changed, 18 insertions(+), 16 deletions(-) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index b016eb1c9f..c368e6b575 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -15,7 +15,6 @@ from cereal.services import service_list from common.params import Params from common.timeout import Timeout from panda.python import ALTERNATIVE_EXPERIENCE -from selfdrive.car.fingerprints import FW_VERSIONS from selfdrive.car.car_helpers import get_car, interfaces from selfdrive.test.process_replay.helpers import OpenpilotPrefix from selfdrive.manager.process import PythonProcess @@ -372,7 +371,7 @@ def setup_env(simulation=False, CP=None): if CP.alternativeExperience == ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS: params.put_bool("DisengageOnAccelerator", False) - if CP.fingerprintSource == "fw" and CP.carFingerprint in FW_VERSIONS: + if CP.fingerprintSource == "fw": params.put("CarParamsCache", CP.as_builder().to_bytes()) else: os.environ['SKIP_FW_QUERY'] = "1" diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py index dfc62a4558..d2f239c249 100755 --- a/selfdrive/test/process_replay/regen.py +++ b/selfdrive/test/process_replay/regen.py @@ -127,7 +127,10 @@ def replay_cameras(lr, frs, disable_tqdm=False): ] def replay_camera(s, stream, dt, vipc_server, frames, size, use_extra_client): - pm = messaging.PubMaster([s, ]) + services = [(s, stream)] + if use_extra_client: + services.append(("wideRoadCameraState", VisionStreamType.VISION_STREAM_WIDE_ROAD)) + pm = messaging.PubMaster([s for s, _ in services]) rk = Ratekeeper(1 / dt, print_delay_threshold=None) img = b"\x00" * int(size[0] * size[1] * 3 / 2) @@ -137,16 +140,15 @@ def replay_cameras(lr, frs, disable_tqdm=False): rk.keep_time() - m = messaging.new_message(s) - msg = getattr(m, s) - msg.frameId = rk.frame - msg.timestampSof = m.logMonoTime - msg.timestampEof = m.logMonoTime - pm.send(s, m) + for s, stream in services: + m = messaging.new_message(s) + msg = getattr(m, s) + msg.frameId = rk.frame + msg.timestampSof = m.logMonoTime + msg.timestampEof = m.logMonoTime + pm.send(s, m) - vipc_server.send(stream, img, msg.frameId, msg.timestampSof, msg.timestampEof) - if use_extra_client: - vipc_server.send(VisionStreamType.VISION_STREAM_WIDE_ROAD, img, msg.frameId, msg.timestampSof, msg.timestampEof) + vipc_server.send(stream, img, msg.frameId, msg.timestampSof, msg.timestampEof) init_data = [m for m in lr if m.which() == 'initData'][0] cameras = tici_cameras if (init_data.initData.deviceType == 'tici') else eon_cameras diff --git a/selfdrive/test/process_replay/regen_all.py b/selfdrive/test/process_replay/regen_all.py index c3ea1d41e1..f10d7ea03a 100755 --- a/selfdrive/test/process_replay/regen_all.py +++ b/selfdrive/test/process_replay/regen_all.py @@ -11,12 +11,12 @@ from selfdrive.test.process_replay.test_processes import FAKEDATA, original_segm from tools.lib.route import SegmentName -def regen_job(segment, disable_tqdm): +def regen_job(segment, upload, disable_tqdm): with OpenpilotPrefix(): sn = SegmentName(segment[1]) fake_dongle_id = 'regen' + ''.join(random.choice('0123456789ABCDEF') for _ in range(11)) try: - relr = regen_and_save(sn.route_name.canonical_name, sn.segment_num, upload=True, use_route_meta=False, outdir=os.path.join(FAKEDATA, fake_dongle_id), disable_tqdm=disable_tqdm) + relr = regen_and_save(sn.route_name.canonical_name, sn.segment_num, upload=upload, use_route_meta=False, outdir=os.path.join(FAKEDATA, fake_dongle_id), disable_tqdm=disable_tqdm) relr = '|'.join(relr.split('/')[-2:]) return f' ("{segment[0]}", "{relr}"), ' except Exception as e: @@ -26,12 +26,13 @@ def regen_job(segment, disable_tqdm): if __name__ == "__main__": parser = argparse.ArgumentParser(description="Generate new segments from old ones") parser.add_argument("-j", "--jobs", type=int, default=1) + parser.add_argument("--no-upload", action="store_true") args = parser.parse_args() with concurrent.futures.ProcessPoolExecutor(max_workers=args.jobs) as pool: - p = list(pool.map(regen_job, segments, [args.jobs > 1] * args.jobs)) + p = pool.map(regen_job, segments, [not args.no_upload] * len(segments), [args.jobs > 1] * len(segments)) msg = "Copy these new segments into test_processes.py:" - for seg in tqdm(p, desc="Generating segments"): + for seg in tqdm(p, desc="Generating segments", total=len(segments)): msg += "\n" + str(seg) print() print() From cd87772e036acde3b7b74857f8c03e87f3af63c1 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 17 Jun 2022 11:43:40 +0200 Subject: [PATCH 077/302] live_cpu_and_temp: handle duplicate proc names --- selfdrive/debug/live_cpu_and_temp.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/selfdrive/debug/live_cpu_and_temp.py b/selfdrive/debug/live_cpu_and_temp.py index baeebb1c4c..c35afc474b 100755 --- a/selfdrive/debug/live_cpu_and_temp.py +++ b/selfdrive/debug/live_cpu_and_temp.py @@ -1,10 +1,11 @@ #!/usr/bin/env python3 import argparse import capnp +from collections import defaultdict from cereal.messaging import SubMaster from common.numpy_fast import mean -from typing import Optional +from typing import Optional, Dict def cputime_total(ct): return ct.user + ct.nice + ct.system + ct.idle + ct.iowait + ct.irq + ct.softirq @@ -75,7 +76,7 @@ if __name__ == "__main__": print(f"CPU {100.0 * mean(cores):.2f}% - RAM: {last_mem:.2f}% - Temp {last_temp:.2f}C") if args.cpu and prev_proclog is not None and prev_proclog_t is not None: - procs = {} + procs: Dict[str, float] = defaultdict(float) dt = (sm.logMonoTime['procLog'] - prev_proclog_t) / 1e9 for proc in m.procs: try: @@ -83,12 +84,12 @@ if __name__ == "__main__": prev_proc = [p for p in prev_proclog.procs if proc.pid == p.pid][0] cpu_time = proc_cputime_total(proc) - proc_cputime_total(prev_proc) cpu_usage = cpu_time / dt * 100. - procs[name] = cpu_usage + procs[name] += cpu_usage except IndexError: pass print("Top CPU usage:") - for k, v in sorted(procs.items(), key=lambda item: item[1], reverse=True)[:10]: # type: ignore + for k, v in sorted(procs.items(), key=lambda item: item[1], reverse=True)[:10]: print(f"{k.rjust(70)} {v:.2f} %") print() From 7c826b4fa1ff5d4a22da4a9643ecef803c0b7536 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 17 Jun 2022 02:56:04 -0700 Subject: [PATCH 078/302] add param to override carParams.dashcamOnly (#24857) * add param to override carParams.dashcamOnly * little cleaner --- common/params.cc | 1 + selfdrive/car/hyundai/interface.py | 5 +---- selfdrive/controls/controlsd.py | 3 +++ 3 files changed, 5 insertions(+), 4 deletions(-) diff --git a/common/params.cc b/common/params.cc index 8cf1baa6c8..b8526bc231 100644 --- a/common/params.cc +++ b/common/params.cc @@ -94,6 +94,7 @@ std::unordered_map keys = { {"CompletedTrainingVersion", PERSISTENT}, {"ControlsReady", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"CurrentRoute", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, + {"DashcamOverride", PERSISTENT}, {"DisableLogging", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"DisablePowerDown", PERSISTENT}, {"DisableRadar_Allow", PERSISTENT}, diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 497d6b3f30..2739ebd8cc 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -1,5 +1,4 @@ #!/usr/bin/env python3 -import os from cereal import car from panda import Panda from common.conversions import Conversions as CV @@ -38,9 +37,7 @@ class CarInterface(CarInterfaceBase): # These cars have been put into dashcam only due to both a lack of users and test coverage. # These cars likely still work fine. Once a user confirms each car works and a test route is # added to selfdrive/car/tests/routes.py, we can remove it from this list. - ret.dashcamOnly = candidate in {CAR.KIA_OPTIMA_H, CAR.ELANTRA_GT_I30} - if candidate in HDA2_CAR: - ret.dashcamOnly = not os.path.exists('/data/enable-ev6') + ret.dashcamOnly = candidate in {CAR.KIA_OPTIMA_H, CAR.ELANTRA_GT_I30} or candidate in HDA2_CAR ret.steerActuatorDelay = 0.1 # Default delay ret.steerLimitTimer = 0.4 diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 033072aa73..67eaf1588b 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -104,6 +104,9 @@ class Controls: if not self.disengage_on_accelerator: self.CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS + if self.CP.dashcamOnly and params.get_bool("DashcamOverride"): + self.CP.dashcamOnly = False + # read params self.is_metric = params.get_bool("IsMetric") self.is_ldw_enabled = params.get_bool("IsLdwEnabled") From b701ea33ce0f36b78c703429afeb5d3d94d38105 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 17 Jun 2022 16:27:05 +0200 Subject: [PATCH 079/302] replay: no HW decoder, fix UV stride --- selfdrive/ui/replay/framereader.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/replay/framereader.cc b/selfdrive/ui/replay/framereader.cc index 8453407ce7..38d98bddc5 100644 --- a/selfdrive/ui/replay/framereader.cc +++ b/selfdrive/ui/replay/framereader.cc @@ -242,7 +242,7 @@ bool FrameReader::copyBuffers(AVFrame *f, uint8_t *yuv) { f->data[1], f->linesize[1], f->data[2], f->linesize[2], y, width, - uv, width / 2, + uv, width, width, height); } return true; From 2c877ce4907657d59111d5e850afb587b3be8d6e Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Fri, 17 Jun 2022 10:35:24 -0700 Subject: [PATCH 080/302] Long e2e planner: better xva weights (#24893) better long xva weights --- selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index bc0fc9fea6..94efd7a875 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -251,7 +251,7 @@ class LongitudinalMpc: self.solver.cost_set(i, 'Zl', Zl) def set_weights_for_xva_policy(self): - W = np.asfortranarray(np.diag([0., 10., 1., 10., 0.0, 1.])) + W = np.asfortranarray(np.diag([0., 0.2, 0.25, 1., 0.0, .1])) for i in range(N): self.solver.cost_set(i, 'W', W) # Setting the slice without the copy make the array not contiguous, From 33eaebfab2387ed92ef3fc69e3c610f27ee3db67 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 17 Jun 2022 19:47:37 +0200 Subject: [PATCH 081/302] ui: show empty box when speed limit is unavailable during nav (#24891) * ui: show empty box when speed limit is unavailable during nav * variant 2, long - --- selfdrive/ui/qt/onroad.cc | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 38541ef2d5..84b538411b 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -186,8 +186,8 @@ void NvgWindow::updateState(const UIState &s) { speed_limit *= (s.scene.is_metric ? MS_TO_KPH : MS_TO_MPH); setProperty("speedLimit", speed_limit); - setProperty("has_us_speed_limit", speed_limit > 1 && speed_limit_sign == cereal::NavInstruction::SpeedLimitSign::MUTCD); - setProperty("has_eu_speed_limit", speed_limit > 1 && speed_limit_sign == cereal::NavInstruction::SpeedLimitSign::VIENNA); + setProperty("has_us_speed_limit", sm["navInstruction"].getValid() && speed_limit_sign == cereal::NavInstruction::SpeedLimitSign::MUTCD); + setProperty("has_eu_speed_limit", sm["navInstruction"].getValid() && speed_limit_sign == cereal::NavInstruction::SpeedLimitSign::VIENNA); setProperty("is_cruise_set", cruise_set); setProperty("speed", cur_speed); @@ -212,7 +212,7 @@ void NvgWindow::drawHud(QPainter &p) { bg.setColorAt(1, QColor::fromRgbF(0, 0, 0, 0)); p.fillRect(0, 0, width(), header_h, bg); - QString speedLimitStr = QString::number(std::nearbyint(speedLimit)); + QString speedLimitStr = (speedLimit > 1) ? QString::number(std::nearbyint(speedLimit)) : "–"; QString speedStr = QString::number(std::nearbyint(speed)); QString setSpeedStr = is_cruise_set ? QString::number(std::nearbyint(setSpeed)) : "–"; @@ -334,6 +334,8 @@ void NvgWindow::drawHud(QPainter &p) { p.drawEllipse(center, inner_radius_2, inner_radius_2); // Speed limit value + if (speedLimit < 1 ) center -= {0, 2}; // Make sure dash is centered if no speed limit available + int font_size = (speedLimitStr.size() >= 3) ? 62 : 70; configFont(p, "Open Sans", font_size, "Bold"); QRect speed_limit_rect = getTextRect(p, Qt::AlignCenter, speedLimitStr); From 208d4a4fc73cf3f41111de67a168b4ef83156e6d Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 17 Jun 2022 13:39:15 -0700 Subject: [PATCH 082/302] Add Hyundai P harness (#24872) * Update docs_definitions.py * Update values.py --- selfdrive/car/docs_definitions.py | 1 + selfdrive/car/hyundai/values.py | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index f09dad7860..e1344174ab 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -144,6 +144,7 @@ class Harness(Enum): hyundai_m = "Hyundai M" hyundai_n = "Hyundai N" hyundai_o = "Hyundai O" + hyundai_p = "Hyundai P" custom = "Developer" obd_ii = "OBD-II" nissan_a = "Nissan A" diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index df7ce1e6f4..cf47501588 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -146,7 +146,7 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { ], CAR.KIA_STINGER: HyundaiCarInfo("Kia Stinger 2018", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", harness=Harness.hyundai_c), CAR.KIA_CEED: HyundaiCarInfo("Kia Ceed 2019", harness=Harness.hyundai_e), - CAR.KIA_EV6: HyundaiCarInfo("Kia EV6 2022", "All", harness=Harness.none), + CAR.KIA_EV6: HyundaiCarInfo("Kia EV6 2022", "All", harness=Harness.hyundai_p), # Genesis CAR.GENESIS_G70: HyundaiCarInfo("Genesis G70 2018", "All", harness=Harness.hyundai_f), From 0f0b4cac893b41dd81288947158d3aa9cbbfc2fd Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Sat, 18 Jun 2022 17:15:45 -0700 Subject: [PATCH 083/302] Chrysler: use unified signal definitions (#24895) * Update some signals to unified names and definitions Co-authored-by: Jonathan * steering looks good * Fix cp signals * Do steering signal changes separately * bump opendbc to master Co-authored-by: Jonathan --- opendbc | 2 +- selfdrive/car/chrysler/carstate.py | 31 +++++++++++++++--------------- 2 files changed, 17 insertions(+), 16 deletions(-) diff --git a/opendbc b/opendbc index 5e2a820268..57c8340a18 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 5e2a82026842a7082e5e81e5823dab6b6616dbf4 +Subproject commit 57c8340a180dd8c75139b18050eb17c72c9cb6e4 diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index e3ee4753cc..7571286c56 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -18,10 +18,10 @@ class CarState(CarStateBase): self.frame = int(cp.vl["EPS_STATUS"]["COUNTER"]) - ret.doorOpen = any([cp.vl["DOORS"]["DOOR_OPEN_FL"], - cp.vl["DOORS"]["DOOR_OPEN_FR"], - cp.vl["DOORS"]["DOOR_OPEN_RL"], - cp.vl["DOORS"]["DOOR_OPEN_RR"]]) + ret.doorOpen = any([cp.vl["BCM_1"]["Driver_Door_Ajar"], + cp.vl["BCM_1"]["Passenger_Door_Ajar"], + cp.vl["BCM_1"]["Left_Rear_Door_Ajar"], + cp.vl["BCM_1"]["Right_Rear_Door_Ajar"]]) ret.seatbeltUnlatched = cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_UNLATCHED"] == 1 # brake pedal @@ -51,12 +51,12 @@ class CarState(CarStateBase): ret.steeringRateDeg = cp.vl["STEERING"]["STEERING_RATE"] ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["GEAR"]["PRNDL"], None)) - ret.cruiseState.enabled = cp.vl["ACC_2"]["ACC_STATUS_2"] == 7 # ACC is green. - ret.cruiseState.available = ret.cruiseState.enabled # FIXME: for now same as enabled + ret.cruiseState.available = cp.vl["DAS_3"]["ACC_Engaged"] == 1 # ACC is white + ret.cruiseState.enabled = cp.vl["DAS_3"]["ACC_Enabled"] == 1 # ACC is green ret.cruiseState.speed = cp.vl["DASHBOARD"]["ACC_SPEED_CONFIG_KPH"] * CV.KPH_TO_MS # CRUISE_STATE is a three bit msg, 0 is off, 1 and 2 are Non-ACC mode, 3 and 4 are ACC mode, find if there are other states too ret.cruiseState.nonAdaptive = cp.vl["DASHBOARD"]["CRUISE_STATE"] in (1, 2) - ret.accFaulted = cp.vl["ACC_2"]["ACC_FAULTED"] != 0 + ret.accFaulted = cp.vl["DAS_3"]["ACC_Faulted"] != 0 ret.steeringTorque = cp.vl["EPS_STATUS"]["TORQUE_DRIVER"] ret.steeringTorqueEps = cp.vl["EPS_STATUS"]["TORQUE_MOTOR"] @@ -82,10 +82,10 @@ class CarState(CarStateBase): signals = [ # sig_name, sig_address ("PRNDL", "GEAR"), - ("DOOR_OPEN_FL", "DOORS"), - ("DOOR_OPEN_FR", "DOORS"), - ("DOOR_OPEN_RL", "DOORS"), - ("DOOR_OPEN_RR", "DOORS"), + ("Driver_Door_Ajar", "BCM_1"), + ("Passenger_Door_Ajar", "BCM_1"), + ("Left_Rear_Door_Ajar", "BCM_1"), + ("Right_Rear_Door_Ajar", "BCM_1"), ("Brake_Pedal_State", "ESP_1"), ("Accelerator_Position", "ECM_5"), ("SPEED_LEFT", "SPEED_1"), @@ -97,8 +97,9 @@ class CarState(CarStateBase): ("STEER_ANGLE", "STEERING"), ("STEERING_RATE", "STEERING"), ("TURN_SIGNALS", "STEERING_LEVERS"), - ("ACC_STATUS_2", "ACC_2"), - ("ACC_FAULTED", "ACC_2"), + ("ACC_Enabled", "DAS_3"), + ("ACC_Engaged", "DAS_3"), + ("ACC_Faulted", "DAS_3"), ("HIGH_BEAM_FLASH", "STEERING_LEVERS"), ("ACC_SPEED_CONFIG_KPH", "DASHBOARD"), ("CRUISE_STATE", "DASHBOARD"), @@ -118,14 +119,14 @@ class CarState(CarStateBase): ("SPEED_1", 100), ("WHEEL_SPEEDS", 50), ("STEERING", 100), - ("ACC_2", 50), + ("DAS_3", 50), ("GEAR", 50), ("ECM_5", 50), ("WHEEL_BUTTONS", 50), ("DASHBOARD", 15), ("STEERING_LEVERS", 10), ("SEATBELT_STATUS", 2), - ("DOORS", 1), + ("BCM_1", 1), ("TRACTION_BUTTON", 1), ] From add335d9e67f24a3090e09d39d4267b8f5620ff1 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 18 Jun 2022 19:01:42 -0700 Subject: [PATCH 084/302] jenkins: move simulator build into lock --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index ebc26a5920..279716d7cf 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -88,8 +88,8 @@ pipeline { steps { sh "git config --global --add safe.directory ${WORKSPACE}" sh "git lfs pull" - sh "${WORKSPACE}/tools/sim/build_container.sh" lock(resource: "", label: "simulator", inversePrecedence: true, quantity: 1) { + sh "${WORKSPACE}/tools/sim/build_container.sh" sh "DETACH=1 ${WORKSPACE}/tools/sim/start_carla.sh" sh "${WORKSPACE}/tools/sim/start_openpilot_docker.sh" } From a27d242e3d35cb76761b0cd14eb0d58e668cfbb9 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 18 Jun 2022 19:02:09 -0700 Subject: [PATCH 085/302] zookeeper: add avg power to power_monitor.py --- tools/zookeeper/power_monitor.py | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/tools/zookeeper/power_monitor.py b/tools/zookeeper/power_monitor.py index d3bdd6679f..f88741813e 100755 --- a/tools/zookeeper/power_monitor.py +++ b/tools/zookeeper/power_monitor.py @@ -1,6 +1,7 @@ #!/usr/bin/env python3 import sys import time +import datetime from common.realtime import Ratekeeper from common.filter_simple import FirstOrderFilter @@ -19,12 +20,19 @@ if __name__ == "__main__": rk = Ratekeeper(rate, print_delay_threshold=None) fltr = FirstOrderFilter(0, 5, 1. / rate, initialized=False) + measurements = [] + start_time = time.monotonic() + try: - start_time = time.monotonic() while duration is None or time.monotonic() - start_time < duration: fltr.update(z.read_power()) if rk.frame % rate == 0: print(f"{fltr.x:.2f} W") + measurements.append(fltr.x) rk.keep_time() except KeyboardInterrupt: pass + + t = datetime.timedelta(seconds=time.monotonic() - start_time) + avg = sum(measurements) / len(measurements) + print(f"\nAverage power: {avg:.2f}W over {t}") From abcc7338d41359e7e4f4d2d37d33449c292224ed Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Sun, 19 Jun 2022 00:06:23 -0700 Subject: [PATCH 086/302] Car Port: 2022 Honda Civic (#24535) * master 2022 Civic * bump panda * bump * bump cereal * fix * needed * try for now * maybe * revert for now * move to Cam parser * fix * move to cam * need AEB_STATUS too * bump for debug prints * bump opendbc and add cruise_params * bump opendbc and update cruise_params * bump * test route * update ref * Revert "update ref" This reverts commit 28345dab63d1919865ccb510265222a4cd4252f4. * cleanup * just to test * bump * revert * need to send val 12 too? * change bus * not needed * update bus * syntax * move this to other bus too * Revert "move this to other bus too" This reverts commit 770bf4745ee244c8426ac108f44b67777198d0a7. * test new lane line signal * needed too * maybe need both? * Test new LKAS hud message * bump * missing comma * missing * maybe * add frame and idx * add in hud_lanes * switch this too * bump panda * add this * I guess need this too * to match * also * wasnt correct * bump opendbc * bump panda * move to cam parser * missing * add here too * bump * remove from cam parser * bump * back to cam parser * its 5hz * bump for new checksum function * bump for correct frequency * update frame and idx * bump * bump and update * send set me bit * bump * pass these values through * silly atom * ret * fix this * use copy instead * add these too * to check keyerror * switch * bump submodules * send too * proper * Replace HUD with BOH * add dashed lanes * small fix * clean up * not needed anymore * remove and change * this too * dont always set * remove additional LKAS message * bump * add * to test * add frame * bump * rebase * remove default values * rename * clean up some carstate logic * regenerate docs * spacing * simplify more logic * bump opendbc * bump opendbc * only if radarless * panda at least builds now * add comment * bump * fixes * bump opendbc * bump opendbc fix for new DBC * bump opendbc * bump opendbc * carstate: fix bus, parser signals * Set safety param * pt bus is 0, not 1 * Fix SCM_BUTTONS and bump panda and opendbc * fixes for ACC_CONTROL * bump opendbc * bump opendbc * convert from MPH on HONDA_BOSCH_RADARLESS move is_metric * make sure we don't disable if radarless * don't show incorrect harness on website don't show incorrect harness on website * bump panda * remove/update comments * bump panda * Fix harnesses * one line check * bump opendbc * remove this * Some carstate cleanup We removed STANDSTILL->WHEELS_MOVING we don't use CRUISE_PARAMS add back add back * more cleanup * update docs * marketing says it has TJA and ACC with low speed follow * send buttons on bus 0 bump panda * comment * camera needs to see buttons on bus 2 comment * bump panda * add to releases * remove comments * comment * we don't use stock hud yet Co-authored-by: vanillagorillaa Co-authored-by: vanillagorillaa <31773928+vanillagorillaa@users.noreply.github.com> Co-authored-by: kevinharbin <76784413+kevinharbin@users.noreply.github.com> --- RELEASES.md | 1 + docs/CARS.md | 3 +- panda | 2 +- release/files_common | 1 + selfdrive/car/docs_definitions.py | 3 +- selfdrive/car/honda/carcontroller.py | 6 +-- selfdrive/car/honda/carstate.py | 56 ++++++++++++++------------ selfdrive/car/honda/hondacan.py | 18 +++++++-- selfdrive/car/honda/interface.py | 16 +++++--- selfdrive/car/honda/values.py | 60 +++++++++++++++++++++++----- selfdrive/car/tests/routes.py | 1 + 11 files changed, 115 insertions(+), 52 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index 7f365e5cef..5d81b43085 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -13,6 +13,7 @@ Version 0.8.15 (2022-XX-XX) * Display speed limit while navigating * Reduced power usage: device runs cooler and fan spins less * AGNOS 5 +* Honda Civic 2022 support * Hyundai Tucson 2021 support thanks to bluesforte! * Lexus NX Hybrid 2020 support thanks to AlexandreSato! diff --git a/docs/CARS.md b/docs/CARS.md index c0bd62eb3f..50db34dbb5 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -149,7 +149,7 @@ How We Rate The Cars |Volkswagen|Taos 2022[7](#footnotes)|Driver Assistance|||||| |Volkswagen|Touran 2017|Driver Assistance|||||| -# Bronze - 69 cars +# Bronze - 70 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -168,6 +168,7 @@ How We Rate The Cars |Honda|Accord Hybrid 2018-21|All|||||| |Honda|Civic 2016-18|Honda Sensing|||||| |Honda|Civic 2019-20|All|||[2](#footnotes)||| +|Honda|Civic 2022|All|||||| |Honda|Civic Hatchback 2017-21|Honda Sensing|||||| |Honda|CR-V 2015-16|Touring|||||| |Honda|CR-V 2017-21|Honda Sensing|||||| diff --git a/panda b/panda index 515df2bb72..e1b2f1253c 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 515df2bb727fe616869e5d460817e8898792e44f +Subproject commit e1b2f1253cb7f05f39d4afa21500565bb8b955d2 diff --git a/release/files_common b/release/files_common index b6cd4fa797..e84c668732 100644 --- a/release/files_common +++ b/release/files_common @@ -495,6 +495,7 @@ opendbc/honda_odyssey_exl_2018_generated.dbc opendbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc opendbc/honda_insight_ex_2019_can_generated.dbc opendbc/acura_ilx_2016_nidec.dbc +opendbc/honda_civic_ex_2022_can_generated.dbc opendbc/kia_ev6.dbc opendbc/hyundai_kia_generic.dbc diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index e1344174ab..618c986d18 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -123,7 +123,8 @@ class CarInfo: class Harness(Enum): nidec = "Honda Nidec" - bosch = "Honda Bosch A" + bosch_a = "Honda Bosch A" + bosch_b = "Honda Bosch B" toyota = "Toyota" subaru = "Subaru" fca = "FCA" diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index a6aa84adf6..4d04927b2f 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -7,7 +7,7 @@ from common.realtime import DT_CTRL from opendbc.can.packer import CANPacker from selfdrive.car import create_gas_interceptor_command from selfdrive.car.honda import hondacan -from selfdrive.car.honda.values import CruiseButtons, VISUAL_HUD, HONDA_BOSCH, HONDA_NIDEC_ALT_PCM_ACCEL, CarControllerParams +from selfdrive.car.honda.values import CruiseButtons, VISUAL_HUD, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, HONDA_NIDEC_ALT_PCM_ACCEL, CarControllerParams from selfdrive.controls.lib.drive_helpers import rate_limit VisualAlert = car.CarControl.HUDControl.VisualAlert @@ -189,7 +189,7 @@ class CarController: pcm_accel = int(clip((accel / 1.44) / max_accel, 0.0, 1.0) * 0xc6) if not self.CP.openpilotLongitudinalControl: - if self.frame % 2 == 0: + if self.frame % 2 == 0 and self.CP.carFingerprint not in HONDA_BOSCH_RADARLESS: # radarless cars don't have supplemental message idx = self.frame // 2 can_sends.append(hondacan.create_bosch_supplemental_1(self.packer, self.CP.carFingerprint, idx)) # If using stock ACC, spam cancel command to kill gas when OP disengages. @@ -241,7 +241,7 @@ class CarController: idx = (self.frame // 10) % 4 hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), hud_control.leadVisible, hud_control.lanesVisible, fcw_display, acc_alert, steer_required) - can_sends.extend(hondacan.create_ui_commands(self.packer, self.CP, CC.enabled, pcm_speed, hud, CS.is_metric, idx, CS.stock_hud)) + can_sends.extend(hondacan.create_ui_commands(self.packer, self.CP, CC.enabled, pcm_speed, hud, CS.is_metric, idx, CS.stock_hud, self.frame)) if self.CP.openpilotLongitudinalControl and self.CP.carFingerprint not in HONDA_BOSCH: self.speed = pcm_speed diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index f5cdc838c4..5358ce249a 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -5,8 +5,9 @@ from common.conversions import Conversions as CV from common.numpy_fast import interp from opendbc.can.can_define import CANDefine from opendbc.can.parser import CANParser +from selfdrive.car.honda.hondacan import get_pt_bus +from selfdrive.car.honda.values import CAR, DBC, STEER_THRESHOLD, HONDA_BOSCH, HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_ALT_BRAKE_SIGNAL, HONDA_BOSCH_RADARLESS from selfdrive.car.interfaces import CarStateBase -from selfdrive.car.honda.values import CAR, DBC, STEER_THRESHOLD, HONDA_BOSCH, HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_ALT_BRAKE_SIGNAL TransmissionType = car.CarParams.TransmissionType @@ -80,7 +81,8 @@ def get_can_signals(CP, gearbox_msg, main_on_sig_msg): checks.append(("EPB_STATUS", 50)) if CP.carFingerprint in HONDA_BOSCH: - if not CP.openpilotLongitudinalControl: + # these messages are on camera bus on radarless cars + if not CP.openpilotLongitudinalControl and CP.carFingerprint not in HONDA_BOSCH_RADARLESS: signals += [ ("CRUISE_CONTROL_LABEL", "ACC_HUD"), ("CRUISE_SPEED", "ACC_HUD"), @@ -100,23 +102,16 @@ def get_can_signals(CP, gearbox_msg, main_on_sig_msg): else: checks.append(("CRUISE_PARAMS", 50)) - if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E): + if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.CIVIC_2022): signals.append(("DRIVERS_DOOR_OPEN", "SCM_FEEDBACK")) - elif CP.carFingerprint == CAR.ODYSSEY_CHN: + elif CP.carFingerprint in (CAR.ODYSSEY_CHN, CAR.FREED, CAR.HRV): signals.append(("DRIVERS_DOOR_OPEN", "SCM_BUTTONS")) - elif CP.carFingerprint in (CAR.FREED, CAR.HRV): - signals += [("DRIVERS_DOOR_OPEN", "SCM_BUTTONS"), - ("WHEELS_MOVING", "STANDSTILL")] else: signals += [("DOOR_OPEN_FL", "DOORS_STATUS"), ("DOOR_OPEN_FR", "DOORS_STATUS"), ("DOOR_OPEN_RL", "DOORS_STATUS"), - ("DOOR_OPEN_RR", "DOORS_STATUS"), - ("WHEELS_MOVING", "STANDSTILL")] - checks += [ - ("DOORS_STATUS", 3), - ("STANDSTILL", 50), - ] + ("DOOR_OPEN_RR", "DOORS_STATUS")] + checks.append(("DOORS_STATUS", 3)) # add gas interceptor reading if we are using it if CP.enableGasInterceptor: @@ -175,7 +170,8 @@ class CarState(CarStateBase): # STANDSTILL->WHEELS_MOVING bit can be noisy around zero, so use XMISSION_SPEED # panda checks if the signal is non-zero ret.standstill = cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] < 1e-5 - if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E): + # TODO: find a common signal across all cars + if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.CIVIC_2022): ret.doorOpen = bool(cp.vl["SCM_FEEDBACK"]["DRIVERS_DOOR_OPEN"]) elif self.CP.carFingerprint in (CAR.ODYSSEY_CHN, CAR.FREED, CAR.HRV): ret.doorOpen = bool(cp.vl["SCM_BUTTONS"]["DRIVERS_DOOR_OPEN"]) @@ -235,11 +231,15 @@ class CarState(CarStateBase): if self.CP.carFingerprint in HONDA_BOSCH: if not self.CP.openpilotLongitudinalControl: - ret.cruiseState.nonAdaptive = cp.vl["ACC_HUD"]["CRUISE_CONTROL_LABEL"] != 0 - ret.cruiseState.standstill = cp.vl["ACC_HUD"]["CRUISE_SPEED"] == 252. + # ACC_HUD is on camera bus on radarless cars + acc_hud = cp_cam.vl["ACC_HUD"] if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS else cp.vl["ACC_HUD"] + ret.cruiseState.nonAdaptive = acc_hud["CRUISE_CONTROL_LABEL"] != 0 + ret.cruiseState.standstill = acc_hud["CRUISE_SPEED"] == 252. + # on certain cars, CRUISE_SPEED changes to imperial with car's unit setting + conversion_factor = CV.MPH_TO_MS if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS and not self.is_metric else CV.KPH_TO_MS # On set, cruise set speed pulses between 254~255 and the set speed prev is set to avoid this. - ret.cruiseState.speed = self.v_cruise_pcm_prev if cp.vl["ACC_HUD"]["CRUISE_SPEED"] > 160.0 else cp.vl["ACC_HUD"]["CRUISE_SPEED"] * CV.KPH_TO_MS + ret.cruiseState.speed = self.v_cruise_pcm_prev if acc_hud["CRUISE_SPEED"] > 160.0 else acc_hud["CRUISE_SPEED"] * conversion_factor self.v_cruise_pcm_prev = ret.cruiseState.speed else: ret.cruiseState.speed = cp.vl["CRUISE"]["CRUISE_SPEED_PCM"] * CV.KPH_TO_MS @@ -269,14 +269,14 @@ class CarState(CarStateBase): ret.brakePressed = True if self.CP.carFingerprint in HONDA_BOSCH: - ret.stockAeb = (not self.CP.openpilotLongitudinalControl) and bool(cp.vl["ACC_CONTROL"]["AEB_STATUS"] and cp.vl["ACC_CONTROL"]["ACCEL_COMMAND"] < -1e-5) + # TODO: find the radarless AEB_STATUS bit and make sure ACCEL_COMMAND is correct to enable AEB alerts + if self.CP.carFingerprint not in HONDA_BOSCH_RADARLESS: + ret.stockAeb = (not self.CP.openpilotLongitudinalControl) and bool(cp.vl["ACC_CONTROL"]["AEB_STATUS"] and cp.vl["ACC_CONTROL"]["ACCEL_COMMAND"] < -1e-5) else: ret.stockAeb = bool(cp_cam.vl["BRAKE_COMMAND"]["AEB_REQ_1"] and cp_cam.vl["BRAKE_COMMAND"]["COMPUTER_BRAKE"] > 1e-5) - if self.CP.carFingerprint in HONDA_BOSCH: - self.stock_hud = False - ret.stockFcw = False - else: + self.stock_hud = False + if self.CP.carFingerprint not in HONDA_BOSCH: ret.stockFcw = cp_cam.vl["BRAKE_COMMAND"]["FCW"] != 0 self.stock_hud = cp_cam.vl["ACC_HUD"] self.stock_brake = cp_cam.vl["BRAKE_COMMAND"] @@ -291,8 +291,7 @@ class CarState(CarStateBase): def get_can_parser(self, CP): signals, checks = get_can_signals(CP, self.gearbox_msg, self.main_on_sig_msg) - bus_pt = 1 if CP.carFingerprint in HONDA_BOSCH else 0 - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, bus_pt) + return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, get_pt_bus(CP.carFingerprint)) @staticmethod def get_cam_can_parser(CP): @@ -301,7 +300,14 @@ class CarState(CarStateBase): ("STEERING_CONTROL", 100), ] - if CP.carFingerprint not in HONDA_BOSCH: + if CP.carFingerprint in HONDA_BOSCH_RADARLESS and not CP.openpilotLongitudinalControl: + signals += [ + ("CRUISE_SPEED", "ACC_HUD"), + ("CRUISE_CONTROL_LABEL", "ACC_HUD"), + ] + checks.append(("ACC_HUD", 10)) + + elif CP.carFingerprint not in HONDA_BOSCH: signals += [("COMPUTER_BRAKE", "BRAKE_COMMAND"), ("AEB_REQ_1", "BRAKE_COMMAND"), ("FCW", "BRAKE_COMMAND"), diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py index 3d8c79c809..6a1fb2e459 100644 --- a/selfdrive/car/honda/hondacan.py +++ b/selfdrive/car/honda/hondacan.py @@ -1,5 +1,5 @@ from common.conversions import Conversions as CV -from selfdrive.car.honda.values import HondaFlags, HONDA_BOSCH, CAR, CarControllerParams +from selfdrive.car.honda.values import HondaFlags, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, CAR, CarControllerParams # CAN bus layout with relay # 0 = ACC-CAN - radar side @@ -7,8 +7,9 @@ from selfdrive.car.honda.values import HondaFlags, HONDA_BOSCH, CAR, CarControll # 2 = ACC-CAN - camera side # 3 = F-CAN A - OBDII port + def get_pt_bus(car_fingerprint): - return 1 if car_fingerprint in HONDA_BOSCH else 0 + return 1 if car_fingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS) else 0 def get_lkas_cmd_bus(car_fingerprint, radar_disabled=False): @@ -18,6 +19,7 @@ def get_lkas_cmd_bus(car_fingerprint, radar_disabled=False): # normally steering commands are sent to radar, which forwards them to powertrain bus return 0 + def create_brake_command(packer, apply_brake, pump_on, pcm_override, pcm_cancel_cmd, fcw, idx, car_fingerprint, stock_brake): # TODO: do we loose pressure if we keep pump off for long? brakelights = apply_brake > 0 @@ -78,6 +80,7 @@ def create_acc_commands(packer, enabled, active, accel, gas, idx, stopping, car_ return commands + def create_steering_control(packer, apply_steer, lkas_active, car_fingerprint, idx, radar_disabled): values = { "STEER_TORQUE": apply_steer if lkas_active else 0, @@ -98,7 +101,7 @@ def create_bosch_supplemental_1(packer, car_fingerprint, idx): return packer.make_can_msg("BOSCH_SUPPLEMENTAL_1", bus, values, idx) -def create_ui_commands(packer, CP, enabled, pcm_speed, hud, is_metric, idx, stock_hud): +def create_ui_commands(packer, CP, enabled, pcm_speed, hud, is_metric, idx, stock_hud, frame): commands = [] bus_pt = get_pt_bus(CP.carFingerprint) radar_disabled = CP.carFingerprint in HONDA_BOSCH and CP.openpilotLongitudinalControl @@ -135,6 +138,12 @@ def create_ui_commands(packer, CP, enabled, pcm_speed, hud, is_metric, idx, stoc 'BEEP': 0, } + if CP.carFingerprint in HONDA_BOSCH_RADARLESS: + lkas_hud_values['LANE_LINES'] = 3 + lkas_hud_values['DASHED_LANES'] = hud.lanes_visible + # TODO: understand this better, does car need to see it fall after start up? + lkas_hud_values['LKAS_PROBLEM'] = 0 if frame > 200 else 1 + if not (CP.flags & HondaFlags.BOSCH_EXT_HUD): lkas_hud_values['SET_ME_X48'] = 0x48 @@ -162,5 +171,6 @@ def spam_buttons_command(packer, button_val, idx, car_fingerprint): 'CRUISE_BUTTONS': button_val, 'CRUISE_SETTING': 0, } - bus = get_pt_bus(car_fingerprint) + # send buttons to camera on radarless cars + bus = 2 if car_fingerprint in HONDA_BOSCH_RADARLESS else get_pt_bus(car_fingerprint) return packer.make_can_msg("SCM_BUTTONS", bus, values, idx) diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 994152608e..a78189b697 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -3,7 +3,7 @@ from cereal import car from panda import Panda from common.conversions import Conversions as CV from common.numpy_fast import interp -from selfdrive.car.honda.values import CarControllerParams, CruiseButtons, HondaFlags, CAR, HONDA_BOSCH, HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_ALT_BRAKE_SIGNAL +from selfdrive.car.honda.values import CarControllerParams, CruiseButtons, HondaFlags, CAR, HONDA_BOSCH, HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_ALT_BRAKE_SIGNAL, HONDA_BOSCH_RADARLESS from selfdrive.car import STD_CARGO_KG, CivicParams, create_button_enable_events, create_button_event, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase from selfdrive.car.disable_ecu import disable_ecu @@ -37,9 +37,10 @@ class CarInterface(CarInterfaceBase): ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hondaBosch)] ret.radarOffCan = True - # Disable the radar and let openpilot control longitudinal - # WARNING: THIS DISABLES AEB! - ret.openpilotLongitudinalControl = disable_radar + if candidate not in HONDA_BOSCH_RADARLESS: + # Disable the radar and let openpilot control longitudinal + # WARNING: THIS DISABLES AEB! + ret.openpilotLongitudinalControl = disable_radar ret.pcmCruise = not ret.openpilotLongitudinalControl else: @@ -104,7 +105,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[1.1], [0.33]] tire_stiffness_factor = 1. - elif candidate in (CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL): + elif candidate in (CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CIVIC_2022): stop_and_go = True ret.mass = CivicParams.MASS ret.wheelbase = CivicParams.WHEELBASE @@ -304,6 +305,9 @@ class CarInterface(CarInterfaceBase): if ret.openpilotLongitudinalControl and candidate in HONDA_BOSCH: ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_BOSCH_LONG + if candidate in HONDA_BOSCH_RADARLESS: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_RADARLESS + # min speed to enable ACC. if car can do stop and go, then set enabling speed # to a negative value, so it won't matter. Otherwise, add 0.5 mph margin to not # conflict with PCM acc @@ -325,7 +329,7 @@ class CarInterface(CarInterfaceBase): @staticmethod def init(CP, logcan, sendcan): - if CP.carFingerprint in HONDA_BOSCH and CP.openpilotLongitudinalControl: + if CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS) and CP.openpilotLongitudinalControl: disable_ecu(logcan, sendcan, bus=1, addr=0x18DAB0F1, com_cont_req=b'\x28\x83\x03') # returns a car.CarState diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 152f71e98a..0bdb8ccd91 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -75,6 +75,7 @@ class CAR: CIVIC = "HONDA CIVIC 2016" CIVIC_BOSCH = "HONDA CIVIC (BOSCH) 2019" CIVIC_BOSCH_DIESEL = "HONDA CIVIC SEDAN 1.6 DIESEL 2019" + CIVIC_2022 = "HONDA CIVIC 2022" ACURA_ILX = "ACURA ILX 2016" CRV = "HONDA CR-V 2016" CRV_5G = "HONDA CR-V 2017" @@ -108,33 +109,34 @@ class HondaCarInfo(CarInfo): CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = { CAR.ACCORD: [ - HondaCarInfo("Honda Accord 2018-21", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch), - HondaCarInfo("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch), + HondaCarInfo("Honda Accord 2018-21", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), + HondaCarInfo("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), ], - CAR.ACCORDH: HondaCarInfo("Honda Accord Hybrid 2018-21", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch), + CAR.ACCORDH: HondaCarInfo("Honda Accord Hybrid 2018-21", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), CAR.CIVIC: HondaCarInfo("Honda Civic 2016-18", harness=Harness.nidec), CAR.CIVIC_BOSCH: [ - HondaCarInfo("Honda Civic 2019-20", "All", video_link="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", footnotes=[Footnote.CIVIC_DIESEL], min_steer_speed=2. * CV.MPH_TO_MS, harness=Harness.bosch), - HondaCarInfo("Honda Civic Hatchback 2017-21", harness=Harness.bosch), + HondaCarInfo("Honda Civic 2019-20", "All", video_link="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", footnotes=[Footnote.CIVIC_DIESEL], min_steer_speed=2. * CV.MPH_TO_MS, harness=Harness.bosch_a), + HondaCarInfo("Honda Civic Hatchback 2017-21", harness=Harness.bosch_a), ], CAR.CIVIC_BOSCH_DIESEL: None, # same platform + CAR.CIVIC_2022: HondaCarInfo("Honda Civic 2022", "All", min_steer_speed=0., harness=Harness.bosch_b), CAR.ACURA_ILX: HondaCarInfo("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS, harness=Harness.nidec), CAR.CRV: HondaCarInfo("Honda CR-V 2015-16", "Touring", harness=Harness.nidec), - CAR.CRV_5G: HondaCarInfo("Honda CR-V 2017-21", harness=Harness.bosch), + CAR.CRV_5G: HondaCarInfo("Honda CR-V 2017-21", harness=Harness.bosch_a), CAR.CRV_EU: None, # HondaCarInfo("Honda CR-V EU", "Touring"), # Euro version of CRV Touring - CAR.CRV_HYBRID: HondaCarInfo("Honda CR-V Hybrid 2017-19", harness=Harness.bosch), + CAR.CRV_HYBRID: HondaCarInfo("Honda CR-V Hybrid 2017-19", harness=Harness.bosch_a), CAR.FIT: HondaCarInfo("Honda Fit 2018-19", harness=Harness.nidec), CAR.FREED: HondaCarInfo("Honda Freed 2020", harness=Harness.nidec), CAR.HRV: HondaCarInfo("Honda HR-V 2019-20", harness=Harness.nidec), CAR.ODYSSEY: HondaCarInfo("Honda Odyssey 2018-20", min_steer_speed=0., harness=Harness.nidec), CAR.ODYSSEY_CHN: None, # Chinese version of Odyssey CAR.ACURA_RDX: HondaCarInfo("Acura RDX 2016-18", "AcuraWatch Plus", harness=Harness.nidec), - CAR.ACURA_RDX_3G: HondaCarInfo("Acura RDX 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch), + CAR.ACURA_RDX_3G: HondaCarInfo("Acura RDX 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), CAR.PILOT: HondaCarInfo("Honda Pilot 2016-21", harness=Harness.nidec), CAR.PASSPORT: HondaCarInfo("Honda Passport 2019-21", "All", harness=Harness.nidec), CAR.RIDGELINE: HondaCarInfo("Honda Ridgeline 2017-22", harness=Harness.nidec), - CAR.INSIGHT: HondaCarInfo("Honda Insight 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch), - CAR.HONDA_E: HondaCarInfo("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch), + CAR.INSIGHT: HondaCarInfo("Honda Insight 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), + CAR.HONDA_E: HondaCarInfo("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), } @@ -1392,6 +1394,40 @@ FW_VERSIONS = { b'57114-TYF-E030\x00\x00' ], }, + CAR.CIVIC_2022: { + (Ecu.eps, 0x18DA30F1, None): [ + b'39990-T39-A130\x00\x00', + b'39990-T43-J020\x00\x00', + ], + (Ecu.gateway, 0x18DAEFF1, None): [ + b'38897-T20-A020\x00\x00', + b'38897-T20-A510\x00\x00', + b'38897-T21-A010\x00\x00', + ], + (Ecu.srs, 0x18DA53F1, None): [ + b'77959-T20-A970\x00\x00', + b'77959-T47-A940\x00\x00', + ], + (Ecu.combinationMeter, 0x18DA60F1, None): [ + b'78108-T21-A220\x00\x00', + b'78108-T21-A620\x00\x00', + b'78108-T23-A110\x00\x00', + ], + (Ecu.vsa, 0x18DA28F1, None): [ + b'57114-T20-AB40\x00\x00', + b'57114-T43-JB30\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-65D-A020\x00\x00', + b'28101-65D-A120\x00\x00', + b'28101-65H-A020\x00\x00', + ], + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-64L-A540\x00\x00', + b'37805-64S-A540\x00\x00', + b'37805-64S-A720\x00\x00', + ], + }, } DBC = { @@ -1417,6 +1453,7 @@ DBC = { CAR.RIDGELINE: dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), CAR.INSIGHT: dbc_dict('honda_insight_ex_2019_can_generated', None), CAR.HONDA_E: dbc_dict('acura_rdx_2020_can_generated', None), + CAR.CIVIC_2022: dbc_dict('honda_civic_ex_2022_can_generated', None), } STEER_THRESHOLD = { @@ -1429,5 +1466,6 @@ HONDA_NIDEC_ALT_PCM_ACCEL = {CAR.ODYSSEY} HONDA_NIDEC_ALT_SCM_MESSAGES = {CAR.ACURA_ILX, CAR.ACURA_RDX, CAR.CRV, CAR.CRV_EU, CAR.FIT, CAR.FREED, CAR.HRV, CAR.ODYSSEY_CHN, CAR.PILOT, CAR.PASSPORT, CAR.RIDGELINE} HONDA_BOSCH = {CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_5G, - CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E} + CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.CIVIC_2022} HONDA_BOSCH_ALT_BRAKE_SIGNAL = {CAR.ACCORD, CAR.CRV_5G, CAR.ACURA_RDX_3G} +HONDA_BOSCH_RADARLESS = {CAR.CIVIC_2022} diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index a9d36f9eab..19b1a05c23 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -71,6 +71,7 @@ routes = [ TestRoute("f34a60d68d83b1e5|2020-10-06--14-35-55", HONDA.ACURA_RDX), TestRoute("54fd8451b3974762|2021-04-01--14-50-10", HONDA.RIDGELINE), TestRoute("2d5808fae0b38ac6|2021-09-01--17-14-11", HONDA.HONDA_E), + TestRoute("f44aa96ace22f34a|2021-12-22--06-22-31", HONDA.CIVIC_2022), TestRoute("6fe86b4e410e4c37|2020-07-22--16-27-13", HYUNDAI.HYUNDAI_GENESIS), TestRoute("70c5bec28ec8e345|2020-08-08--12-22-23", HYUNDAI.GENESIS_G70), From 28431f7dddb72da31a79005ef37fb6642f822a4c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 19 Jun 2022 14:07:19 -0700 Subject: [PATCH 087/302] Revert "Chrysler: use unified signal definitions (#24895)" This reverts commit 0f0b4cac893b41dd81288947158d3aa9cbbfc2fd. --- opendbc | 2 +- selfdrive/car/chrysler/carstate.py | 31 +++++++++++++++--------------- 2 files changed, 16 insertions(+), 17 deletions(-) diff --git a/opendbc b/opendbc index 57c8340a18..5e2a820268 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 57c8340a180dd8c75139b18050eb17c72c9cb6e4 +Subproject commit 5e2a82026842a7082e5e81e5823dab6b6616dbf4 diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index 7571286c56..e3ee4753cc 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -18,10 +18,10 @@ class CarState(CarStateBase): self.frame = int(cp.vl["EPS_STATUS"]["COUNTER"]) - ret.doorOpen = any([cp.vl["BCM_1"]["Driver_Door_Ajar"], - cp.vl["BCM_1"]["Passenger_Door_Ajar"], - cp.vl["BCM_1"]["Left_Rear_Door_Ajar"], - cp.vl["BCM_1"]["Right_Rear_Door_Ajar"]]) + ret.doorOpen = any([cp.vl["DOORS"]["DOOR_OPEN_FL"], + cp.vl["DOORS"]["DOOR_OPEN_FR"], + cp.vl["DOORS"]["DOOR_OPEN_RL"], + cp.vl["DOORS"]["DOOR_OPEN_RR"]]) ret.seatbeltUnlatched = cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_UNLATCHED"] == 1 # brake pedal @@ -51,12 +51,12 @@ class CarState(CarStateBase): ret.steeringRateDeg = cp.vl["STEERING"]["STEERING_RATE"] ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["GEAR"]["PRNDL"], None)) - ret.cruiseState.available = cp.vl["DAS_3"]["ACC_Engaged"] == 1 # ACC is white - ret.cruiseState.enabled = cp.vl["DAS_3"]["ACC_Enabled"] == 1 # ACC is green + ret.cruiseState.enabled = cp.vl["ACC_2"]["ACC_STATUS_2"] == 7 # ACC is green. + ret.cruiseState.available = ret.cruiseState.enabled # FIXME: for now same as enabled ret.cruiseState.speed = cp.vl["DASHBOARD"]["ACC_SPEED_CONFIG_KPH"] * CV.KPH_TO_MS # CRUISE_STATE is a three bit msg, 0 is off, 1 and 2 are Non-ACC mode, 3 and 4 are ACC mode, find if there are other states too ret.cruiseState.nonAdaptive = cp.vl["DASHBOARD"]["CRUISE_STATE"] in (1, 2) - ret.accFaulted = cp.vl["DAS_3"]["ACC_Faulted"] != 0 + ret.accFaulted = cp.vl["ACC_2"]["ACC_FAULTED"] != 0 ret.steeringTorque = cp.vl["EPS_STATUS"]["TORQUE_DRIVER"] ret.steeringTorqueEps = cp.vl["EPS_STATUS"]["TORQUE_MOTOR"] @@ -82,10 +82,10 @@ class CarState(CarStateBase): signals = [ # sig_name, sig_address ("PRNDL", "GEAR"), - ("Driver_Door_Ajar", "BCM_1"), - ("Passenger_Door_Ajar", "BCM_1"), - ("Left_Rear_Door_Ajar", "BCM_1"), - ("Right_Rear_Door_Ajar", "BCM_1"), + ("DOOR_OPEN_FL", "DOORS"), + ("DOOR_OPEN_FR", "DOORS"), + ("DOOR_OPEN_RL", "DOORS"), + ("DOOR_OPEN_RR", "DOORS"), ("Brake_Pedal_State", "ESP_1"), ("Accelerator_Position", "ECM_5"), ("SPEED_LEFT", "SPEED_1"), @@ -97,9 +97,8 @@ class CarState(CarStateBase): ("STEER_ANGLE", "STEERING"), ("STEERING_RATE", "STEERING"), ("TURN_SIGNALS", "STEERING_LEVERS"), - ("ACC_Enabled", "DAS_3"), - ("ACC_Engaged", "DAS_3"), - ("ACC_Faulted", "DAS_3"), + ("ACC_STATUS_2", "ACC_2"), + ("ACC_FAULTED", "ACC_2"), ("HIGH_BEAM_FLASH", "STEERING_LEVERS"), ("ACC_SPEED_CONFIG_KPH", "DASHBOARD"), ("CRUISE_STATE", "DASHBOARD"), @@ -119,14 +118,14 @@ class CarState(CarStateBase): ("SPEED_1", 100), ("WHEEL_SPEEDS", 50), ("STEERING", 100), - ("DAS_3", 50), + ("ACC_2", 50), ("GEAR", 50), ("ECM_5", 50), ("WHEEL_BUTTONS", 50), ("DASHBOARD", 15), ("STEERING_LEVERS", 10), ("SEATBELT_STATUS", 2), - ("BCM_1", 1), + ("DOORS", 1), ("TRACTION_BUTTON", 1), ] From d3185a0af0d5a0382cf4688fa35ab79a48a0914c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 19 Jun 2022 14:08:14 -0700 Subject: [PATCH 088/302] Chrysler: 2022 pacific hybrid is supported --- docs/CARS.md | 2 +- selfdrive/car/chrysler/values.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 50db34dbb5..77b1c5e787 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -161,7 +161,7 @@ How We Rate The Cars |Chrysler|Pacifica 2017-18|Adaptive Cruise|||||| |Chrysler|Pacifica 2020|Adaptive Cruise|||||| |Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise|||||| -|Chrysler|Pacifica Hybrid 2019-21|Adaptive Cruise|||||| +|Chrysler|Pacifica Hybrid 2019-22|Adaptive Cruise|||||| |Genesis|G90 2018|All|||||| |GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise|||||| |Honda|Accord 2018-21|All|||||| diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index a0d4225d9a..bdd80757f4 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -37,7 +37,7 @@ class ChryslerCarInfo(CarInfo): CAR_INFO: Dict[str, Optional[Union[ChryslerCarInfo, List[ChryslerCarInfo]]]] = { CAR.PACIFICA_2017_HYBRID: ChryslerCarInfo("Chrysler Pacifica Hybrid 2017-18"), CAR.PACIFICA_2018_HYBRID: None, # same platforms - CAR.PACIFICA_2019_HYBRID: ChryslerCarInfo("Chrysler Pacifica Hybrid 2019-21"), + CAR.PACIFICA_2019_HYBRID: ChryslerCarInfo("Chrysler Pacifica Hybrid 2019-22"), CAR.PACIFICA_2018: ChryslerCarInfo("Chrysler Pacifica 2017-18"), CAR.PACIFICA_2020: ChryslerCarInfo("Chrysler Pacifica 2020"), CAR.JEEP_CHEROKEE: ChryslerCarInfo("Jeep Grand Cherokee 2016-18", video_link="https://www.youtube.com/watch?v=eLR9o2JkuRk"), From 6123ab3d1c901ed3763e1a7cb8e1aac3f6b8fda3 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 19 Jun 2022 14:43:49 -0700 Subject: [PATCH 089/302] Move camerad to system/ (#24836) * mv camerad * add hardware symlink * fix unit tests --- .github/workflows/selfdrive_tests.yaml | 2 +- Jenkinsfile | 4 +-- SConstruct | 4 +-- docs/c_docs.rst | 6 ++-- release/files_common | 31 ++++++++++--------- release/files_tici | 6 ++-- selfdrive/athena/athenad.py | 2 +- selfdrive/loggerd/encoder/encoder.h | 2 +- selfdrive/loggerd/loggerd.h | 2 +- selfdrive/manager/process_config.py | 4 +-- selfdrive/test/process_replay/test_debayer.py | 4 +-- selfdrive/ui/qt/widgets/cameraview.h | 2 +- selfdrive/ui/replay/logreader.h | 2 +- {selfdrive => system}/camerad/SConscript | 0 {selfdrive => system}/camerad/__init__.py | 0 .../camerad/cameras/camera_common.cc | 8 ++--- .../camerad/cameras/camera_common.h | 2 +- .../camerad/cameras/camera_qcom2.cc | 4 +-- .../camerad/cameras/camera_qcom2.h | 2 +- .../camerad/cameras/real_debayer.cl | 0 .../camerad/cameras/sensor2_i2c.h | 0 {selfdrive => system}/camerad/imgproc/conv.cl | 0 {selfdrive => system}/camerad/imgproc/pool.cl | 0 .../camerad/imgproc/utils.cc | 2 +- {selfdrive => system}/camerad/imgproc/utils.h | 0 .../camerad/include/media/cam_cpas.h | 0 .../camerad/include/media/cam_defs.h | 0 .../camerad/include/media/cam_fd.h | 0 .../camerad/include/media/cam_icp.h | 0 .../camerad/include/media/cam_isp.h | 0 .../camerad/include/media/cam_isp_ife.h | 0 .../camerad/include/media/cam_isp_vfe.h | 0 .../camerad/include/media/cam_jpeg.h | 0 .../camerad/include/media/cam_lrme.h | 0 .../camerad/include/media/cam_req_mgr.h | 0 .../camerad/include/media/cam_sensor.h | 0 .../include/media/cam_sensor_cmn_header.h | 0 .../camerad/include/media/cam_sync.h | 0 .../camerad/include/msm_cam_sensor.h | 0 .../camerad/include/msm_camsensor_sdk.h | 0 .../camerad/include/msmb_camera.h | 0 .../camerad/include/msmb_isp.h | 0 .../camerad/include/msmb_ispif.h | 0 {selfdrive => system}/camerad/main.cc | 2 +- .../camerad/snapshot/__init__.py | 0 .../camerad/snapshot/snapshot.py | 2 +- {selfdrive => system}/camerad/test/.gitignore | 0 .../camerad/test/ae_gray_test.cc | 2 +- .../camerad/test/ae_gray_test.h | 0 .../camerad/test/camera_test.h | 0 .../camerad/test/check_skips.py | 0 .../camerad/test/frame_test.py | 0 .../test/get_thumbnails_for_segment.py | 0 .../camerad/test/stress_restart.sh | 0 .../camerad/test/test_camerad.py | 0 .../camerad/test/test_exposure.py | 2 +- .../camerad/transforms/rgb_to_yuv.cc | 2 +- .../camerad/transforms/rgb_to_yuv.cl | 0 .../camerad/transforms/rgb_to_yuv.h | 0 .../camerad/transforms/rgb_to_yuv_test.cc | 2 +- tools/webcam/README.md | 4 +-- 61 files changed, 53 insertions(+), 52 deletions(-) rename {selfdrive => system}/camerad/SConscript (100%) rename {selfdrive => system}/camerad/__init__.py (100%) rename {selfdrive => system}/camerad/cameras/camera_common.cc (98%) rename {selfdrive => system}/camerad/cameras/camera_common.h (98%) rename {selfdrive => system}/camerad/cameras/camera_qcom2.cc (99%) rename {selfdrive => system}/camerad/cameras/camera_qcom2.h (98%) rename {selfdrive => system}/camerad/cameras/real_debayer.cl (100%) rename {selfdrive => system}/camerad/cameras/sensor2_i2c.h (100%) rename {selfdrive => system}/camerad/imgproc/conv.cl (100%) rename {selfdrive => system}/camerad/imgproc/pool.cl (100%) rename {selfdrive => system}/camerad/imgproc/utils.cc (98%) rename {selfdrive => system}/camerad/imgproc/utils.h (100%) rename {selfdrive => system}/camerad/include/media/cam_cpas.h (100%) rename {selfdrive => system}/camerad/include/media/cam_defs.h (100%) rename {selfdrive => system}/camerad/include/media/cam_fd.h (100%) rename {selfdrive => system}/camerad/include/media/cam_icp.h (100%) rename {selfdrive => system}/camerad/include/media/cam_isp.h (100%) rename {selfdrive => system}/camerad/include/media/cam_isp_ife.h (100%) rename {selfdrive => system}/camerad/include/media/cam_isp_vfe.h (100%) rename {selfdrive => system}/camerad/include/media/cam_jpeg.h (100%) rename {selfdrive => system}/camerad/include/media/cam_lrme.h (100%) rename {selfdrive => system}/camerad/include/media/cam_req_mgr.h (100%) rename {selfdrive => system}/camerad/include/media/cam_sensor.h (100%) rename {selfdrive => system}/camerad/include/media/cam_sensor_cmn_header.h (100%) rename {selfdrive => system}/camerad/include/media/cam_sync.h (100%) rename {selfdrive => system}/camerad/include/msm_cam_sensor.h (100%) rename {selfdrive => system}/camerad/include/msm_camsensor_sdk.h (100%) rename {selfdrive => system}/camerad/include/msmb_camera.h (100%) rename {selfdrive => system}/camerad/include/msmb_isp.h (100%) rename {selfdrive => system}/camerad/include/msmb_ispif.h (100%) rename {selfdrive => system}/camerad/main.cc (89%) rename {selfdrive => system}/camerad/snapshot/__init__.py (100%) rename {selfdrive => system}/camerad/snapshot/snapshot.py (98%) rename {selfdrive => system}/camerad/test/.gitignore (100%) rename {selfdrive => system}/camerad/test/ae_gray_test.cc (97%) rename {selfdrive => system}/camerad/test/ae_gray_test.h (100%) rename {selfdrive => system}/camerad/test/camera_test.h (100%) rename {selfdrive => system}/camerad/test/check_skips.py (100%) rename {selfdrive => system}/camerad/test/frame_test.py (100%) rename {selfdrive => system}/camerad/test/get_thumbnails_for_segment.py (100%) rename {selfdrive => system}/camerad/test/stress_restart.sh (100%) rename {selfdrive => system}/camerad/test/test_camerad.py (100%) rename {selfdrive => system}/camerad/test/test_exposure.py (96%) rename {selfdrive => system}/camerad/transforms/rgb_to_yuv.cc (96%) rename {selfdrive => system}/camerad/transforms/rgb_to_yuv.cl (100%) rename {selfdrive => system}/camerad/transforms/rgb_to_yuv.h (100%) rename {selfdrive => system}/camerad/transforms/rgb_to_yuv_test.cc (99%) diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 5bd9acc200..fedeaa734b 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -310,7 +310,7 @@ jobs: ./selfdrive/loggerd/tests/test_logger &&\ ./system/proclogd/tests/test_proclog && \ ./selfdrive/ui/replay/tests/test_replay && \ - ./selfdrive/camerad/test/ae_gray_test && \ + ./system/camerad/test/ae_gray_test && \ coverage xml" - name: "Upload coverage to Codecov" uses: codecov/codecov-action@v2 diff --git a/Jenkinsfile b/Jenkinsfile index 279716d7cf..dba1f257d6 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -139,8 +139,8 @@ pipeline { steps { phone_steps("tici-party", [ ["build", "cd selfdrive/manager && ./build.py"], - ["test camerad", "python selfdrive/camerad/test/test_camerad.py"], - ["test exposure", "python selfdrive/camerad/test/test_exposure.py"], + ["test camerad", "python system/camerad/test/test_camerad.py"], + ["test exposure", "python system/camerad/test/test_exposure.py"], ]) } } diff --git a/SConstruct b/SConstruct index b5c4edc99b..b243a4dc45 100644 --- a/SConstruct +++ b/SConstruct @@ -94,7 +94,7 @@ if arch == "larch64": "/usr/lib/aarch64-linux-gnu" ] cpppath += [ - "#selfdrive/camerad/include", + "#system/camerad/include", ] cflags = ["-DQCOM2", "-mcpu=cortex-a57"] cxxflags = ["-DQCOM2", "-mcpu=cortex-a57"] @@ -379,6 +379,7 @@ SConscript(['rednose/SConscript']) # Build system services SConscript([ + 'system/camerad/SConscript', 'system/clocksd/SConscript', 'system/proclogd/SConscript', ]) @@ -396,7 +397,6 @@ SConscript(['third_party/SConscript']) SConscript(['common/kalman/SConscript']) SConscript(['common/transformations/SConscript']) -SConscript(['selfdrive/camerad/SConscript']) SConscript(['selfdrive/modeld/SConscript']) SConscript(['selfdrive/controls/lib/cluster/SConscript']) diff --git a/docs/c_docs.rst b/docs/c_docs.rst index 218cd5a7d9..4e1e8a247a 100644 --- a/docs/c_docs.rst +++ b/docs/c_docs.rst @@ -28,11 +28,11 @@ selfdrive camerad ^^^^^^^ .. autodoxygenindex:: - :project: selfdrive_camerad_cameras + :project: system_camerad_cameras .. autodoxygenindex:: - :project: selfdrive_camerad_transforms + :project: system_camerad_transforms .. autodoxygenindex:: - :project: selfdrive_camerad_imgproc + :project: system_camerad_imgproc locationd ^^^^^^^^^ diff --git a/release/files_common b/release/files_common index e84c668732..ecb71b4e69 100644 --- a/release/files_common +++ b/release/files_common @@ -182,6 +182,7 @@ selfdrive/controls/lib/longitudinal_mpc_lib/.gitignore selfdrive/controls/lib/lateral_mpc_lib/* selfdrive/controls/lib/longitudinal_mpc_lib/* +selfdrive/hardware system/hardware/__init__.py system/hardware/base.h system/hardware/base.py @@ -298,24 +299,24 @@ selfdrive/ui/replay/*.h selfdrive/ui/qt/maps/*.cc selfdrive/ui/qt/maps/*.h -selfdrive/camerad/SConscript -selfdrive/camerad/main.cc +system/camerad/SConscript +system/camerad/main.cc -selfdrive/camerad/snapshot/* -selfdrive/camerad/include/* -selfdrive/camerad/cameras/camera_common.h -selfdrive/camerad/cameras/camera_common.cc -selfdrive/camerad/cameras/sensor2_i2c.h +system/camerad/snapshot/* +system/camerad/include/* +system/camerad/cameras/camera_common.h +system/camerad/cameras/camera_common.cc +system/camerad/cameras/sensor2_i2c.h -selfdrive/camerad/transforms/rgb_to_yuv.cc -selfdrive/camerad/transforms/rgb_to_yuv.h -selfdrive/camerad/transforms/rgb_to_yuv.cl -selfdrive/camerad/transforms/rgb_to_yuv_test.cc +system/camerad/transforms/rgb_to_yuv.cc +system/camerad/transforms/rgb_to_yuv.h +system/camerad/transforms/rgb_to_yuv.cl +system/camerad/transforms/rgb_to_yuv_test.cc -selfdrive/camerad/imgproc/conv.cl -selfdrive/camerad/imgproc/pool.cl -selfdrive/camerad/imgproc/utils.cc -selfdrive/camerad/imgproc/utils.h +system/camerad/imgproc/conv.cl +system/camerad/imgproc/pool.cl +system/camerad/imgproc/utils.cc +system/camerad/imgproc/utils.h selfdrive/manager/__init__.py selfdrive/manager/build.py diff --git a/release/files_tici b/release/files_tici index 485a898799..f8c0a27959 100644 --- a/release/files_tici +++ b/release/files_tici @@ -7,9 +7,9 @@ system/timezoned.py selfdrive/assets/navigation/* selfdrive/assets/training_wide/* -selfdrive/camerad/cameras/camera_qcom2.cc -selfdrive/camerad/cameras/camera_qcom2.h -selfdrive/camerad/cameras/real_debayer.cl +system/camerad/cameras/camera_qcom2.cc +system/camerad/cameras/camera_qcom2.h +system/camerad/cameras/real_debayer.cl selfdrive/ui/qt/spinner_larch64 selfdrive/ui/qt/text_larch64 diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index 26220dfa99..b0e138c495 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -493,7 +493,7 @@ def getNetworks(): @dispatcher.add_method def takeSnapshot(): - from selfdrive.camerad.snapshot.snapshot import jpeg_write, snapshot + from system.camerad.snapshot.snapshot import jpeg_write, snapshot ret = snapshot() if ret is not None: def b64jpeg(x): diff --git a/selfdrive/loggerd/encoder/encoder.h b/selfdrive/loggerd/encoder/encoder.h index 312b68ba19..21ef65cf12 100644 --- a/selfdrive/loggerd/encoder/encoder.h +++ b/selfdrive/loggerd/encoder/encoder.h @@ -8,7 +8,7 @@ #include "cereal/visionipc/visionipc.h" #include "common/queue.h" #include "selfdrive/loggerd/video_writer.h" -#include "selfdrive/camerad/cameras/camera_common.h" +#include "system/camerad/cameras/camera_common.h" #define V4L2_BUF_FLAG_KEYFRAME 8 diff --git a/selfdrive/loggerd/loggerd.h b/selfdrive/loggerd/loggerd.h index 7e13e90e63..2c4990086a 100644 --- a/selfdrive/loggerd/loggerd.h +++ b/selfdrive/loggerd/loggerd.h @@ -15,7 +15,7 @@ #include "cereal/services.h" #include "cereal/visionipc/visionipc.h" #include "cereal/visionipc/visionipc_client.h" -#include "selfdrive/camerad/cameras/camera_common.h" +#include "system/camerad/cameras/camera_common.h" #include "common/params.h" #include "common/swaglog.h" #include "common/timing.h" diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index a9a5c78a7f..7e4029664d 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -18,6 +18,8 @@ def logging(started, params, CP: car.CarParams) -> bool: return started and run procs = [ + # due to qualcomm kernel bugs SIGKILLing camerad sometimes causes page table corruption + NativeProcess("camerad", "system/camerad", ["./camerad"], unkillable=True, callback=driverview), NativeProcess("clocksd", "system/clocksd", ["./clocksd"]), NativeProcess("logcatd", "system/logcatd", ["./logcatd"]), NativeProcess("proclogd", "system/proclogd", ["./proclogd"]), @@ -25,8 +27,6 @@ procs = [ PythonProcess("timezoned", "system.timezoned", enabled=not PC, offroad=True), DaemonProcess("manage_athenad", "selfdrive.athena.manage_athenad", "AthenadPid"), - # due to qualcomm kernel bugs SIGKILLing camerad sometimes causes page table corruption - NativeProcess("camerad", "selfdrive/camerad", ["./camerad"], unkillable=True, callback=driverview), NativeProcess("dmonitoringmodeld", "selfdrive/modeld", ["./dmonitoringmodeld"], enabled=(not PC or WEBCAM), callback=driverview), NativeProcess("encoderd", "selfdrive/loggerd", ["./encoderd"]), NativeProcess("loggerd", "selfdrive/loggerd", ["./loggerd"], onroad=False, callback=logging), diff --git a/selfdrive/test/process_replay/test_debayer.py b/selfdrive/test/process_replay/test_debayer.py index eff77fc479..1b3e0f112e 100755 --- a/selfdrive/test/process_replay/test_debayer.py +++ b/selfdrive/test/process_replay/test_debayer.py @@ -10,7 +10,7 @@ from system.hardware import PC, TICI from common.basedir import BASEDIR from selfdrive.test.openpilotci import BASE_URL, get_url from system.version import get_commit -from selfdrive.camerad.snapshot.snapshot import yuv_to_rgb +from system.camerad.snapshot.snapshot import yuv_to_rgb from tools.lib.logreader import LogReader from tools.lib.filereader import FileReader @@ -62,7 +62,7 @@ def unbzip_frames(url): def init_kernels(frame_offset=0): ctx = cl.create_some_context(interactive=False) - with open(os.path.join(BASEDIR, 'selfdrive/camerad/cameras/real_debayer.cl')) as f: + with open(os.path.join(BASEDIR, 'system/camerad/cameras/real_debayer.cl')) as f: build_args = ' -cl-fast-relaxed-math -cl-denorms-are-zero -cl-single-precision-constant' + \ f' -DFRAME_STRIDE={FRAME_STRIDE} -DRGB_WIDTH={FRAME_WIDTH} -DRGB_HEIGHT={FRAME_HEIGHT} -DFRAME_OFFSET={frame_offset} -DCAM_NUM=0' if PC: diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index ddc3fc253b..42e9043602 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -17,7 +17,7 @@ #endif #include "cereal/visionipc/visionipc_client.h" -#include "selfdrive/camerad/cameras/camera_common.h" +#include "system/camerad/cameras/camera_common.h" #include "selfdrive/ui/ui.h" const int FRAME_BUFFER_SIZE = 5; diff --git a/selfdrive/ui/replay/logreader.h b/selfdrive/ui/replay/logreader.h index 7ada20605e..b4a38a5721 100644 --- a/selfdrive/ui/replay/logreader.h +++ b/selfdrive/ui/replay/logreader.h @@ -6,7 +6,7 @@ #endif #include "cereal/gen/cpp/log.capnp.h" -#include "selfdrive/camerad/cameras/camera_common.h" +#include "system/camerad/cameras/camera_common.h" #include "selfdrive/ui/replay/filereader.h" const CameraType ALL_CAMERAS[] = {RoadCam, DriverCam, WideRoadCam}; diff --git a/selfdrive/camerad/SConscript b/system/camerad/SConscript similarity index 100% rename from selfdrive/camerad/SConscript rename to system/camerad/SConscript diff --git a/selfdrive/camerad/__init__.py b/system/camerad/__init__.py similarity index 100% rename from selfdrive/camerad/__init__.py rename to system/camerad/__init__.py diff --git a/selfdrive/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc similarity index 98% rename from selfdrive/camerad/cameras/camera_common.cc rename to system/camerad/cameras/camera_common.cc index a94cfedf1a..34dde9389c 100644 --- a/selfdrive/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -1,4 +1,4 @@ -#include "selfdrive/camerad/cameras/camera_common.h" +#include "system/camerad/cameras/camera_common.h" #include @@ -10,7 +10,7 @@ #include "libyuv.h" #include -#include "selfdrive/camerad/imgproc/utils.h" +#include "system/camerad/imgproc/utils.h" #include "common/clutil.h" #include "common/modeldata.h" #include "common/swaglog.h" @@ -20,9 +20,9 @@ #ifdef QCOM2 #include "CL/cl_ext_qcom.h" -#include "selfdrive/camerad/cameras/camera_qcom2.h" +#include "system/camerad/cameras/camera_qcom2.h" #else -#include "selfdrive/camerad/test/camera_test.h" +#include "system/camerad/test/camera_test.h" #endif ExitHandler do_exit; diff --git a/selfdrive/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h similarity index 98% rename from selfdrive/camerad/cameras/camera_common.h rename to system/camerad/cameras/camera_common.h index e9c7ccd757..6b483372bb 100644 --- a/selfdrive/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -9,7 +9,7 @@ #include "cereal/visionipc/visionbuf.h" #include "cereal/visionipc/visionipc.h" #include "cereal/visionipc/visionipc_server.h" -#include "selfdrive/camerad/transforms/rgb_to_yuv.h" +#include "system/camerad/transforms/rgb_to_yuv.h" #include "common/mat.h" #include "common/queue.h" #include "common/swaglog.h" diff --git a/selfdrive/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc similarity index 99% rename from selfdrive/camerad/cameras/camera_qcom2.cc rename to system/camerad/cameras/camera_qcom2.cc index c1ffc1275a..f001009b9a 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -1,4 +1,4 @@ -#include "selfdrive/camerad/cameras/camera_qcom2.h" +#include "system/camerad/cameras/camera_qcom2.h" #include #include @@ -20,7 +20,7 @@ #include "media/cam_sensor_cmn_header.h" #include "media/cam_sync.h" #include "common/swaglog.h" -#include "selfdrive/camerad/cameras/sensor2_i2c.h" +#include "system/camerad/cameras/sensor2_i2c.h" // For debugging: // echo "4294967295" > /sys/module/cam_debug_util/parameters/debug_mdl diff --git a/selfdrive/camerad/cameras/camera_qcom2.h b/system/camerad/cameras/camera_qcom2.h similarity index 98% rename from selfdrive/camerad/cameras/camera_qcom2.h rename to system/camerad/cameras/camera_qcom2.h index 88766a68e9..57fef8d49a 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.h +++ b/system/camerad/cameras/camera_qcom2.h @@ -6,7 +6,7 @@ #include -#include "selfdrive/camerad/cameras/camera_common.h" +#include "system/camerad/cameras/camera_common.h" #include "common/util.h" #define FRAME_BUF_COUNT 4 diff --git a/selfdrive/camerad/cameras/real_debayer.cl b/system/camerad/cameras/real_debayer.cl similarity index 100% rename from selfdrive/camerad/cameras/real_debayer.cl rename to system/camerad/cameras/real_debayer.cl diff --git a/selfdrive/camerad/cameras/sensor2_i2c.h b/system/camerad/cameras/sensor2_i2c.h similarity index 100% rename from selfdrive/camerad/cameras/sensor2_i2c.h rename to system/camerad/cameras/sensor2_i2c.h diff --git a/selfdrive/camerad/imgproc/conv.cl b/system/camerad/imgproc/conv.cl similarity index 100% rename from selfdrive/camerad/imgproc/conv.cl rename to system/camerad/imgproc/conv.cl diff --git a/selfdrive/camerad/imgproc/pool.cl b/system/camerad/imgproc/pool.cl similarity index 100% rename from selfdrive/camerad/imgproc/pool.cl rename to system/camerad/imgproc/pool.cl diff --git a/selfdrive/camerad/imgproc/utils.cc b/system/camerad/imgproc/utils.cc similarity index 98% rename from selfdrive/camerad/imgproc/utils.cc rename to system/camerad/imgproc/utils.cc index a88b8f4bb1..a7bbeb9e86 100644 --- a/selfdrive/camerad/imgproc/utils.cc +++ b/system/camerad/imgproc/utils.cc @@ -1,4 +1,4 @@ -#include "selfdrive/camerad/imgproc/utils.h" +#include "system/camerad/imgproc/utils.h" #include #include diff --git a/selfdrive/camerad/imgproc/utils.h b/system/camerad/imgproc/utils.h similarity index 100% rename from selfdrive/camerad/imgproc/utils.h rename to system/camerad/imgproc/utils.h diff --git a/selfdrive/camerad/include/media/cam_cpas.h b/system/camerad/include/media/cam_cpas.h similarity index 100% rename from selfdrive/camerad/include/media/cam_cpas.h rename to system/camerad/include/media/cam_cpas.h diff --git a/selfdrive/camerad/include/media/cam_defs.h b/system/camerad/include/media/cam_defs.h similarity index 100% rename from selfdrive/camerad/include/media/cam_defs.h rename to system/camerad/include/media/cam_defs.h diff --git a/selfdrive/camerad/include/media/cam_fd.h b/system/camerad/include/media/cam_fd.h similarity index 100% rename from selfdrive/camerad/include/media/cam_fd.h rename to system/camerad/include/media/cam_fd.h diff --git a/selfdrive/camerad/include/media/cam_icp.h b/system/camerad/include/media/cam_icp.h similarity index 100% rename from selfdrive/camerad/include/media/cam_icp.h rename to system/camerad/include/media/cam_icp.h diff --git a/selfdrive/camerad/include/media/cam_isp.h b/system/camerad/include/media/cam_isp.h similarity index 100% rename from selfdrive/camerad/include/media/cam_isp.h rename to system/camerad/include/media/cam_isp.h diff --git a/selfdrive/camerad/include/media/cam_isp_ife.h b/system/camerad/include/media/cam_isp_ife.h similarity index 100% rename from selfdrive/camerad/include/media/cam_isp_ife.h rename to system/camerad/include/media/cam_isp_ife.h diff --git a/selfdrive/camerad/include/media/cam_isp_vfe.h b/system/camerad/include/media/cam_isp_vfe.h similarity index 100% rename from selfdrive/camerad/include/media/cam_isp_vfe.h rename to system/camerad/include/media/cam_isp_vfe.h diff --git a/selfdrive/camerad/include/media/cam_jpeg.h b/system/camerad/include/media/cam_jpeg.h similarity index 100% rename from selfdrive/camerad/include/media/cam_jpeg.h rename to system/camerad/include/media/cam_jpeg.h diff --git a/selfdrive/camerad/include/media/cam_lrme.h b/system/camerad/include/media/cam_lrme.h similarity index 100% rename from selfdrive/camerad/include/media/cam_lrme.h rename to system/camerad/include/media/cam_lrme.h diff --git a/selfdrive/camerad/include/media/cam_req_mgr.h b/system/camerad/include/media/cam_req_mgr.h similarity index 100% rename from selfdrive/camerad/include/media/cam_req_mgr.h rename to system/camerad/include/media/cam_req_mgr.h diff --git a/selfdrive/camerad/include/media/cam_sensor.h b/system/camerad/include/media/cam_sensor.h similarity index 100% rename from selfdrive/camerad/include/media/cam_sensor.h rename to system/camerad/include/media/cam_sensor.h diff --git a/selfdrive/camerad/include/media/cam_sensor_cmn_header.h b/system/camerad/include/media/cam_sensor_cmn_header.h similarity index 100% rename from selfdrive/camerad/include/media/cam_sensor_cmn_header.h rename to system/camerad/include/media/cam_sensor_cmn_header.h diff --git a/selfdrive/camerad/include/media/cam_sync.h b/system/camerad/include/media/cam_sync.h similarity index 100% rename from selfdrive/camerad/include/media/cam_sync.h rename to system/camerad/include/media/cam_sync.h diff --git a/selfdrive/camerad/include/msm_cam_sensor.h b/system/camerad/include/msm_cam_sensor.h similarity index 100% rename from selfdrive/camerad/include/msm_cam_sensor.h rename to system/camerad/include/msm_cam_sensor.h diff --git a/selfdrive/camerad/include/msm_camsensor_sdk.h b/system/camerad/include/msm_camsensor_sdk.h similarity index 100% rename from selfdrive/camerad/include/msm_camsensor_sdk.h rename to system/camerad/include/msm_camsensor_sdk.h diff --git a/selfdrive/camerad/include/msmb_camera.h b/system/camerad/include/msmb_camera.h similarity index 100% rename from selfdrive/camerad/include/msmb_camera.h rename to system/camerad/include/msmb_camera.h diff --git a/selfdrive/camerad/include/msmb_isp.h b/system/camerad/include/msmb_isp.h similarity index 100% rename from selfdrive/camerad/include/msmb_isp.h rename to system/camerad/include/msmb_isp.h diff --git a/selfdrive/camerad/include/msmb_ispif.h b/system/camerad/include/msmb_ispif.h similarity index 100% rename from selfdrive/camerad/include/msmb_ispif.h rename to system/camerad/include/msmb_ispif.h diff --git a/selfdrive/camerad/main.cc b/system/camerad/main.cc similarity index 89% rename from selfdrive/camerad/main.cc rename to system/camerad/main.cc index 32899a8547..c1f38f2224 100644 --- a/selfdrive/camerad/main.cc +++ b/system/camerad/main.cc @@ -1,4 +1,4 @@ -#include "selfdrive/camerad/cameras/camera_common.h" +#include "system/camerad/cameras/camera_common.h" #include diff --git a/selfdrive/camerad/snapshot/__init__.py b/system/camerad/snapshot/__init__.py similarity index 100% rename from selfdrive/camerad/snapshot/__init__.py rename to system/camerad/snapshot/__init__.py diff --git a/selfdrive/camerad/snapshot/snapshot.py b/system/camerad/snapshot/snapshot.py similarity index 98% rename from selfdrive/camerad/snapshot/snapshot.py rename to system/camerad/snapshot/snapshot.py index fa88849b69..9a81937eec 100755 --- a/selfdrive/camerad/snapshot/snapshot.py +++ b/system/camerad/snapshot/snapshot.py @@ -13,7 +13,7 @@ from system.hardware import PC from selfdrive.controls.lib.alertmanager import set_offroad_alert from selfdrive.manager.process_config import managed_processes -LM_THRESH = 120 # defined in selfdrive/camerad/imgproc/utils.h +LM_THRESH = 120 # defined in system/camerad/imgproc/utils.h VISION_STREAMS = { "roadCameraState": VisionStreamType.VISION_STREAM_ROAD, diff --git a/selfdrive/camerad/test/.gitignore b/system/camerad/test/.gitignore similarity index 100% rename from selfdrive/camerad/test/.gitignore rename to system/camerad/test/.gitignore diff --git a/selfdrive/camerad/test/ae_gray_test.cc b/system/camerad/test/ae_gray_test.cc similarity index 97% rename from selfdrive/camerad/test/ae_gray_test.cc rename to system/camerad/test/ae_gray_test.cc index 69ef2ac6de..aabd7534ee 100644 --- a/selfdrive/camerad/test/ae_gray_test.cc +++ b/system/camerad/test/ae_gray_test.cc @@ -8,7 +8,7 @@ #include #include "common/util.h" -#include "selfdrive/camerad/cameras/camera_common.h" +#include "system/camerad/cameras/camera_common.h" int main() { // set up fake camerabuf diff --git a/selfdrive/camerad/test/ae_gray_test.h b/system/camerad/test/ae_gray_test.h similarity index 100% rename from selfdrive/camerad/test/ae_gray_test.h rename to system/camerad/test/ae_gray_test.h diff --git a/selfdrive/camerad/test/camera_test.h b/system/camerad/test/camera_test.h similarity index 100% rename from selfdrive/camerad/test/camera_test.h rename to system/camerad/test/camera_test.h diff --git a/selfdrive/camerad/test/check_skips.py b/system/camerad/test/check_skips.py similarity index 100% rename from selfdrive/camerad/test/check_skips.py rename to system/camerad/test/check_skips.py diff --git a/selfdrive/camerad/test/frame_test.py b/system/camerad/test/frame_test.py similarity index 100% rename from selfdrive/camerad/test/frame_test.py rename to system/camerad/test/frame_test.py diff --git a/selfdrive/camerad/test/get_thumbnails_for_segment.py b/system/camerad/test/get_thumbnails_for_segment.py similarity index 100% rename from selfdrive/camerad/test/get_thumbnails_for_segment.py rename to system/camerad/test/get_thumbnails_for_segment.py diff --git a/selfdrive/camerad/test/stress_restart.sh b/system/camerad/test/stress_restart.sh similarity index 100% rename from selfdrive/camerad/test/stress_restart.sh rename to system/camerad/test/stress_restart.sh diff --git a/selfdrive/camerad/test/test_camerad.py b/system/camerad/test/test_camerad.py similarity index 100% rename from selfdrive/camerad/test/test_camerad.py rename to system/camerad/test/test_camerad.py diff --git a/selfdrive/camerad/test/test_exposure.py b/system/camerad/test/test_exposure.py similarity index 96% rename from selfdrive/camerad/test/test_exposure.py rename to system/camerad/test/test_exposure.py index f42d0bfbe3..8cce7e7ffa 100755 --- a/selfdrive/camerad/test/test_exposure.py +++ b/system/camerad/test/test_exposure.py @@ -4,7 +4,7 @@ import unittest import numpy as np from selfdrive.test.helpers import with_processes -from selfdrive.camerad.snapshot.snapshot import get_snapshots +from system.camerad.snapshot.snapshot import get_snapshots from system.hardware import TICI diff --git a/selfdrive/camerad/transforms/rgb_to_yuv.cc b/system/camerad/transforms/rgb_to_yuv.cc similarity index 96% rename from selfdrive/camerad/transforms/rgb_to_yuv.cc rename to system/camerad/transforms/rgb_to_yuv.cc index 63e032e2dc..5e51579cf9 100644 --- a/selfdrive/camerad/transforms/rgb_to_yuv.cc +++ b/system/camerad/transforms/rgb_to_yuv.cc @@ -1,4 +1,4 @@ -#include "selfdrive/camerad/transforms/rgb_to_yuv.h" +#include "system/camerad/transforms/rgb_to_yuv.h" #include #include diff --git a/selfdrive/camerad/transforms/rgb_to_yuv.cl b/system/camerad/transforms/rgb_to_yuv.cl similarity index 100% rename from selfdrive/camerad/transforms/rgb_to_yuv.cl rename to system/camerad/transforms/rgb_to_yuv.cl diff --git a/selfdrive/camerad/transforms/rgb_to_yuv.h b/system/camerad/transforms/rgb_to_yuv.h similarity index 100% rename from selfdrive/camerad/transforms/rgb_to_yuv.h rename to system/camerad/transforms/rgb_to_yuv.h diff --git a/selfdrive/camerad/transforms/rgb_to_yuv_test.cc b/system/camerad/transforms/rgb_to_yuv_test.cc similarity index 99% rename from selfdrive/camerad/transforms/rgb_to_yuv_test.cc rename to system/camerad/transforms/rgb_to_yuv_test.cc index c960d168de..2f909e3b73 100644 --- a/selfdrive/camerad/transforms/rgb_to_yuv_test.cc +++ b/system/camerad/transforms/rgb_to_yuv_test.cc @@ -30,7 +30,7 @@ #include #include "libyuv.h" -#include "selfdrive/camerad/transforms/rgb_to_yuv.h" +#include "system/camerad/transforms/rgb_to_yuv.h" #include "common/clutil.h" static inline double millis_since_boot() { diff --git a/tools/webcam/README.md b/tools/webcam/README.md index 48e5accb2a..1e07bdbbe6 100644 --- a/tools/webcam/README.md +++ b/tools/webcam/README.md @@ -23,14 +23,14 @@ git clone https://github.com/commaai/openpilot.git ``` cd ~/openpilot ``` -- check out selfdrive/camerad/cameras/camera_webcam.cc lines 72 and 146 before building if any camera is upside down +- check out system/camerad/cameras/camera_webcam.cc lines 72 and 146 before building if any camera is upside down ``` USE_WEBCAM=1 scons -j$(nproc) ``` ## Connect the hardware - Connect the road facing camera first, then the driver facing camera -- (default indexes are 1 and 2; can be modified in selfdrive/camerad/cameras/camera_webcam.cc) +- (default indexes are 1 and 2; can be modified in system/camerad/cameras/camera_webcam.cc) - Connect your computer to panda ## GO From 1baf0e3f4a40084a43c6a6d4d1a43b99e4e90532 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 19 Jun 2022 15:49:38 -0700 Subject: [PATCH 090/302] sim: update cl kernel path --- tools/sim/bridge.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index ae65e8deb8..faf67c3ef5 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -81,7 +81,7 @@ class Camerad: cl_arg = f" -DHEIGHT={H} -DWIDTH={W} -DRGB_STRIDE={W * 3} -DUV_WIDTH={W // 2} -DUV_HEIGHT={H // 2} -DRGB_SIZE={W * H} -DCL_DEBUG " # TODO: move rgb_to_yuv.cl to local dir once the frame stream camera is removed - kernel_fn = os.path.join(BASEDIR, "selfdrive", "camerad", "transforms", "rgb_to_yuv.cl") + kernel_fn = os.path.join(BASEDIR, "system", "camerad", "transforms", "rgb_to_yuv.cl") with open(kernel_fn) as f: prg = cl.Program(self.ctx, f.read()).build(cl_arg) self.krnl = prg.rgb_to_yuv From 7a815418d600bed1e2500b4fdbe4f1958f432555 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 20 Jun 2022 12:12:18 +0200 Subject: [PATCH 091/302] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 6faf34064b..f445245a8f 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 6faf34064b70ab98c241d4a1cd9006b09ecaadfc +Subproject commit f445245a8fbe01c33a372d82897575e7acc08ffc From e2757208622e29a00d5191d7d2f971cafcf61602 Mon Sep 17 00:00:00 2001 From: Robbe Derks Date: Mon, 20 Jun 2022 12:15:39 +0200 Subject: [PATCH 092/302] Add new message to Tesla AP2 fingerprint (#24912) * add new message * fix spacing * add space --- selfdrive/car/tesla/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/tesla/values.py b/selfdrive/car/tesla/values.py index 2ed4c963ee..296169587a 100644 --- a/selfdrive/car/tesla/values.py +++ b/selfdrive/car/tesla/values.py @@ -22,7 +22,7 @@ CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { FINGERPRINTS = { CAR.AP2_MODELS: [ { - 1: 8, 3: 8, 14: 8, 21: 4, 69: 8, 109: 4, 257: 3, 264: 8, 277: 6, 280: 6, 293: 4, 296: 4, 309: 5, 325: 8, 328: 5, 336: 8, 341: 8, 360: 7, 373: 8, 389: 8, 415: 8, 513: 5, 516: 8, 518: 8, 520: 4, 522: 8, 524: 8, 526: 8, 532: 3, 536: 8, 537: 3, 538: 8, 542: 8, 551: 5, 552: 2, 556: 8, 558: 8, 568: 8, 569: 8, 574: 8, 576: 3, 577: 8, 582: 5, 583: 8, 584: 4, 585: 8, 590: 8, 601: 8, 606: 8, 608: 1, 622: 8, 627: 6, 638: 8, 641: 8, 643: 8, 692: 8, 693: 8, 695: 8, 696: 8, 697: 8, 699: 8, 700: 8, 701: 8, 702: 8, 703: 8, 704: 8, 708: 8, 709: 8, 710: 8, 711: 8, 712: 8, 728: 8, 744: 8, 760: 8, 772: 8, 775: 8, 776: 8, 777: 8, 778: 8, 782: 8, 788: 8, 791: 8, 792: 8, 796: 2, 797: 8, 798: 6, 799: 8, 804: 8, 805: 8, 807: 8, 808: 1, 811: 8, 812: 8, 813: 8, 814: 5, 815: 8, 820: 8, 823: 8, 824: 8, 829: 8, 830: 5, 836: 8, 840: 8, 845: 8, 846: 5, 848: 8, 852: 8, 853: 8, 856: 4, 857: 6, 861: 8, 862: 5, 872: 8, 876: 8, 877: 8, 879: 8, 880: 8, 882: 8, 884: 8, 888: 8, 893: 8, 894: 8, 901: 6, 904: 3, 905: 8, 906: 8, 908: 2, 909: 8, 910: 8, 912: 8, 920: 8, 921: 8, 925: 4, 926: 6, 936: 8, 941: 8, 949: 8, 952: 8, 953: 6, 968: 8, 969: 6, 970: 8, 971: 8, 977: 8, 984: 8, 987: 8, 990: 8, 1000: 8, 1001: 8, 1006: 8, 1007: 8, 1008: 8, 1010: 6, 1014: 1, 1015: 8, 1016: 8, 1017: 8, 1018: 8, 1020: 8, 1026: 8, 1028: 8, 1029: 8, 1030: 8, 1032: 1, 1033: 1, 1034: 8, 1048: 1, 1049: 8, 1061: 8, 1064: 8, 1065: 8, 1070: 8, 1080: 8, 1081: 8, 1097: 8, 1113: 8, 1129: 8, 1145: 8, 1160: 4, 1177: 8, 1281: 8, 1328: 8, 1329: 8, 1332: 8, 1335: 8, 1337: 8, 1353: 8, 1368: 8, 1412: 8, 1436: 8, 1476: 8, 1481: 8, 1497: 8, 1513: 8, 1519: 8, 1601: 8, 1605: 8, 1617: 8, 1621: 8, 1625: 8, 1800: 4, 1804: 8, 1812: 8, 1815: 8, 1816: 8, 1824: 8, 1828: 8, 1831: 8, 1832: 8, 1840: 8, 1848: 8, 1864: 8, 1880: 8, 1892: 8, 1896: 8, 1912: 8, 1960: 8, 1992: 8, 2008: 3, 2015: 8, 2043: 5, 2045: 4 + 1: 8, 3: 8, 14: 8, 21: 4, 69: 8, 109: 4, 257: 3, 264: 8, 277: 6, 280: 6, 293: 4, 296: 4, 309: 5, 325: 8, 328: 5, 336: 8, 341: 8, 360: 7, 373: 8, 389: 8, 415: 8, 513: 5, 516: 8, 518: 8, 520: 4, 522: 8, 524: 8, 526: 8, 532: 3, 536: 8, 537: 3, 538: 8, 542: 8, 551: 5, 552: 2, 556: 8, 558: 8, 568: 8, 569: 8, 574: 8, 576: 3, 577: 8, 582: 5, 583: 8, 584: 4, 585: 8, 590: 8, 601: 8, 606: 8, 608: 1, 622: 8, 627: 6, 638: 8, 641: 8, 643: 8, 692: 8, 693: 8, 695: 8, 696: 8, 697: 8, 699: 8, 700: 8, 701: 8, 702: 8, 703: 8, 704: 8, 708: 8, 709: 8, 710: 8, 711: 8, 712: 8, 728: 8, 744: 8, 760: 8, 772: 8, 775: 8, 776: 8, 777: 8, 778: 8, 782: 8, 788: 8, 791: 8, 792: 8, 796: 2, 797: 8, 798: 6, 799: 8, 804: 8, 805: 8, 807: 8, 808: 1, 811: 8, 812: 8, 813: 8, 814: 5, 815: 8, 820: 8, 823: 8, 824: 8, 829: 8, 830: 5, 836: 8, 840: 8, 845: 8, 846: 5, 848: 8, 852: 8, 853: 8, 856: 4, 857: 6, 861: 8, 862: 5, 872: 8, 876: 8, 877: 8, 879: 8, 880: 8, 882: 8, 884: 8, 888: 8, 893: 8, 894: 8, 901: 6, 904: 3, 905: 8, 906: 8, 908: 2, 909: 8, 910: 8, 912: 8, 920: 8, 921: 8, 925: 4, 926: 6, 936: 8, 941: 8, 949: 8, 952: 8, 953: 6, 968: 8, 969: 6, 970: 8, 971: 8, 977: 8, 984: 8, 987: 8, 990: 8, 1000: 8, 1001: 8, 1006: 8, 1007: 8, 1008: 8, 1010: 6, 1014: 1, 1015: 8, 1016: 8, 1017: 8, 1018: 8, 1020: 8, 1026: 8, 1028: 8, 1029: 8, 1030: 8, 1032: 1, 1033: 1, 1034: 8, 1048: 1, 1049: 8, 1061: 8, 1064: 8, 1065: 8, 1070: 8, 1080: 8, 1081: 8, 1097: 8, 1113: 8, 1129: 8, 1145: 8, 1160: 4, 1177: 8, 1281: 8, 1328: 8, 1329: 8, 1332: 8, 1335: 8, 1337: 8, 1353: 8, 1368: 8, 1412: 8, 1436: 8, 1476: 8, 1481: 8, 1497: 8, 1513: 8, 1519: 8, 1601: 8, 1605: 8, 1617: 8, 1621: 8, 1625: 8, 1665: 8, 1800: 4, 1804: 8, 1812: 8, 1815: 8, 1816: 8, 1824: 8, 1828: 8, 1831: 8, 1832: 8, 1840: 8, 1848: 8, 1864: 8, 1880: 8, 1892: 8, 1896: 8, 1912: 8, 1960: 8, 1992: 8, 2008: 3, 2015: 8, 2043: 5, 2045: 4 }, ], CAR.AP1_MODELS: [ From 1c4b145aa4d85b7107254be6618592781ff7323e Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Mon, 20 Jun 2022 14:24:11 +0200 Subject: [PATCH 093/302] Improve laikad cpu usage. Less pos fix. Less local imports (#24887) * Improve laikad cpu usage. Less pos fix. Not local imports * Add laika to files_common * Add laika to dockerfile sim * Fix * Fix * undo --- release/files_common | 1 + selfdrive/locationd/laikad.py | 35 ++++++++++++---------- selfdrive/locationd/models/gnss_helpers.py | 4 +-- tools/sim/Dockerfile.sim | 1 + 4 files changed, 23 insertions(+), 18 deletions(-) diff --git a/release/files_common b/release/files_common index ecb71b4e69..7274ee9bf6 100644 --- a/release/files_common +++ b/release/files_common @@ -414,6 +414,7 @@ pyextra/.gitignore pyextra/acados_template/** rednose/** +laika/** cereal/.gitignore cereal/__init__.py diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 6fd70875ac..f1997bceb0 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -39,7 +39,9 @@ class Laikad: self.save_ephemeris = save_ephemeris self.load_cache() self.posfix_functions = {constellation: get_posfix_sympy_fun(constellation) for constellation in (ConstellationId.GPS, ConstellationId.GLONASS)} - self.last_pos_fix = last_known_position + self.last_pos_fix = last_known_position if last_known_position is not None else [] + self.last_pos_residual = [] + self.last_pos_fix_t = None def load_cache(self): cache = Params().get(EPHEMERIS_CACHE) @@ -62,23 +64,26 @@ class Laikad: def process_ublox_msg(self, ublox_msg, ublox_mono_time: int, block=False): if ublox_msg.which == 'measurementReport': + t = ublox_mono_time * 1e-9 report = ublox_msg.measurementReport if report.gpsWeek > 0: latest_msg_t = GPSTime(report.gpsWeek, report.rcvTow) self.fetch_orbits(latest_msg_t + SECS_IN_MIN, block) + new_meas = read_raw_ublox(report) processed_measurements = process_measurements(new_meas, self.astro_dog) - min_measurements = 5 if any(p.constellation_id == ConstellationId.GLONASS for p in processed_measurements) else 4 - pos_fix, pos_fix_residual = calc_pos_fix_gauss_newton(processed_measurements, self.posfix_functions, min_measurements=min_measurements) - if len(pos_fix) > 0: - self.last_pos_fix = pos_fix[:3] - est_pos = self.last_pos_fix + if self.last_pos_fix_t is None or abs(self.last_pos_fix_t - t) >= 2: + min_measurements = 5 if any(p.constellation_id == ConstellationId.GLONASS for p in processed_measurements) else 4 + pos_fix, pos_fix_residual = calc_pos_fix_gauss_newton(processed_measurements, self.posfix_functions, min_measurements=min_measurements) + if len(pos_fix) > 0: + self.last_pos_fix = pos_fix[:3] + self.last_pos_residual = pos_fix_residual + self.last_pos_fix_t = t - corrected_measurements = correct_measurements(processed_measurements, est_pos, self.astro_dog) if est_pos is not None else [] + corrected_measurements = correct_measurements(processed_measurements, self.last_pos_fix, self.astro_dog) if self.last_pos_fix_t is not None else [] - t = ublox_mono_time * 1e-9 - self.update_localizer(est_pos, t, corrected_measurements) + self.update_localizer(self.last_pos_fix, t, corrected_measurements) kf_valid = all(self.kf_valid(t)) ecef_pos = self.gnss_kf.x[GStates.ECEF_POS].tolist() ecef_vel = self.gnss_kf.x[GStates.ECEF_VELOCITY].tolist() @@ -94,7 +99,7 @@ class Laikad: "gpsTimeOfWeek": report.rcvTow, "positionECEF": measurement_msg(value=ecef_pos, std=pos_std, valid=kf_valid), "velocityECEF": measurement_msg(value=ecef_vel, std=vel_std, valid=kf_valid), - "positionFixECEF": measurement_msg(value=pos_fix, std=pos_fix_residual, valid=len(pos_fix) > 0), + "positionFixECEF": measurement_msg(value=self.last_pos_fix, std=self.last_pos_residual, valid=self.last_pos_fix_t == t), "ubloxMonoTime": ublox_mono_time, "correctedMeasurements": meas_msgs } @@ -116,7 +121,7 @@ class Laikad: cloudlog.error("Time gap of over 10s detected, gnss kalman reset") elif not valid[2]: cloudlog.error("Gnss kalman filter state is nan") - if est_pos is not None: + if len(est_pos) > 0: cloudlog.info(f"Reset kalman filter with {est_pos}") self.init_gnss_localizer(est_pos) else: @@ -211,13 +216,13 @@ def kf_add_observations(gnss_kf: GNSSKalman, t: float, measurements: List[GNSSMe m_arr = m.as_array() if m.constellation_id == ConstellationId.GPS: ekf_data[ObservationKind.PSEUDORANGE_GPS].append(m_arr) - ekf_data[ObservationKind.PSEUDORANGE_RATE_GPS].append(m_arr) elif m.constellation_id == ConstellationId.GLONASS: ekf_data[ObservationKind.PSEUDORANGE_GLONASS].append(m_arr) - ekf_data[ObservationKind.PSEUDORANGE_RATE_GLONASS].append(m_arr) - + ekf_data[ObservationKind.PSEUDORANGE_RATE_GPS] = ekf_data[ObservationKind.PSEUDORANGE_GPS] + ekf_data[ObservationKind.PSEUDORANGE_RATE_GLONASS] = ekf_data[ObservationKind.PSEUDORANGE_GLONASS] for kind, data in ekf_data.items(): - gnss_kf.predict_and_observe(t, kind, data) + if len(data) >0: + gnss_kf.predict_and_observe(t, kind, data) class CacheSerializer(json.JSONEncoder): diff --git a/selfdrive/locationd/models/gnss_helpers.py b/selfdrive/locationd/models/gnss_helpers.py index a3bcbc0002..b6c1771ec6 100644 --- a/selfdrive/locationd/models/gnss_helpers.py +++ b/selfdrive/locationd/models/gnss_helpers.py @@ -1,16 +1,14 @@ import numpy as np +from laika.raw_gnss import GNSSMeasurement def parse_prr(m): - from laika.raw_gnss import GNSSMeasurement sat_pos_vel_i = np.concatenate((m[GNSSMeasurement.SAT_POS], m[GNSSMeasurement.SAT_VEL])) R_i = np.atleast_2d(m[GNSSMeasurement.PRR_STD]**2) z_i = m[GNSSMeasurement.PRR] return z_i, R_i, sat_pos_vel_i - def parse_pr(m): - from laika.raw_gnss import GNSSMeasurement pseudorange = m[GNSSMeasurement.PR] pseudorange_stdev = m[GNSSMeasurement.PR_STD] sat_pos_freq_i = np.concatenate((m[GNSSMeasurement.SAT_POS], diff --git a/tools/sim/Dockerfile.sim b/tools/sim/Dockerfile.sim index 0d6e8e584c..3692d48e0f 100644 --- a/tools/sim/Dockerfile.sim +++ b/tools/sim/Dockerfile.sim @@ -18,6 +18,7 @@ COPY ./third_party $HOME/openpilot/third_party COPY ./pyextra $HOME/openpilot/pyextra COPY ./site_scons $HOME/openpilot/site_scons COPY ./rednose $HOME/openpilot/rednose +COPY ./laika $HOME/openpilot/laika COPY ./common $HOME/openpilot/common COPY ./opendbc $HOME/openpilot/opendbc COPY ./cereal $HOME/openpilot/cereal From 8270c1c1a3584c1244f12143fc1314cdbbb05541 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 20 Jun 2022 19:14:43 +0200 Subject: [PATCH 094/302] ui: onroad widget check if sockets alive (#24913) * ui: onroad widget check if socket alive * cleanup --- selfdrive/ui/qt/onroad.cc | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 84b538411b..45bf41ba2d 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -172,22 +172,28 @@ NvgWindow::NvgWindow(VisionStreamType type, QWidget* parent) : fps_filter(UI_FRE void NvgWindow::updateState(const UIState &s) { const int SET_SPEED_NA = 255; const SubMaster &sm = *(s.sm); + + const bool cs_alive = sm.alive("controlsState"); + const bool nav_alive = sm.alive("navInstruction") && sm["navInstruction"].getValid(); + const auto cs = sm["controlsState"].getControlsState(); - float set_speed = cs.getVCruise(); + float set_speed = cs_alive ? cs.getVCruise() : SET_SPEED_NA; bool cruise_set = set_speed > 0 && (int)set_speed != SET_SPEED_NA; if (cruise_set && !s.scene.is_metric) { set_speed *= KM_TO_MILE; } - float cur_speed = std::max(0.0, sm["carState"].getCarState().getVEgo() * (s.scene.is_metric ? MS_TO_KPH : MS_TO_MPH)); + + float cur_speed = cs_alive ? std::max(0.0, sm["carState"].getCarState().getVEgo()) : 0.0; + cur_speed *= s.scene.is_metric ? MS_TO_KPH : MS_TO_MPH; auto speed_limit_sign = sm["navInstruction"].getNavInstruction().getSpeedLimitSign(); - float speed_limit = sm["navInstruction"].getValid() ? sm["navInstruction"].getNavInstruction().getSpeedLimit() : 0.0; + float speed_limit = nav_alive ? sm["navInstruction"].getNavInstruction().getSpeedLimit() : 0.0; speed_limit *= (s.scene.is_metric ? MS_TO_KPH : MS_TO_MPH); setProperty("speedLimit", speed_limit); - setProperty("has_us_speed_limit", sm["navInstruction"].getValid() && speed_limit_sign == cereal::NavInstruction::SpeedLimitSign::MUTCD); - setProperty("has_eu_speed_limit", sm["navInstruction"].getValid() && speed_limit_sign == cereal::NavInstruction::SpeedLimitSign::VIENNA); + setProperty("has_us_speed_limit", nav_alive && speed_limit_sign == cereal::NavInstruction::SpeedLimitSign::MUTCD); + setProperty("has_eu_speed_limit", nav_alive && speed_limit_sign == cereal::NavInstruction::SpeedLimitSign::VIENNA); setProperty("is_cruise_set", cruise_set); setProperty("speed", cur_speed); From 1f2f9ea9c9dc37bdea9c6e32e4cb8f88ea0a34bf Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Mon, 20 Jun 2022 16:24:51 -0700 Subject: [PATCH 095/302] fullframe DM model (#24860) * Revert "put cereal on master" This reverts commit a8ccd8f838aff958a60546de04bf42220567b288. * Revert "Revert fullframe DM model (#24812)" This reverts commit c646eeee0ac54925db5afc51b95c5d869d6dba68. * revert revert cereal * clip6 * 0.8 is fair * Fiction compensation should be based on error * Update refs * Add deadzone * not that * good mg * ref * ref * ee8f * minor tweak * ref * recompile * ref * cereal * match driverstatus * new ref * new ref * pass token through jenkins credentials * quote * fix snpe dead weights * final ref Co-authored-by: Harald Schafer Co-authored-by: Adeeb Shihadeh --- Jenkinsfile | 2 + cereal | 2 +- common/modeldata.h | 6 - selfdrive/modeld/dmonitoringmodeld.cc | 6 +- selfdrive/modeld/models/dmonitoring.cc | 234 ++++++------------ selfdrive/modeld/models/dmonitoring.h | 33 ++- .../modeld/models/dmonitoring_model.current | 4 +- .../modeld/models/dmonitoring_model.onnx | 4 +- .../modeld/models/dmonitoring_model_q.dlc | 4 +- selfdrive/modeld/runners/onnx_runner.py | 21 +- selfdrive/modeld/runners/onnxmodel.cc | 6 +- selfdrive/modeld/runners/onnxmodel.h | 3 +- selfdrive/modeld/runners/snpemodel.cc | 12 +- selfdrive/modeld/runners/snpemodel.h | 3 +- selfdrive/monitoring/dmonitoringd.py | 7 +- selfdrive/monitoring/driver_monitor.py | 94 +++---- selfdrive/monitoring/test_monitoring.py | 24 +- selfdrive/test/process_replay/model_replay.py | 8 +- .../process_replay/model_replay_ref_commit | 2 +- .../test/process_replay/process_replay.py | 2 +- selfdrive/test/test_onroad.py | 6 +- selfdrive/ui/qt/offroad/driverview.cc | 43 ++-- selfdrive/ui/qt/widgets/cameraview.cc | 9 +- system/hardware/tici/test_power_draw.py | 2 +- 24 files changed, 229 insertions(+), 308 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index dba1f257d6..0fa623fbcd 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -10,6 +10,7 @@ export TEST_DIR=${env.TEST_DIR} export SOURCE_DIR=${env.SOURCE_DIR} export GIT_BRANCH=${env.GIT_BRANCH} export GIT_COMMIT=${env.GIT_COMMIT} +export AZURE_TOKEN='${env.AZURE_TOKEN}' source ~/.bash_profile if [ -f /TICI ]; then @@ -45,6 +46,7 @@ pipeline { CI = "1" TEST_DIR = "/data/openpilot" SOURCE_DIR = "/data/openpilot_source/" + AZURE_TOKEN = credentials('azure_token') } options { timeout(time: 4, unit: 'HOURS') diff --git a/cereal b/cereal index f445245a8f..05bbdafb67 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit f445245a8fbe01c33a372d82897575e7acc08ffc +Subproject commit 05bbdafb67060ffb62e6e0af812935494ad91933 diff --git a/common/modeldata.h b/common/modeldata.h index aee9fdfd83..b193841416 100644 --- a/common/modeldata.h +++ b/common/modeldata.h @@ -24,12 +24,6 @@ constexpr auto T_IDXS_FLOAT = build_idxs(10.0); constexpr auto X_IDXS = build_idxs(192.0); constexpr auto X_IDXS_FLOAT = build_idxs(192.0); -namespace tici_dm_crop { - const int x_offset = -72; - const int y_offset = -144; - const int width = 954; -}; - const mat3 fcam_intrinsic_matrix = (mat3){{2648.0, 0.0, 1928.0 / 2, 0.0, 2648.0, 1208.0 / 2, 0.0, 0.0, 1.0}}; diff --git a/selfdrive/modeld/dmonitoringmodeld.cc b/selfdrive/modeld/dmonitoringmodeld.cc index 68c49572e6..cde13a9bee 100644 --- a/selfdrive/modeld/dmonitoringmodeld.cc +++ b/selfdrive/modeld/dmonitoringmodeld.cc @@ -12,7 +12,7 @@ ExitHandler do_exit; void run_model(DMonitoringModelState &model, VisionIpcClient &vipc_client) { - PubMaster pm({"driverState"}); + PubMaster pm({"driverStateV2"}); SubMaster sm({"liveCalibration"}); float calib[CALIB_LEN] = {0}; double last = 0; @@ -31,11 +31,11 @@ void run_model(DMonitoringModelState &model, VisionIpcClient &vipc_client) { } double t1 = millis_since_boot(); - DMonitoringResult res = dmonitoring_eval_frame(&model, buf->addr, buf->width, buf->height, buf->stride, buf->uv_offset, calib); + DMonitoringModelResult model_res = dmonitoring_eval_frame(&model, buf->addr, buf->width, buf->height, buf->stride, buf->uv_offset, calib); double t2 = millis_since_boot(); // send dm packet - dmonitoring_publish(pm, extra.frame_id, res, (t2 - t1) / 1000.0, model.output); + dmonitoring_publish(pm, extra.frame_id, model_res, (t2 - t1) / 1000.0, model.output); //printf("dmonitoring process: %.2fms, from last %.2fms\n", t2 - t1, t1 - last); last = t1; diff --git a/selfdrive/modeld/models/dmonitoring.cc b/selfdrive/modeld/models/dmonitoring.cc index 71da8dad53..8c7e14edb2 100644 --- a/selfdrive/modeld/models/dmonitoring.cc +++ b/selfdrive/modeld/models/dmonitoring.cc @@ -10,8 +10,8 @@ #include "selfdrive/modeld/models/dmonitoring.h" -constexpr int MODEL_WIDTH = 320; -constexpr int MODEL_HEIGHT = 640; +constexpr int MODEL_WIDTH = 1440; +constexpr int MODEL_HEIGHT = 960; template static inline T *get_buffer(std::vector &buf, const size_t size) { @@ -19,199 +19,115 @@ static inline T *get_buffer(std::vector &buf, const size_t size) { return buf.data(); } -static inline void init_yuv_buf(std::vector &buf, const int width, int height) { - uint8_t *y = get_buffer(buf, width * height * 3 / 2); - uint8_t *u = y + width * height; - uint8_t *v = u + (width / 2) * (height / 2); - - // needed on comma two to make the padded border black - // equivalent to RGB(0,0,0) in YUV space - memset(y, 16, width * height); - memset(u, 128, (width / 2) * (height / 2)); - memset(v, 128, (width / 2) * (height / 2)); -} - void dmonitoring_init(DMonitoringModelState* s) { s->is_rhd = Params().getBool("IsRHD"); - for (int x = 0; x < std::size(s->tensor); ++x) { - s->tensor[x] = (x - 128.f) * 0.0078125f; - } - init_yuv_buf(s->resized_buf, MODEL_WIDTH, MODEL_HEIGHT); #ifdef USE_ONNX_MODEL - s->m = new ONNXModel("models/dmonitoring_model.onnx", &s->output[0], OUTPUT_SIZE, USE_DSP_RUNTIME); + s->m = new ONNXModel("models/dmonitoring_model.onnx", &s->output[0], OUTPUT_SIZE, USE_DSP_RUNTIME, false, true); #else - s->m = new SNPEModel("models/dmonitoring_model_q.dlc", &s->output[0], OUTPUT_SIZE, USE_DSP_RUNTIME); + s->m = new SNPEModel("models/dmonitoring_model_q.dlc", &s->output[0], OUTPUT_SIZE, USE_DSP_RUNTIME, false, true); #endif s->m->addCalib(s->calib, CALIB_LEN); } -static inline auto get_yuv_buf(std::vector &buf, const int width, int height) { - uint8_t *y = get_buffer(buf, width * height * 3 / 2); - uint8_t *u = y + width * height; - uint8_t *v = u + (width /2) * (height / 2); - return std::make_tuple(y, u, v); +void parse_driver_data(DriverStateResult &ds_res, const DMonitoringModelState* s, int out_idx_offset) { + for (int i = 0; i < 3; ++i) { + ds_res.face_orientation[i] = s->output[out_idx_offset+i] * REG_SCALE; + ds_res.face_orientation_std[i] = exp(s->output[out_idx_offset+6+i]); + } + for (int i = 0; i < 2; ++i) { + ds_res.face_position[i] = s->output[out_idx_offset+3+i] * REG_SCALE; + ds_res.face_position_std[i] = exp(s->output[out_idx_offset+9+i]); + } + for (int i = 0; i < 4; ++i) { + ds_res.ready_prob[i] = sigmoid(s->output[out_idx_offset+35+i]); + } + for (int i = 0; i < 2; ++i) { + ds_res.not_ready_prob[i] = sigmoid(s->output[out_idx_offset+39+i]); + } + ds_res.face_prob = sigmoid(s->output[out_idx_offset+12]); + ds_res.left_eye_prob = sigmoid(s->output[out_idx_offset+21]); + ds_res.right_eye_prob = sigmoid(s->output[out_idx_offset+30]); + ds_res.left_blink_prob = sigmoid(s->output[out_idx_offset+31]); + ds_res.right_blink_prob = sigmoid(s->output[out_idx_offset+32]); + ds_res.sunglasses_prob = sigmoid(s->output[out_idx_offset+33]); + ds_res.occluded_prob = sigmoid(s->output[out_idx_offset+34]); } -struct Rect {int x, y, w, h;}; -void crop_nv12_to_yuv(uint8_t *raw, int stride, int uv_offset, uint8_t *y, uint8_t *u, uint8_t *v, const Rect &rect) { - uint8_t *raw_y = raw; - uint8_t *raw_uv = raw_y + uv_offset; - for (int r = 0; r < rect.h / 2; r++) { - memcpy(y + 2 * r * rect.w, raw_y + (2 * r + rect.y) * stride + rect.x, rect.w); - memcpy(y + (2 * r + 1) * rect.w, raw_y + (2 * r + rect.y + 1) * stride + rect.x, rect.w); - for (int h = 0; h < rect.w / 2; h++) { - u[r * rect.w/2 + h] = raw_uv[(r + (rect.y/2)) * stride + (rect.x/2 + h)*2]; - v[r * rect.w/2 + h] = raw_uv[(r + (rect.y/2)) * stride + (rect.x/2 + h)*2 + 1]; - } - } +void fill_driver_data(cereal::DriverStateV2::DriverData::Builder ddata, const DriverStateResult &ds_res) { + ddata.setFaceOrientation(ds_res.face_orientation); + ddata.setFaceOrientationStd(ds_res.face_orientation_std); + ddata.setFacePosition(ds_res.face_position); + ddata.setFacePositionStd(ds_res.face_position_std); + ddata.setFaceProb(ds_res.face_prob); + ddata.setLeftEyeProb(ds_res.left_eye_prob); + ddata.setRightEyeProb(ds_res.right_eye_prob); + ddata.setLeftBlinkProb(ds_res.left_blink_prob); + ddata.setRightBlinkProb(ds_res.right_blink_prob); + ddata.setSunglassesProb(ds_res.sunglasses_prob); + ddata.setOccludedProb(ds_res.occluded_prob); + ddata.setReadyProb(ds_res.ready_prob); + ddata.setNotReadyProb(ds_res.not_ready_prob); } -DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_buf, int width, int height, int stride, int uv_offset, float *calib) { - const int cropped_height = tici_dm_crop::width / 1.33; - Rect crop_rect = {width / 2 - tici_dm_crop::width / 2 + tici_dm_crop::x_offset, - height / 2 - cropped_height / 2 + tici_dm_crop::y_offset, - cropped_height / 2, - cropped_height}; - if (!s->is_rhd) { - crop_rect.x += tici_dm_crop::width - crop_rect.w; - } +DMonitoringModelResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_buf, int width, int height, int stride, int uv_offset, float *calib) { + int v_off = height - MODEL_HEIGHT; + int h_off = (width - MODEL_WIDTH) / 2; + int yuv_buf_len = MODEL_WIDTH * MODEL_HEIGHT; - int resized_width = MODEL_WIDTH; - int resized_height = MODEL_HEIGHT; - - auto [cropped_y, cropped_u, cropped_v] = get_yuv_buf(s->cropped_buf, crop_rect.w, crop_rect.h); - if (!s->is_rhd) { - crop_nv12_to_yuv((uint8_t *)stream_buf, stride, uv_offset, cropped_y, cropped_u, cropped_v, crop_rect); - } else { - auto [mirror_y, mirror_u, mirror_v] = get_yuv_buf(s->premirror_cropped_buf, crop_rect.w, crop_rect.h); - crop_nv12_to_yuv((uint8_t *)stream_buf, stride, uv_offset, mirror_y, mirror_u, mirror_v, crop_rect); - libyuv::I420Mirror(mirror_y, crop_rect.w, - mirror_u, crop_rect.w / 2, - mirror_v, crop_rect.w / 2, - cropped_y, crop_rect.w, - cropped_u, crop_rect.w / 2, - cropped_v, crop_rect.w / 2, - crop_rect.w, crop_rect.h); - } + uint8_t *raw_buf = (uint8_t *) stream_buf; + // vertical crop free + uint8_t *raw_y_start = raw_buf + stride * v_off; - auto [resized_buf, resized_u, resized_v] = get_yuv_buf(s->resized_buf, resized_width, resized_height); - uint8_t *resized_y = resized_buf; - libyuv::FilterMode mode = libyuv::FilterModeEnum::kFilterBilinear; - libyuv::I420Scale(cropped_y, crop_rect.w, - cropped_u, crop_rect.w / 2, - cropped_v, crop_rect.w / 2, - crop_rect.w, crop_rect.h, - resized_y, resized_width, - resized_u, resized_width / 2, - resized_v, resized_width / 2, - resized_width, resized_height, - mode); - - - int yuv_buf_len = (MODEL_WIDTH/2) * (MODEL_HEIGHT/2) * 6; // Y|u|v -> y|y|y|y|u|v - float *net_input_buf = get_buffer(s->net_input_buf, yuv_buf_len); - // one shot conversion, O(n) anyway - // yuvframe2tensor, normalize - for (int r = 0; r < MODEL_HEIGHT/2; r++) { - for (int c = 0; c < MODEL_WIDTH/2; c++) { - // Y_ul - net_input_buf[(r*MODEL_WIDTH/2) + c + (0*(MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = s->tensor[resized_y[(2*r)*resized_width + 2*c]]; - // Y_dl - net_input_buf[(r*MODEL_WIDTH/2) + c + (1*(MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = s->tensor[resized_y[(2*r+1)*resized_width + 2*c]]; - // Y_ur - net_input_buf[(r*MODEL_WIDTH/2) + c + (2*(MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = s->tensor[resized_y[(2*r)*resized_width + 2*c+1]]; - // Y_dr - net_input_buf[(r*MODEL_WIDTH/2) + c + (3*(MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = s->tensor[resized_y[(2*r+1)*resized_width + 2*c+1]]; - // U - net_input_buf[(r*MODEL_WIDTH/2) + c + (4*(MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = s->tensor[resized_u[r*resized_width/2 + c]]; - // V - net_input_buf[(r*MODEL_WIDTH/2) + c + (5*(MODEL_WIDTH/2)*(MODEL_HEIGHT/2))] = s->tensor[resized_v[r*resized_width/2 + c]]; - } - } - - //printf("preprocess completed. %d \n", yuv_buf_len); - //FILE *dump_yuv_file = fopen("/tmp/rawdump.yuv", "wb"); - //fwrite(resized_buf, yuv_buf_len, sizeof(uint8_t), dump_yuv_file); - //fclose(dump_yuv_file); + uint8_t *net_input_buf = get_buffer(s->net_input_buf, yuv_buf_len); - // *** testing *** - // idat = np.frombuffer(open("/tmp/inputdump.yuv", "rb").read(), np.float32).reshape(6, 160, 320) - // imshow(cv2.cvtColor(tensor_to_frames(idat[None]/0.0078125+128)[0], cv2.COLOR_YUV2RGB_I420)) + // here makes a uint8 copy + for (int r = 0; r < MODEL_HEIGHT; ++r) { + memcpy(net_input_buf + r * MODEL_WIDTH, raw_y_start + r * stride + h_off, MODEL_WIDTH); + } - //FILE *dump_yuv_file2 = fopen("/tmp/inputdump.yuv", "wb"); - //fwrite(net_input_buf, MODEL_HEIGHT*MODEL_WIDTH*3/2, sizeof(float), dump_yuv_file2); - //fclose(dump_yuv_file2); + // printf("preprocess completed. %d \n", yuv_buf_len); + // FILE *dump_yuv_file = fopen("/tmp/rawdump.yuv", "wb"); + // fwrite(net_input_buf, yuv_buf_len, sizeof(uint8_t), dump_yuv_file); + // fclose(dump_yuv_file); double t1 = millis_since_boot(); - s->m->addImage(net_input_buf, yuv_buf_len); + s->m->addImage((float*)net_input_buf, yuv_buf_len / 4); for (int i = 0; i < CALIB_LEN; i++) { s->calib[i] = calib[i]; } s->m->execute(); double t2 = millis_since_boot(); - DMonitoringResult ret = {0}; - for (int i = 0; i < 3; ++i) { - ret.face_orientation[i] = s->output[i] * REG_SCALE; - ret.face_orientation_meta[i] = exp(s->output[6 + i]); - } - for (int i = 0; i < 2; ++i) { - ret.face_position[i] = s->output[3 + i] * REG_SCALE; - ret.face_position_meta[i] = exp(s->output[9 + i]); - } - for (int i = 0; i < 4; ++i) { - ret.ready_prob[i] = sigmoid(s->output[39 + i]); - } - for (int i = 0; i < 2; ++i) { - ret.not_ready_prob[i] = sigmoid(s->output[43 + i]); - } - ret.face_prob = sigmoid(s->output[12]); - ret.left_eye_prob = sigmoid(s->output[21]); - ret.right_eye_prob = sigmoid(s->output[30]); - ret.left_blink_prob = sigmoid(s->output[31]); - ret.right_blink_prob = sigmoid(s->output[32]); - ret.sg_prob = sigmoid(s->output[33]); - ret.poor_vision = sigmoid(s->output[34]); - ret.partial_face = sigmoid(s->output[35]); - ret.distracted_pose = sigmoid(s->output[36]); - ret.distracted_eyes = sigmoid(s->output[37]); - ret.occluded_prob = sigmoid(s->output[38]); - ret.dsp_execution_time = (t2 - t1) / 1000.; - return ret; + DMonitoringModelResult model_res = {0}; + parse_driver_data(model_res.driver_state_lhd, s, 0); + parse_driver_data(model_res.driver_state_rhd, s, 41); + model_res.poor_vision_prob = sigmoid(s->output[82]); + model_res.wheel_on_right_prob = sigmoid(s->output[83]); + model_res.dsp_execution_time = (t2 - t1) / 1000.; + + return model_res; } -void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResult &res, float execution_time, kj::ArrayPtr raw_pred) { +void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringModelResult &model_res, float execution_time, kj::ArrayPtr raw_pred) { // make msg MessageBuilder msg; - auto framed = msg.initEvent().initDriverState(); + auto framed = msg.initEvent().initDriverStateV2(); framed.setFrameId(frame_id); framed.setModelExecutionTime(execution_time); - framed.setDspExecutionTime(res.dsp_execution_time); - - framed.setFaceOrientation(res.face_orientation); - framed.setFaceOrientationStd(res.face_orientation_meta); - framed.setFacePosition(res.face_position); - framed.setFacePositionStd(res.face_position_meta); - framed.setFaceProb(res.face_prob); - framed.setLeftEyeProb(res.left_eye_prob); - framed.setRightEyeProb(res.right_eye_prob); - framed.setLeftBlinkProb(res.left_blink_prob); - framed.setRightBlinkProb(res.right_blink_prob); - framed.setSunglassesProb(res.sg_prob); - framed.setPoorVision(res.poor_vision); - framed.setPartialFace(res.partial_face); - framed.setDistractedPose(res.distracted_pose); - framed.setDistractedEyes(res.distracted_eyes); - framed.setOccludedProb(res.occluded_prob); - framed.setReadyProb(res.ready_prob); - framed.setNotReadyProb(res.not_ready_prob); + framed.setDspExecutionTime(model_res.dsp_execution_time); + + framed.setPoorVisionProb(model_res.poor_vision_prob); + framed.setWheelOnRightProb(model_res.wheel_on_right_prob); + fill_driver_data(framed.initLeftDriverData(), model_res.driver_state_lhd); + fill_driver_data(framed.initRightDriverData(), model_res.driver_state_rhd); + if (send_raw_pred) { framed.setRawPredictions(raw_pred.asBytes()); } - pm.send("driverState", msg); + pm.send("driverStateV2", msg); } void dmonitoring_free(DMonitoringModelState* s) { diff --git a/selfdrive/modeld/models/dmonitoring.h b/selfdrive/modeld/models/dmonitoring.h index a1be91e3bb..874722cd93 100644 --- a/selfdrive/modeld/models/dmonitoring.h +++ b/selfdrive/modeld/models/dmonitoring.h @@ -9,44 +9,43 @@ #define CALIB_LEN 3 -#define OUTPUT_SIZE 45 +#define OUTPUT_SIZE 84 #define REG_SCALE 0.25f -typedef struct DMonitoringResult { +typedef struct DriverStateResult { float face_orientation[3]; - float face_orientation_meta[3]; + float face_orientation_std[3]; float face_position[2]; - float face_position_meta[2]; + float face_position_std[2]; float face_prob; float left_eye_prob; float right_eye_prob; float left_blink_prob; float right_blink_prob; - float sg_prob; - float poor_vision; - float partial_face; - float distracted_pose; - float distracted_eyes; + float sunglasses_prob; float occluded_prob; float ready_prob[4]; float not_ready_prob[2]; +} DriverStateResult; + +typedef struct DMonitoringModelResult { + DriverStateResult driver_state_lhd; + DriverStateResult driver_state_rhd; + float poor_vision_prob; + float wheel_on_right_prob; float dsp_execution_time; -} DMonitoringResult; +} DMonitoringModelResult; typedef struct DMonitoringModelState { RunModel *m; bool is_rhd; float output[OUTPUT_SIZE]; - std::vector resized_buf; - std::vector cropped_buf; - std::vector premirror_cropped_buf; - std::vector net_input_buf; + std::vector net_input_buf; float calib[CALIB_LEN]; - float tensor[UINT8_MAX + 1]; } DMonitoringModelState; void dmonitoring_init(DMonitoringModelState* s); -DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_buf, int width, int height, int stride, int uv_offset, float *calib); -void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResult &res, float execution_time, kj::ArrayPtr raw_pred); +DMonitoringModelResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_buf, int width, int height, int stride, int uv_offset, float *calib); +void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringModelResult &model_res, float execution_time, kj::ArrayPtr raw_pred); void dmonitoring_free(DMonitoringModelState* s); diff --git a/selfdrive/modeld/models/dmonitoring_model.current b/selfdrive/modeld/models/dmonitoring_model.current index 74bcfe17a4..d1e7d1136f 100644 --- a/selfdrive/modeld/models/dmonitoring_model.current +++ b/selfdrive/modeld/models/dmonitoring_model.current @@ -1,2 +1,2 @@ -a8236e30-5bee-4689-8ea0-fc102e2770e5 -d508c79bae1c1c451f3af3e2bc231ce33678cb43 \ No newline at end of file +ee8f830b-d6a1-42ef-9b1b-50fd0b2faae4 +cac8f7b69d420506707ff7a19d573d5011ef2533 \ No newline at end of file diff --git a/selfdrive/modeld/models/dmonitoring_model.onnx b/selfdrive/modeld/models/dmonitoring_model.onnx index 51b0d1ed76..4cbd6bb7dd 100644 --- a/selfdrive/modeld/models/dmonitoring_model.onnx +++ b/selfdrive/modeld/models/dmonitoring_model.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:00731ebd06fcff7e5837607b91bc56cad3bed5d7ee89052c911c981e8f665308 -size 3679940 +oid sha256:932e589e5cce66e5d9f48492426a33c74cd7f352a870d3ddafcede3e9156f30d +size 9157561 diff --git a/selfdrive/modeld/models/dmonitoring_model_q.dlc b/selfdrive/modeld/models/dmonitoring_model_q.dlc index 2e54f7ee4b..94632030ed 100644 --- a/selfdrive/modeld/models/dmonitoring_model_q.dlc +++ b/selfdrive/modeld/models/dmonitoring_model_q.dlc @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:667df5e925570a0f6a33dfb890e186a1f13f101885b46db47ec45305737dffb6 -size 1145921 +oid sha256:3587976a8b7e3be274fa86c2e2233e3e464cad713f5077c4394cd1ddd3c7c6c5 +size 2636965 diff --git a/selfdrive/modeld/runners/onnx_runner.py b/selfdrive/modeld/runners/onnx_runner.py index e282a66b66..ac7cc68814 100755 --- a/selfdrive/modeld/runners/onnx_runner.py +++ b/selfdrive/modeld/runners/onnx_runner.py @@ -9,20 +9,24 @@ os.environ["OMP_WAIT_POLICY"] = "PASSIVE" import onnxruntime as ort # pylint: disable=import-error -def read(sz): +def read(sz, tf8=False): dd = [] gt = 0 - while gt < sz * 4: - st = os.read(0, sz * 4 - gt) + szof = 1 if tf8 else 4 + while gt < sz * szof: + st = os.read(0, sz * szof - gt) assert(len(st) > 0) dd.append(st) gt += len(st) - return np.frombuffer(b''.join(dd), dtype=np.float32) + r = np.frombuffer(b''.join(dd), dtype=np.uint8 if tf8 else np.float32).astype(np.float32) + if tf8: + r = r / 255. + return r def write(d): os.write(1, d.tobytes()) -def run_loop(m): +def run_loop(m, tf8_input=False): ishapes = [[1]+ii.shape[1:] for ii in m.get_inputs()] keys = [x.name for x in m.get_inputs()] @@ -33,10 +37,10 @@ def run_loop(m): print("ready to run onnx model", keys, ishapes, file=sys.stderr) while 1: inputs = [] - for shp in ishapes: + for k, shp in zip(keys, ishapes): ts = np.product(shp) #print("reshaping %s with offset %d" % (str(shp), offset), file=sys.stderr) - inputs.append(read(ts).reshape(shp)) + inputs.append(read(ts, (k=='input_img' and tf8_input)).reshape(shp)) ret = m.run(None, dict(zip(keys, inputs))) #print(ret, file=sys.stderr) for r in ret: @@ -44,6 +48,7 @@ def run_loop(m): if __name__ == "__main__": + print(sys.argv, file=sys.stderr) print("Onnx available providers: ", ort.get_available_providers(), file=sys.stderr) options = ort.SessionOptions() options.graph_optimization_level = ort.GraphOptimizationLevel.ORT_DISABLE_ALL @@ -63,6 +68,6 @@ if __name__ == "__main__": print("Onnx selected provider: ", [provider], file=sys.stderr) ort_session = ort.InferenceSession(sys.argv[1], options, providers=[provider]) print("Onnx using ", ort_session.get_providers(), file=sys.stderr) - run_loop(ort_session) + run_loop(ort_session, tf8_input=("--use_tf8" in sys.argv)) except KeyboardInterrupt: pass diff --git a/selfdrive/modeld/runners/onnxmodel.cc b/selfdrive/modeld/runners/onnxmodel.cc index 9b4d6fd015..1f9f551abc 100644 --- a/selfdrive/modeld/runners/onnxmodel.cc +++ b/selfdrive/modeld/runners/onnxmodel.cc @@ -14,12 +14,13 @@ #include "common/swaglog.h" #include "common/util.h" -ONNXModel::ONNXModel(const char *path, float *_output, size_t _output_size, int runtime, bool _use_extra) { +ONNXModel::ONNXModel(const char *path, float *_output, size_t _output_size, int runtime, bool _use_extra, bool _use_tf8) { LOGD("loading model %s", path); output = _output; output_size = _output_size; use_extra = _use_extra; + use_tf8 = _use_tf8; int err = pipe(pipein); assert(err == 0); @@ -28,11 +29,12 @@ ONNXModel::ONNXModel(const char *path, float *_output, size_t _output_size, int std::string exe_dir = util::dir_name(util::readlink("/proc/self/exe")); std::string onnx_runner = exe_dir + "/runners/onnx_runner.py"; + std::string tf8_arg = use_tf8 ? "--use_tf8" : ""; proc_pid = fork(); if (proc_pid == 0) { LOGD("spawning onnx process %s", onnx_runner.c_str()); - char *argv[] = {(char*)onnx_runner.c_str(), (char*)path, nullptr}; + char *argv[] = {(char*)onnx_runner.c_str(), (char*)path, (char*)tf8_arg.c_str(), nullptr}; dup2(pipein[0], 0); dup2(pipeout[1], 1); close(pipein[0]); diff --git a/selfdrive/modeld/runners/onnxmodel.h b/selfdrive/modeld/runners/onnxmodel.h index 567d81d29e..4ac599e2af 100644 --- a/selfdrive/modeld/runners/onnxmodel.h +++ b/selfdrive/modeld/runners/onnxmodel.h @@ -6,7 +6,7 @@ class ONNXModel : public RunModel { public: - ONNXModel(const char *path, float *output, size_t output_size, int runtime, bool use_extra = false); + ONNXModel(const char *path, float *output, size_t output_size, int runtime, bool use_extra = false, bool _use_tf8 = false); ~ONNXModel(); void addRecurrent(float *state, int state_size); void addDesire(float *state, int state_size); @@ -31,6 +31,7 @@ private: int calib_size; float *image_input_buf = NULL; int image_buf_size; + bool use_tf8; float *extra_input_buf = NULL; int extra_buf_size; bool use_extra; diff --git a/selfdrive/modeld/runners/snpemodel.cc b/selfdrive/modeld/runners/snpemodel.cc index 1861494d59..4d6917e894 100644 --- a/selfdrive/modeld/runners/snpemodel.cc +++ b/selfdrive/modeld/runners/snpemodel.cc @@ -14,10 +14,11 @@ void PrintErrorStringAndExit() { std::exit(EXIT_FAILURE); } -SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra) { +SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra, bool luse_tf8) { output = loutput; output_size = loutput_size; use_extra = luse_extra; + use_tf8 = luse_tf8; #ifdef QCOM2 if (runtime==USE_GPU_RUNTIME) { Runtime = zdl::DlSystem::Runtime_t::GPU; @@ -70,14 +71,16 @@ SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int printf("model: %s -> %s\n", input_tensor_name, output_tensor_name); zdl::DlSystem::UserBufferEncodingFloat userBufferEncodingFloat; + zdl::DlSystem::UserBufferEncodingTf8 userBufferEncodingTf8(0, 1./255); // network takes 0-1 zdl::DlSystem::IUserBufferFactory& ubFactory = zdl::SNPE::SNPEFactory::getUserBufferFactory(); + size_t size_of_input = use_tf8 ? sizeof(uint8_t) : sizeof(float); // create input buffer { const auto &inputDims_opt = snpe->getInputDimensions(input_tensor_name); const zdl::DlSystem::TensorShape& bufferShape = *inputDims_opt; std::vector strides(bufferShape.rank()); - strides[strides.size() - 1] = sizeof(float); + strides[strides.size() - 1] = size_of_input; size_t product = 1; for (size_t i = 0; i < bufferShape.rank(); i++) product *= bufferShape[i]; size_t stride = strides[strides.size() - 1]; @@ -86,7 +89,10 @@ SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int strides[i-1] = stride; } printf("input product is %lu\n", product); - inputBuffer = ubFactory.createUserBuffer(NULL, product*sizeof(float), strides, &userBufferEncodingFloat); + inputBuffer = ubFactory.createUserBuffer(NULL, + product*size_of_input, + strides, + use_tf8 ? (zdl::DlSystem::UserBufferEncoding*)&userBufferEncodingTf8 : (zdl::DlSystem::UserBufferEncoding*)&userBufferEncodingFloat); inputMap.add(input_tensor_name, inputBuffer.get()); } diff --git a/selfdrive/modeld/runners/snpemodel.h b/selfdrive/modeld/runners/snpemodel.h index ba51fdced0..ed9d58d1e1 100644 --- a/selfdrive/modeld/runners/snpemodel.h +++ b/selfdrive/modeld/runners/snpemodel.h @@ -23,7 +23,7 @@ class SNPEModel : public RunModel { public: - SNPEModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra = false); + SNPEModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra = false, bool use_tf8 = false); void addRecurrent(float *state, int state_size); void addTrafficConvention(float *state, int state_size); void addCalib(float *state, int state_size); @@ -52,6 +52,7 @@ private: std::unique_ptr inputBuffer; float *input; size_t input_size; + bool use_tf8; // snpe output stuff zdl::DlSystem::UserBufferMap outputMap; diff --git a/selfdrive/monitoring/dmonitoringd.py b/selfdrive/monitoring/dmonitoringd.py index 9a3196030b..c31e9da43b 100755 --- a/selfdrive/monitoring/dmonitoringd.py +++ b/selfdrive/monitoring/dmonitoringd.py @@ -18,7 +18,7 @@ def dmonitoringd_thread(sm=None, pm=None): pm = messaging.PubMaster(['driverMonitoringState']) if sm is None: - sm = messaging.SubMaster(['driverState', 'liveCalibration', 'carState', 'controlsState', 'modelV2'], poll=['driverState']) + sm = messaging.SubMaster(['driverStateV2', 'liveCalibration', 'carState', 'controlsState', 'modelV2'], poll=['driverStateV2']) driver_status = DriverStatus(rhd=Params().get_bool("IsRHD")) @@ -34,7 +34,7 @@ def dmonitoringd_thread(sm=None, pm=None): while True: sm.update() - if not sm.updated['driverState']: + if not sm.updated['driverStateV2']: continue # Get interaction @@ -51,7 +51,7 @@ def dmonitoringd_thread(sm=None, pm=None): # Get data from dmonitoringmodeld events = Events() - driver_status.update_states(sm['driverState'], sm['liveCalibration'].rpyCalib, sm['carState'].vEgo, sm['controlsState'].enabled) + driver_status.update_states(sm['driverStateV2'], sm['liveCalibration'].rpyCalib, sm['carState'].vEgo, sm['controlsState'].enabled) # Block engaging after max number of distrations if driver_status.terminal_alert_cnt >= driver_status.settings._MAX_TERMINAL_ALERTS or \ @@ -79,6 +79,7 @@ def dmonitoringd_thread(sm=None, pm=None): "isLowStd": driver_status.pose.low_std, "hiStdCount": driver_status.hi_stds, "isActiveMode": driver_status.active_monitoring_mode, + "isRHD": driver_status.wheel_on_right, } pm.send('driverMonitoringState', dat) diff --git a/selfdrive/monitoring/driver_monitor.py b/selfdrive/monitoring/driver_monitor.py index 662e0d76ce..f2d0524422 100644 --- a/selfdrive/monitoring/driver_monitor.py +++ b/selfdrive/monitoring/driver_monitor.py @@ -5,6 +5,7 @@ from common.numpy_fast import interp from common.realtime import DT_DMON from common.filter_simple import FirstOrderFilter from common.stat_live import RunningStatFilter +from common.transformations.camera import tici_d_frame_size EventName = car.CarEvent.EventName @@ -25,33 +26,30 @@ class DRIVER_MONITOR_SETTINGS(): self._DISTRACTED_PRE_TIME_TILL_TERMINAL = 8. self._DISTRACTED_PROMPT_TIME_TILL_TERMINAL = 6. - self._FACE_THRESHOLD = 0.5 - self._PARTIAL_FACE_THRESHOLD = 0.8 + self._FACE_THRESHOLD = 0.7 self._EYE_THRESHOLD = 0.65 - self._SG_THRESHOLD = 0.925 - self._BLINK_THRESHOLD = 0.8 - self._BLINK_THRESHOLD_SLACK = 0.9 - self._BLINK_THRESHOLD_STRICT = self._BLINK_THRESHOLD + self._SG_THRESHOLD = 0.9 + self._BLINK_THRESHOLD = 0.87 self._EE_THRESH11 = 0.75 self._EE_THRESH12 = 3.25 self._EE_THRESH21 = 0.01 self._EE_THRESH22 = 0.35 - self._POSE_PITCH_THRESHOLD = 0.3237 - self._POSE_PITCH_THRESHOLD_SLACK = 0.3657 + self._POSE_PITCH_THRESHOLD = 0.3133 + self._POSE_PITCH_THRESHOLD_SLACK = 0.3237 self._POSE_PITCH_THRESHOLD_STRICT = self._POSE_PITCH_THRESHOLD - self._POSE_YAW_THRESHOLD = 0.3109 - self._POSE_YAW_THRESHOLD_SLACK = 0.4294 + self._POSE_YAW_THRESHOLD = 0.4020 + self._POSE_YAW_THRESHOLD_SLACK = 0.5042 self._POSE_YAW_THRESHOLD_STRICT = self._POSE_YAW_THRESHOLD - self._PITCH_NATURAL_OFFSET = 0.057 # initial value before offset is learned - self._YAW_NATURAL_OFFSET = 0.11 # initial value before offset is learned + self._PITCH_NATURAL_OFFSET = 0.029 # initial value before offset is learned + self._YAW_NATURAL_OFFSET = 0.097 # initial value before offset is learned self._PITCH_MAX_OFFSET = 0.124 self._PITCH_MIN_OFFSET = -0.0881 self._YAW_MAX_OFFSET = 0.289 self._YAW_MIN_OFFSET = -0.0246 - self._POSESTD_THRESHOLD = 0.315 + self._POSESTD_THRESHOLD = 0.3 self._HI_STD_FALLBACK_TIME = int(10 / self._DT_DMON) # fall back to wheel touch if model is uncertain for 10s self._DISTRACTED_FILTER_TS = 0.25 # 0.6Hz @@ -59,6 +57,9 @@ class DRIVER_MONITOR_SETTINGS(): self._POSE_OFFSET_MIN_COUNT = int(60 / self._DT_DMON) # valid data counts before calibration completes, 1min cumulative self._POSE_OFFSET_MAX_COUNT = int(360 / self._DT_DMON) # stop deweighting new data after 6 min, aka "short term memory" + self._WHEELPOS_THRESHOLD = 0.5 + self._WHEELPOS_FILTER_MIN_COUNT = int(5 / self._DT_DMON) + self._RECOVERY_FACTOR_MAX = 5. # relative to minus step change self._RECOVERY_FACTOR_MIN = 1.25 # relative to minus step change @@ -66,9 +67,9 @@ class DRIVER_MONITOR_SETTINGS(): self._MAX_TERMINAL_DURATION = int(30 / self._DT_DMON) # not allowed to engage after 30s of terminal alerts -# model output refers to center of cropped image, so need to apply the x displacement offset -RESIZED_FOCAL = 320.0 -H, W, FULL_W = 320, 160, 426 +# model output refers to center of undistorted+leveled image +EFL = 598.0 # focal length in K +W, H = tici_d_frame_size # corrected image has same size as raw class DistractedType: NOT_DISTRACTED = 0 @@ -76,22 +77,22 @@ class DistractedType: DISTRACTED_BLINK = 2 DISTRACTED_E2E = 4 -def face_orientation_from_net(angles_desc, pos_desc, rpy_calib, is_rhd): +def face_orientation_from_net(angles_desc, pos_desc, rpy_calib): # the output of these angles are in device frame # so from driver's perspective, pitch is up and yaw is right pitch_net, yaw_net, roll_net = angles_desc - face_pixel_position = ((pos_desc[0] + .5)*W - W + FULL_W, (pos_desc[1]+.5)*H) - yaw_focal_angle = atan2(face_pixel_position[0] - FULL_W//2, RESIZED_FOCAL) - pitch_focal_angle = atan2(face_pixel_position[1] - H//2, RESIZED_FOCAL) + face_pixel_position = ((pos_desc[0]+0.5)*W, (pos_desc[1]+0.5)*H) + yaw_focal_angle = atan2(face_pixel_position[0] - W//2, EFL) + pitch_focal_angle = atan2(face_pixel_position[1] - H//2, EFL) pitch = pitch_net + pitch_focal_angle yaw = -yaw_net + yaw_focal_angle # no calib for roll pitch -= rpy_calib[1] - yaw -= rpy_calib[2] * (1 - 2 * int(is_rhd)) # lhd -> -=, rhd -> += + yaw -= rpy_calib[2] return roll_net, pitch, yaw class DriverPose(): @@ -112,7 +113,6 @@ class DriverBlink(): def __init__(self): self.left_blink = 0. self.right_blink = 0. - self.cfactor = 1. class DriverStatus(): def __init__(self, rhd=False, settings=DRIVER_MONITOR_SETTINGS()): @@ -120,7 +120,7 @@ class DriverStatus(): self.settings = settings # init driver status - self.is_rhd_region = rhd + # self.wheelpos_learner = RunningStatFilter() self.pose = DriverPose(self.settings._POSE_OFFSET_MAX_COUNT) self.pose_calibrated = False self.blink = DriverBlink() @@ -137,8 +137,8 @@ class DriverStatus(): self.distracted_types = [] self.driver_distracted = False self.driver_distraction_filter = FirstOrderFilter(0., self.settings._DISTRACTED_FILTER_TS, self.settings._DT_DMON) + self.wheel_on_right = rhd self.face_detected = False - self.face_partial = False self.terminal_alert_cnt = 0 self.terminal_time = 0 self.step_change = 0. @@ -197,7 +197,7 @@ class DriverStatus(): yaw_error > self.settings._POSE_YAW_THRESHOLD*self.pose.cfactor_yaw: distracted_types.append(DistractedType.DISTRACTED_POSE) - if (self.blink.left_blink + self.blink.right_blink)*0.5 > self.settings._BLINK_THRESHOLD*self.blink.cfactor: + if (self.blink.left_blink + self.blink.right_blink)*0.5 > self.settings._BLINK_THRESHOLD: distracted_types.append(DistractedType.DISTRACTED_BLINK) if self.ee1_calibrated: @@ -214,13 +214,7 @@ class DriverStatus(): return distracted_types def set_policy(self, model_data, car_speed): - ep = min(model_data.meta.engagedProb, 0.8) / 0.8 # engaged prob bp = model_data.meta.disengagePredictions.brakeDisengageProbs[0] # brake disengage prob in next 2s - # TODO: retune adaptive blink - self.blink.cfactor = interp(ep, [0, 0.5, 1], - [self.settings._BLINK_THRESHOLD_STRICT, - self.settings._BLINK_THRESHOLD, - self.settings._BLINK_THRESHOLD_SLACK]) / self.settings._BLINK_THRESHOLD k1 = max(-0.00156*((car_speed-16)**2)+0.6, 0.2) bp_normal = max(min(bp / k1, 0.5),0) self.pose.cfactor_pitch = interp(bp_normal, [0, 0.5], @@ -231,28 +225,36 @@ class DriverStatus(): self.settings._POSE_YAW_THRESHOLD_STRICT]) / self.settings._POSE_YAW_THRESHOLD def update_states(self, driver_state, cal_rpy, car_speed, op_engaged): - if not all(len(x) > 0 for x in (driver_state.faceOrientation, driver_state.facePosition, - driver_state.faceOrientationStd, driver_state.facePositionStd, - driver_state.readyProb, driver_state.notReadyProb)): + # rhd_pred = driver_state.wheelOnRightProb + # if car_speed > 0.01: + # self.wheelpos_learner.push_and_update(rhd_pred) + # if self.wheelpos_learner.filtered_stat.n > self.settings._WHEELPOS_FILTER_MIN_COUNT: + # self.wheel_on_right = self.wheelpos_learner.filtered_stat.M > self.settings._WHEELPOS_THRESHOLD + # else: + # self.wheel_on_right = rhd_pred > self.settings._WHEELPOS_THRESHOLD + driver_data = driver_state.rightDriverData if self.wheel_on_right else driver_state.leftDriverData + if not all(len(x) > 0 for x in (driver_data.faceOrientation, driver_data.facePosition, + driver_data.faceOrientationStd, driver_data.facePositionStd, + driver_data.readyProb, driver_data.notReadyProb)): return - self.face_partial = driver_state.partialFace > self.settings._PARTIAL_FACE_THRESHOLD - self.face_detected = driver_state.faceProb > self.settings._FACE_THRESHOLD or self.face_partial - self.pose.roll, self.pose.pitch, self.pose.yaw = face_orientation_from_net(driver_state.faceOrientation, driver_state.facePosition, cal_rpy, self.is_rhd_region) - self.pose.pitch_std = driver_state.faceOrientationStd[0] - self.pose.yaw_std = driver_state.faceOrientationStd[1] - # self.pose.roll_std = driver_state.faceOrientationStd[2] + self.face_detected = driver_data.faceProb > self.settings._FACE_THRESHOLD + self.pose.roll, self.pose.pitch, self.pose.yaw = face_orientation_from_net(driver_data.faceOrientation, driver_data.facePosition, cal_rpy) + if self.wheel_on_right: + self.pose.yaw *= -1 + self.pose.pitch_std = driver_data.faceOrientationStd[0] + self.pose.yaw_std = driver_data.faceOrientationStd[1] model_std_max = max(self.pose.pitch_std, self.pose.yaw_std) - self.pose.low_std = model_std_max < self.settings._POSESTD_THRESHOLD and not self.face_partial - self.blink.left_blink = driver_state.leftBlinkProb * (driver_state.leftEyeProb > self.settings._EYE_THRESHOLD) * (driver_state.sunglassesProb < self.settings._SG_THRESHOLD) - self.blink.right_blink = driver_state.rightBlinkProb * (driver_state.rightEyeProb > self.settings._EYE_THRESHOLD) * (driver_state.sunglassesProb < self.settings._SG_THRESHOLD) - self.eev1 = driver_state.notReadyProb[1] - self.eev2 = driver_state.readyProb[0] + self.pose.low_std = model_std_max < self.settings._POSESTD_THRESHOLD + self.blink.left_blink = driver_data.leftBlinkProb * (driver_data.leftEyeProb > self.settings._EYE_THRESHOLD) * (driver_data.sunglassesProb < self.settings._SG_THRESHOLD) + self.blink.right_blink = driver_data.rightBlinkProb * (driver_data.rightEyeProb > self.settings._EYE_THRESHOLD) * (driver_data.sunglassesProb < self.settings._SG_THRESHOLD) + self.eev1 = driver_data.notReadyProb[1] + self.eev2 = driver_data.readyProb[0] self.distracted_types = self._get_distracted_types() self.driver_distracted = (DistractedType.DISTRACTED_POSE in self.distracted_types or DistractedType.DISTRACTED_BLINK in self.distracted_types) and \ - driver_state.faceProb > self.settings._FACE_THRESHOLD and self.pose.low_std + driver_data.faceProb > self.settings._FACE_THRESHOLD and self.pose.low_std self.driver_distraction_filter.update(self.driver_distracted) # update offseter diff --git a/selfdrive/monitoring/test_monitoring.py b/selfdrive/monitoring/test_monitoring.py index a84ed242ba..43b5e7747e 100755 --- a/selfdrive/monitoring/test_monitoring.py +++ b/selfdrive/monitoring/test_monitoring.py @@ -17,19 +17,19 @@ INVISIBLE_SECONDS_TO_ORANGE = dm_settings._AWARENESS_TIME - dm_settings._AWARENE INVISIBLE_SECONDS_TO_RED = dm_settings._AWARENESS_TIME + 1 def make_msg(face_detected, distracted=False, model_uncertain=False): - ds = log.DriverState.new_message() - ds.faceOrientation = [0., 0., 0.] - ds.facePosition = [0., 0.] - ds.faceProb = 1. * face_detected - ds.leftEyeProb = 1. - ds.rightEyeProb = 1. - ds.leftBlinkProb = 1. * distracted - ds.rightBlinkProb = 1. * distracted - ds.faceOrientationStd = [1.*model_uncertain, 1.*model_uncertain, 1.*model_uncertain] - ds.facePositionStd = [1.*model_uncertain, 1.*model_uncertain] + ds = log.DriverStateV2.new_message() + ds.leftDriverData.faceOrientation = [0., 0., 0.] + ds.leftDriverData.facePosition = [0., 0.] + ds.leftDriverData.faceProb = 1. * face_detected + ds.leftDriverData.leftEyeProb = 1. + ds.leftDriverData.rightEyeProb = 1. + ds.leftDriverData.leftBlinkProb = 1. * distracted + ds.leftDriverData.rightBlinkProb = 1. * distracted + ds.leftDriverData.faceOrientationStd = [1.*model_uncertain, 1.*model_uncertain, 1.*model_uncertain] + ds.leftDriverData.facePositionStd = [1.*model_uncertain, 1.*model_uncertain] # TODO: test both separately when e2e is used - ds.readyProb = [0., 0., 0., 0.] - ds.notReadyProb = [0., 0.] + ds.leftDriverData.readyProb = [0., 0., 0., 0.] + ds.leftDriverData.notReadyProb = [0., 0.] return ds diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index f3bb286635..bccad5d92c 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -52,7 +52,7 @@ def model_replay(lr, frs): vipc_server.create_buffers(VisionStreamType.VISION_STREAM_WIDE_ROAD, 40, False, *(tici_f_frame_size)) vipc_server.start_listener() - sm = messaging.SubMaster(['modelV2', 'driverState']) + sm = messaging.SubMaster(['modelV2', 'driverStateV2']) pm = messaging.PubMaster(['roadCameraState', 'wideRoadCameraState', 'driverCameraState', 'liveCalibration', 'lateralPlan']) try: @@ -112,7 +112,7 @@ def model_replay(lr, frs): if min(frame_idxs['roadCameraState'], frame_idxs['wideRoadCameraState']) > recv_cnt['modelV2']: recv = "modelV2" elif msg.which() == 'driverCameraState': - recv = "driverState" + recv = "driverStateV2" # wait for a response with Timeout(15, f"timed out waiting for {recv}"): @@ -170,8 +170,8 @@ if __name__ == "__main__": 'logMonoTime', 'modelV2.frameDropPerc', 'modelV2.modelExecutionTime', - 'driverState.modelExecutionTime', - 'driverState.dspExecutionTime' + 'driverStateV2.modelExecutionTime', + 'driverStateV2.dspExecutionTime' ] # TODO this tolerence is absurdly large tolerance = 5e-1 if PC else None diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 54c2ed54ad..0c4c2305eb 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -629eaa7b26d1721a71547f9de880f99732cb27f3 +5434b3c1696554e9a889e77f794d80cd1cb0a7ec diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index c368e6b575..62c5eb4826 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -293,7 +293,7 @@ CONFIGS = [ ProcessConfig( proc_name="dmonitoringd", pub_sub={ - "driverState": ["driverMonitoringState"], + "driverStateV2": ["driverMonitoringState"], "liveCalibration": [], "carState": [], "modelV2": [], "controlsState": [], }, ignore=["logMonoTime", "valid"], diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 3586f86f12..f10c79313b 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -33,7 +33,7 @@ PROCS = { "selfdrive.controls.radard": 4.5, "./_modeld": 4.48, "./boardd": 3.63, - "./_dmonitoringmodeld": 10.0, + "./_dmonitoringmodeld": 5.0, "selfdrive.thermald.thermald": 3.87, "selfdrive.locationd.calibrationd": 2.0, "./_soundd": 1.0, @@ -60,7 +60,7 @@ TIMINGS = { "roadCameraState": [2.5, 0.35], "driverCameraState": [2.5, 0.35], "modelV2": [2.5, 0.35], - "driverState": [2.5, 0.40], + "driverStateV2": [2.5, 0.40], "liveLocationKalman": [2.5, 0.35], "wideRoadCameraState": [1.5, 0.35], } @@ -221,7 +221,7 @@ class TestOnroad(unittest.TestCase): # TODO: this went up when plannerd cpu usage increased, why? cfgs = [ ("modelV2", 0.050, 0.036), - ("driverState", 0.050, 0.026), + ("driverStateV2", 0.050, 0.026), ] for (s, instant_max, avg_max) in cfgs: ts = [getattr(getattr(m, s), "modelExecutionTime") for m in self.lr if m.which() == s] diff --git a/selfdrive/ui/qt/offroad/driverview.cc b/selfdrive/ui/qt/offroad/driverview.cc index 06578b455a..dc9f292df1 100644 --- a/selfdrive/ui/qt/offroad/driverview.cc +++ b/selfdrive/ui/qt/offroad/driverview.cc @@ -25,7 +25,7 @@ void DriverViewWindow::mouseReleaseEvent(QMouseEvent* e) { emit done(); } -DriverViewScene::DriverViewScene(QWidget* parent) : sm({"driverState"}), QWidget(parent) { +DriverViewScene::DriverViewScene(QWidget* parent) : sm({"driverStateV2"}), QWidget(parent) { face_img = loadPixmap("../assets/img_driver_face.png", {FACE_IMG_SIZE, FACE_IMG_SIZE}); } @@ -57,43 +57,36 @@ void DriverViewScene::paintEvent(QPaintEvent* event) { return; } - const int width = 4 * height() / 3; - const QRect rect2 = {rect().center().x() - width / 2, rect().top(), width, rect().height()}; - const QRect valid_rect = {is_rhd ? rect2.right() - rect2.height() / 2 : rect2.left(), rect2.top(), rect2.height() / 2, rect2.height()}; + cereal::DriverStateV2::Reader driver_state = sm["driverStateV2"].getDriverStateV2(); + cereal::DriverStateV2::DriverData::Reader driver_data; - // blackout - const QColor bg(0, 0, 0, 140); - const QRect& blackout_rect = rect(); - p.fillRect(blackout_rect.adjusted(0, 0, valid_rect.left() - blackout_rect.right(), 0), bg); - p.fillRect(blackout_rect.adjusted(valid_rect.right() - blackout_rect.left(), 0, 0, 0), bg); - p.fillRect(blackout_rect.adjusted(valid_rect.left()-blackout_rect.left()+1, 0, valid_rect.right()-blackout_rect.right()-1, -valid_rect.height()*7/10), bg); // top dz + // is_rhd = driver_state.getWheelOnRightProb() > 0.5; + driver_data = is_rhd ? driver_state.getRightDriverData() : driver_state.getLeftDriverData(); - // face bounding box - cereal::DriverState::Reader driver_state = sm["driverState"].getDriverState(); - bool face_detected = driver_state.getFaceProb() > 0.5; + bool face_detected = driver_data.getFaceProb() > 0.7; if (face_detected) { - auto fxy_list = driver_state.getFacePosition(); - auto std_list = driver_state.getFaceOrientationStd(); + auto fxy_list = driver_data.getFacePosition(); + auto std_list = driver_data.getFaceOrientationStd(); float face_x = fxy_list[0]; float face_y = fxy_list[1]; float face_std = std::max(std_list[0], std_list[1]); float alpha = 0.7; - if (face_std > 0.08) { - alpha = std::max(0.7 - (face_std-0.08)*7, 0.0); + if (face_std > 0.15) { + alpha = std::max(0.7 - (face_std-0.15)*3.5, 0.0); } - const int box_size = 0.6 * rect2.height() / 2; - const float rhd_offset = 0.05; // lhd is shifted, so rhd is not mirrored - int fbox_x = valid_rect.center().x() + (is_rhd ? (face_x + rhd_offset) : -face_x) * valid_rect.width(); - int fbox_y = valid_rect.center().y() + face_y * valid_rect.height(); + const int box_size = 220; + // use approx instead of distort_points + int fbox_x = 1080.0 - 1714.0 * face_x; + int fbox_y = -135.0 + (504.0 + std::abs(face_x)*112.0) + (1205.0 - std::abs(face_x)*724.0) * face_y; p.setPen(QPen(QColor(255, 255, 255, alpha * 255), 10)); p.drawRoundedRect(fbox_x - box_size / 2, fbox_y - box_size / 2, box_size, box_size, 35.0, 35.0); } // icon - const int img_offset = 30; - const int img_x = is_rhd ? rect2.right() - FACE_IMG_SIZE - img_offset : rect2.left() + img_offset; - const int img_y = rect2.bottom() - FACE_IMG_SIZE - img_offset; - p.setOpacity(face_detected ? 1.0 : 0.3); + const int img_offset = 60; + const int img_x = rect().left() + img_offset; + const int img_y = rect().bottom() - FACE_IMG_SIZE - img_offset; + p.setOpacity(face_detected ? 1.0 : 0.2); p.drawPixmap(img_x, img_y, face_img); } diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 000ac48475..8666eb1d4e 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -67,16 +67,15 @@ const mat4 device_transform = {{ }}; mat4 get_driver_view_transform(int screen_width, int screen_height, int stream_width, int stream_height) { - const float driver_view_ratio = 1.333; - const float yscale = stream_height * driver_view_ratio / tici_dm_crop::width; + const float driver_view_ratio = 2.0; + const float yscale = stream_height * driver_view_ratio / stream_width; const float xscale = yscale*screen_height/screen_width*stream_width/stream_height; mat4 transform = (mat4){{ - xscale, 0.0, 0.0, xscale*tici_dm_crop::x_offset/stream_width*2, - 0.0, yscale, 0.0, yscale*tici_dm_crop::y_offset/stream_height*2, + xscale, 0.0, 0.0, 0.0, + 0.0, yscale, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, }}; - return transform; } diff --git a/system/hardware/tici/test_power_draw.py b/system/hardware/tici/test_power_draw.py index b6b5c735fa..4277bb9273 100755 --- a/system/hardware/tici/test_power_draw.py +++ b/system/hardware/tici/test_power_draw.py @@ -21,7 +21,7 @@ class Proc: PROCS = [ Proc('camerad', 2.15), Proc('modeld', 1.0, atol=0.15), - Proc('dmonitoringmodeld', 0.25), + Proc('dmonitoringmodeld', 0.35), Proc('encoderd', 0.23), ] From 2e2118dac33f51b5f03d7e2a5512fc9154c12122 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 20 Jun 2022 16:32:59 -0700 Subject: [PATCH 096/302] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 05bbdafb67..c6acc0698a 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 05bbdafb67060ffb62e6e0af812935494ad91933 +Subproject commit c6acc0698a604e715e960250359b6bf97e4987e3 From 5e0713122115604ccdbbb3844a6ab8d49657bc6a Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 20 Jun 2022 19:16:49 -0700 Subject: [PATCH 097/302] Toyota: international corolla cross is supported --- docs/CARS.md | 3 ++- selfdrive/car/toyota/values.py | 1 + 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/docs/CARS.md b/docs/CARS.md index 77b1c5e787..7c73bd3403 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -35,7 +35,7 @@ How We Rate The Cars **All supported cars can move between the tiers as support changes.** -# Gold - 28 cars +# Gold - 29 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -58,6 +58,7 @@ How We Rate The Cars |Toyota|Camry 2021-22|All||[4](#footnotes)|||| |Toyota|Camry Hybrid 2021-22|All|||||| |Toyota|Corolla 2020-22|All|||||| +|Toyota|Corolla Cross 2020-21 (Non-US only)|All|||||| |Toyota|Corolla Hatchback 2019-22|All|||||| |Toyota|Corolla Hybrid 2020-22|All|||||| |Toyota|Highlander 2020-22|All|||||| diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 2c151266cf..b1c6da922b 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -119,6 +119,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { CAR.COROLLA: ToyotaCarInfo("Toyota Corolla 2017-19", footnotes=[Footnote.DSU]), CAR.COROLLA_TSS2: [ ToyotaCarInfo("Toyota Corolla 2020-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"), + ToyotaCarInfo("Toyota Corolla Cross 2020-21 (Non-US only)"), ToyotaCarInfo("Toyota Corolla Hatchback 2019-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"), ], CAR.COROLLAH_TSS2: [ From 04b8e1b6a03aa0ad39b424f6c899365d0bc98604 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 20 Jun 2022 19:37:02 -0700 Subject: [PATCH 098/302] FPv2: log correct response address (#24918) log correct response address (29 bit addresses have a different standard) --- selfdrive/car/fw_versions.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 81883cecaa..a03b6b881d 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -350,7 +350,7 @@ def get_fw_versions(logcan, sendcan, extra=None, timeout=0.1, debug=False, progr f.ecu = ecu_types[addr] f.fwVersion = version f.address = addr[0] - f.responseAddress = addr[0] + rx_offset + f.responseAddress = uds.get_rx_addr_for_tx_addr(addr[0], rx_offset) f.request = request if addr[1] is not None: From 59055724d6069471618a7090270797e50d59f798 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 20 Jun 2022 20:20:24 -0700 Subject: [PATCH 099/302] 22 civic hatcback is supported --- docs/CARS.md | 3 ++- selfdrive/car/honda/values.py | 5 ++++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 7c73bd3403..73ffcc0e0a 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -150,7 +150,7 @@ How We Rate The Cars |Volkswagen|Taos 2022[7](#footnotes)|Driver Assistance|||||| |Volkswagen|Touran 2017|Driver Assistance|||||| -# Bronze - 70 cars +# Bronze - 71 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -171,6 +171,7 @@ How We Rate The Cars |Honda|Civic 2019-20|All|||[2](#footnotes)||| |Honda|Civic 2022|All|||||| |Honda|Civic Hatchback 2017-21|Honda Sensing|||||| +|Honda|Civic Hatchback 2022|All|||||| |Honda|CR-V 2015-16|Touring|||||| |Honda|CR-V 2017-21|Honda Sensing|||||| |Honda|CR-V Hybrid 2017-19|Honda Sensing|||||| diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 0bdb8ccd91..c6e20f2d83 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -119,7 +119,10 @@ CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = { HondaCarInfo("Honda Civic Hatchback 2017-21", harness=Harness.bosch_a), ], CAR.CIVIC_BOSCH_DIESEL: None, # same platform - CAR.CIVIC_2022: HondaCarInfo("Honda Civic 2022", "All", min_steer_speed=0., harness=Harness.bosch_b), + CAR.CIVIC_2022: [ + HondaCarInfo("Honda Civic 2022", "All", min_steer_speed=0., harness=Harness.bosch_b), + HondaCarInfo("Honda Civic Hatchback 2022", "All", min_steer_speed=0., harness=Harness.bosch_b), + ], CAR.ACURA_ILX: HondaCarInfo("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS, harness=Harness.nidec), CAR.CRV: HondaCarInfo("Honda CR-V 2015-16", "Touring", harness=Harness.nidec), CAR.CRV_5G: HondaCarInfo("Honda CR-V 2017-21", harness=Harness.bosch_a), From cccab50b166272d13ab51eab1eb10e21beca604e Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 20 Jun 2022 22:14:13 -0700 Subject: [PATCH 100/302] FPv2: log all present ECU addresses (#24916) * eliminate brands based on ECUs that respond to tester present * make it work * Add type hint for can message Use make_can_msg * Only query for addresses in fingerprints, and account for different busses * These need to be addresses, not response addresses * We need to listen to response addresses, not query addresses * add to files_common * Unused Optional Drain sock raw * add logging * only query essential ecus comments * simplify get_brand_candidates(), keep track of multiple request variants per make and request each subaddress * fixes make dat bytes bus is src Fix check * (addr, subaddr, bus) can be common across brands, add a match to each brand * fix length * query subaddrs in sequence * fix * candidate if a platform is a subset of responding ecu addresses comment comment * do logging for shadow mode * log responses so we can calculate candidates offline * get has_subaddress from response set * one liner * fix mypy * set to default at top * always log for now * log to make sure it's taking exactly timeout time * import time * fix logging * 0.1 timeout * clean up Co-authored-by: Greg Hogan --- release/files_common | 1 + selfdrive/car/car_helpers.py | 8 ++-- selfdrive/car/ecu_addrs.py | 90 ++++++++++++++++++++++++++++++++++++ selfdrive/car/fw_versions.py | 42 +++++++++++++++-- 4 files changed, 135 insertions(+), 6 deletions(-) create mode 100755 selfdrive/car/ecu_addrs.py diff --git a/release/files_common b/release/files_common index 7274ee9bf6..96649b9f16 100644 --- a/release/files_common +++ b/release/files_common @@ -101,6 +101,7 @@ selfdrive/car/interfaces.py selfdrive/car/vin.py selfdrive/car/disable_ecu.py selfdrive/car/fw_versions.py +selfdrive/car/ecu_addrs.py selfdrive/car/isotp_parallel_query.py selfdrive/car/tests/__init__.py selfdrive/car/tests/test_car_interfaces.py diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 3bfd99f88d..8c0fd7c90d 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -8,7 +8,7 @@ from system.version import is_comma_remote, is_tested_branch from selfdrive.car.interfaces import get_interface_attr from selfdrive.car.fingerprints import eliminate_incompatible_cars, all_legacy_fingerprint_cars from selfdrive.car.vin import get_vin, VIN_UNKNOWN -from selfdrive.car.fw_versions import get_fw_versions, match_fw_to_car +from selfdrive.car.fw_versions import get_fw_versions, match_fw_to_car, get_present_ecus from system.swaglog import cloudlog import cereal.messaging as messaging from selfdrive.car import gen_empty_fingerprint @@ -79,6 +79,7 @@ interfaces = load_interfaces(interface_names) def fingerprint(logcan, sendcan): fixed_fingerprint = os.environ.get('FINGERPRINT', "") skip_fw_query = os.environ.get('SKIP_FW_QUERY', False) + ecu_responses = set() if not fixed_fingerprint and not skip_fw_query: # Vin query only reliably works thorugh OBDII @@ -97,6 +98,7 @@ def fingerprint(logcan, sendcan): else: cloudlog.warning("Getting VIN & FW versions") _, vin = get_vin(logcan, sendcan, bus) + ecu_responses = get_present_ecus(logcan, sendcan) car_fw = get_fw_versions(logcan, sendcan) exact_fw_match, fw_candidates = match_fw_to_car(car_fw) @@ -163,8 +165,8 @@ def fingerprint(logcan, sendcan): car_fingerprint = fixed_fingerprint source = car.CarParams.FingerprintSource.fixed - cloudlog.event("fingerprinted", car_fingerprint=car_fingerprint, - source=source, fuzzy=not exact_match, fw_count=len(car_fw)) + cloudlog.event("fingerprinted", car_fingerprint=car_fingerprint, source=source, fuzzy=not exact_match, + fw_count=len(car_fw), ecu_responses=ecu_responses, error=True) return car_fingerprint, finger, vin, car_fw, source, exact_match diff --git a/selfdrive/car/ecu_addrs.py b/selfdrive/car/ecu_addrs.py new file mode 100755 index 0000000000..267701509a --- /dev/null +++ b/selfdrive/car/ecu_addrs.py @@ -0,0 +1,90 @@ +#!/usr/bin/env python3 +import capnp +import time +import traceback +from typing import Optional, Set, Tuple + +import cereal.messaging as messaging +from panda.python.uds import SERVICE_TYPE +from selfdrive.car import make_can_msg +from selfdrive.boardd.boardd import can_list_to_can_capnp +from system.swaglog import cloudlog + + +def make_tester_present_msg(addr, bus, subaddr=None): + dat = [0x02, SERVICE_TYPE.TESTER_PRESENT, 0x0] + if subaddr is not None: + dat.insert(0, subaddr) + + dat.extend([0x0] * (8 - len(dat))) + return make_can_msg(addr, bytes(dat), bus) + + +def is_tester_present_response(msg: capnp.lib.capnp._DynamicStructReader, subaddr: Optional[int] = None) -> bool: + # ISO-TP messages are always padded to 8 bytes + # tester present response is always a single frame + dat_offset = 1 if subaddr is not None else 0 + if len(msg.dat) == 8 and 1 <= msg.dat[dat_offset] <= 7: + # success response + if msg.dat[dat_offset + 1] == (SERVICE_TYPE.TESTER_PRESENT + 0x40): + return True + # error response + if msg.dat[dat_offset + 1] == 0x7F and msg.dat[dat_offset + 2] == SERVICE_TYPE.TESTER_PRESENT: + return True + return False + + +def get_all_ecu_addrs(logcan: messaging.SubSocket, sendcan: messaging.PubSocket, bus: int, timeout: float = 1, debug: bool = True) -> Set[Tuple[int, Optional[int], int]]: + addr_list = [0x700 + i for i in range(256)] + [0x18da00f1 + (i << 8) for i in range(256)] + queries: Set[Tuple[int, Optional[int], int]] = {(addr, None, bus) for addr in addr_list} + responses = queries + return get_ecu_addrs(logcan, sendcan, queries, responses, timeout=timeout, debug=debug) + + +def get_ecu_addrs(logcan: messaging.SubSocket, sendcan: messaging.PubSocket, queries: Set[Tuple[int, Optional[int], int]], + responses: Set[Tuple[int, Optional[int], int]], timeout: float = 1, debug: bool = False) -> Set[Tuple[int, Optional[int], int]]: + ecu_responses: Set[Tuple[int, Optional[int], int]] = set() # set((addr, subaddr, bus),) + try: + msgs = [make_tester_present_msg(addr, bus, subaddr) for addr, subaddr, bus in queries] + + messaging.drain_sock_raw(logcan) + sendcan.send(can_list_to_can_capnp(msgs, msgtype='sendcan')) + start_time = time.monotonic() + while time.monotonic() - start_time < timeout: + can_packets = messaging.drain_sock(logcan, wait_for_one=True) + for packet in can_packets: + for msg in packet.can: + subaddr = None if (msg.address, None, msg.src) in responses else msg.dat[0] + if (msg.address, subaddr, msg.src) in responses and is_tester_present_response(msg, subaddr): + if debug: + print(f"CAN-RX: {hex(msg.address)} - 0x{bytes.hex(msg.dat)}") + if (msg.address, subaddr, msg.src) in ecu_responses: + print(f"Duplicate ECU address: {hex(msg.address)}") + ecu_responses.add((msg.address, subaddr, msg.src)) + except Exception: + cloudlog.warning(f"ECU addr scan exception: {traceback.format_exc()}") + return ecu_responses + + +if __name__ == "__main__": + import argparse + + parser = argparse.ArgumentParser(description='Get addresses of all ECUs') + parser.add_argument('--debug', action='store_true') + args = parser.parse_args() + + logcan = messaging.sub_sock('can') + sendcan = messaging.pub_sock('sendcan') + + time.sleep(1.0) + + print("Getting ECU addresses ...") + ecu_addrs = get_all_ecu_addrs(logcan, sendcan, 1, debug=args.debug) + + print() + print("Found ECUs on addresses:") + for addr, subaddr, bus in ecu_addrs: + msg = f" 0x{hex(addr)}" + if subaddr is not None: + msg += f" (sub-address: 0x{hex(subaddr)})" + print(msg) diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index a03b6b881d..66f0564fca 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -3,11 +3,12 @@ import struct import traceback from collections import defaultdict from dataclasses import dataclass, field -from typing import Any, List +from typing import Any, List, Optional, Set, Tuple from tqdm import tqdm import panda.python.uds as uds from cereal import car +from selfdrive.car.ecu_addrs import get_ecu_addrs from selfdrive.car.interfaces import get_interface_attr from selfdrive.car.fingerprints import FW_VERSIONS from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery @@ -15,6 +16,7 @@ from selfdrive.car.toyota.values import CAR as TOYOTA from system.swaglog import cloudlog Ecu = car.CarParams.Ecu +ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.esp, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa] def p16(val): @@ -261,7 +263,6 @@ def match_fw_to_car_exact(fw_versions_dict): ecu_type = ecu[0] addr = ecu[1:] found_version = fw_versions_dict.get(addr, None) - ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.esp, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa] if ecu_type == Ecu.esp and candidate in (TOYOTA.RAV4, TOYOTA.COROLLA, TOYOTA.HIGHLANDER, TOYOTA.SIENNA, TOYOTA.LEXUS_IS) and found_version is None: continue @@ -299,11 +300,46 @@ def match_fw_to_car(fw_versions, allow_fuzzy=True): return exact_match, matches +def get_present_ecus(logcan, sendcan): + queries = list() + parallel_queries = list() + responses = set() + versions = get_interface_attr('FW_VERSIONS', ignore_none=True) + + for r in REQUESTS: + if r.brand not in versions: + continue + + for brand_versions in versions[r.brand].values(): + for ecu_type, addr, sub_addr in brand_versions: + # Only query ecus in whitelist if whitelist is not empty + if len(r.whitelist_ecus) == 0 or ecu_type in r.whitelist_ecus: + a = (addr, sub_addr, r.bus) + # Build set of queries + if sub_addr is None: + if a not in parallel_queries: + parallel_queries.append(a) + else: # subaddresses must be queried one by one + if [a] not in queries: + queries.append([a]) + + # Build set of expected responses to filter + response_addr = uds.get_rx_addr_for_tx_addr(addr, r.rx_offset) + responses.add((response_addr, sub_addr, r.bus)) + + queries.insert(0, parallel_queries) + + ecu_responses: Set[Tuple[int, Optional[int], int]] = set() + for query in queries: + ecu_responses.update(get_ecu_addrs(logcan, sendcan, set(query), responses, timeout=0.1)) + return ecu_responses + + def get_fw_versions(logcan, sendcan, extra=None, timeout=0.1, debug=False, progress=False): ecu_types = {} # Extract ECU addresses to query from fingerprints - # ECUs using a subadress need be queried one by one, the rest can be done in parallel + # ECUs using a subaddress need be queried one by one, the rest can be done in parallel addrs = [] parallel_addrs = [] From bd782c982f17221a33b660d82dab7aa297e10c60 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 20 Jun 2022 23:23:14 -0700 Subject: [PATCH 101/302] Mazda: log standstill bit (#24923) * set standstill bit for mazda * use bit in carcontroller * Revert "use bit in carcontroller" This reverts commit f38210a191bcd6e34ff81626e857f778207a55e7. --- selfdrive/car/mazda/carstate.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py index 6e1ad3e481..944d79809b 100644 --- a/selfdrive/car/mazda/carstate.py +++ b/selfdrive/car/mazda/carstate.py @@ -79,6 +79,7 @@ class CarState(CarStateBase): # it should be used for carState.cruiseState.nonAdaptive instead ret.cruiseState.available = cp.vl["CRZ_CTRL"]["CRZ_AVAILABLE"] == 1 ret.cruiseState.enabled = cp.vl["CRZ_CTRL"]["CRZ_ACTIVE"] == 1 + ret.cruiseState.standstill = cp.vl["PEDALS"]["STANDSTILL"] == 1 ret.cruiseState.speed = cp.vl["CRZ_EVENTS"]["CRZ_SPEED"] * CV.KPH_TO_MS if ret.cruiseState.enabled: From 5ce9b5d38cbba4d59935ef8504ec2a8cfb0eb149 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Tue, 21 Jun 2022 00:11:13 -0700 Subject: [PATCH 102/302] Bump laika (#24920) --- laika_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/laika_repo b/laika_repo index 44f048bc1f..824b49327a 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 44f048bc1f58ae9e28dfdeb98e40aea3e0f2b699 +Subproject commit 824b49327aa2f41eb0dafbe3806e6c4841b19f11 From e45eb1bd28623571079122030392fa0fe03e7a42 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 21 Jun 2022 00:11:55 -0700 Subject: [PATCH 103/302] test_models: check cruiseState.available (#24924) * check available is true if enabled is true * remove extra line --- selfdrive/car/tests/test_models.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 27dc4ba776..cb4b868582 100755 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -221,6 +221,7 @@ class TestCarModelBase(unittest.TestCase): # TODO: check rest of panda's carstate (steering, ACC main on, etc.) checks['gasPressed'] += CS.gasPressed != self.safety.get_gas_pressed_prev() + checks['cruiseState'] += CS.cruiseState.enabled and not CS.cruiseState.available # TODO: remove this exception once this mismatch is resolved brake_pressed = CS.brakePressed From d261ff6d0395f3344e41fbf47b6d9aa149ac642f Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 21 Jun 2022 11:01:44 +0200 Subject: [PATCH 104/302] bump laika --- laika_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/laika_repo b/laika_repo index 824b49327a..27a0d8a776 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 824b49327aa2f41eb0dafbe3806e6c4841b19f11 +Subproject commit 27a0d8a776fc8c1eaf8608d17ce81a00136f8bd0 From f7205f3b07d15ff4e9d840a689792d7f5b5be0d8 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 21 Jun 2022 11:14:25 +0200 Subject: [PATCH 105/302] ui: metric wider set speed box (#24890) --- selfdrive/ui/qt/onroad.cc | 3 ++- selfdrive/ui/qt/onroad.h | 2 ++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 45bf41ba2d..482f04c032 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -196,6 +196,7 @@ void NvgWindow::updateState(const UIState &s) { setProperty("has_eu_speed_limit", nav_alive && speed_limit_sign == cereal::NavInstruction::SpeedLimitSign::VIENNA); setProperty("is_cruise_set", cruise_set); + setProperty("is_metric", s.scene.is_metric); setProperty("speed", cur_speed); setProperty("setSpeed", set_speed); setProperty("speedUnit", s.scene.is_metric ? "km/h" : "mph"); @@ -225,8 +226,8 @@ void NvgWindow::drawHud(QPainter &p) { // Draw outer box + border to contain set speed and speed limit int default_rect_width = 172; int rect_width = default_rect_width; + if (is_metric || has_eu_speed_limit) rect_width = 200; if (has_us_speed_limit && speedLimitStr.size() >= 3) rect_width = 223; - else if (has_eu_speed_limit) rect_width = 200; int rect_height = 204; if (has_us_speed_limit) rect_height = 402; diff --git a/selfdrive/ui/qt/onroad.h b/selfdrive/ui/qt/onroad.h index e58d7a7972..4cd88fc9e3 100644 --- a/selfdrive/ui/qt/onroad.h +++ b/selfdrive/ui/qt/onroad.h @@ -34,6 +34,7 @@ class NvgWindow : public CameraViewWidget { Q_PROPERTY(bool is_cruise_set MEMBER is_cruise_set); Q_PROPERTY(bool has_eu_speed_limit MEMBER has_eu_speed_limit); Q_PROPERTY(bool has_us_speed_limit MEMBER has_us_speed_limit); + Q_PROPERTY(bool is_metric MEMBER is_metric); Q_PROPERTY(bool engageable MEMBER engageable); Q_PROPERTY(bool dmActive MEMBER dmActive); @@ -57,6 +58,7 @@ private: float setSpeed; float speedLimit; bool is_cruise_set = false; + bool is_metric = false; bool engageable = false; bool dmActive = false; bool hideDM = false; From 21dd464fd3b0e23e2277479532c56230fe1e66bd Mon Sep 17 00:00:00 2001 From: sshane Date: Tue, 21 Jun 2022 03:22:38 -0700 Subject: [PATCH 106/302] Revert "VW FPv2: reduce number of ECU queries (#24706)" This reverts commit 6c02e554e7174745c7605f4e8f0e3c1aea637091. --- selfdrive/car/fw_versions.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 66f0564fca..758485c393 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -148,14 +148,12 @@ REQUESTS: List[Request] = [ "volkswagen", [VOLKSWAGEN_VERSION_REQUEST_MULTI], [VOLKSWAGEN_VERSION_RESPONSE], - whitelist_ecus=[Ecu.srs, Ecu.eps, Ecu.fwdRadar], rx_offset=VOLKSWAGEN_RX_OFFSET, ), Request( "volkswagen", [VOLKSWAGEN_VERSION_REQUEST_MULTI], [VOLKSWAGEN_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine, Ecu.transmission], ), # Mazda Request( From 278f7b9e8a54839989d6a5bd8d37d6aeca789d2a Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 21 Jun 2022 13:15:26 +0200 Subject: [PATCH 107/302] ui: draw MAX above set speed (#24930) --- selfdrive/ui/qt/onroad.cc | 44 ++++++++++++++++++++------------------- 1 file changed, 23 insertions(+), 21 deletions(-) diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 482f04c032..d92cf36b89 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -241,26 +241,6 @@ void NvgWindow::drawHud(QPainter &p) { p.setBrush(blackColor(166)); drawRoundedRect(p, set_speed_rect, top_radius, top_radius, bottom_radius, bottom_radius); - // Draw set speed - if (is_cruise_set) { - if (speedLimit > 0 && status != STATUS_DISENGAGED && status != STATUS_OVERRIDE) { - p.setPen(interpColor( - setSpeed, - {speedLimit + 5, speedLimit + 15, speedLimit + 25}, - {whiteColor(), QColor(0xff, 0x95, 0x00, 0xff), QColor(0xff, 0x00, 0x00, 0xff)} - )); - } else { - p.setPen(whiteColor()); - } - } else { - p.setPen(QColor(0x72, 0x72, 0x72, 0xff)); - } - configFont(p, "Open Sans", 90, "Bold"); - QRect speed_rect = getTextRect(p, Qt::AlignCenter, setSpeedStr); - speed_rect.moveCenter({set_speed_rect.center().x(), 0}); - speed_rect.moveTop(set_speed_rect.top() + 8); - p.drawText(speed_rect, Qt::AlignCenter, setSpeedStr); - // Draw MAX if (is_cruise_set) { if (status == STATUS_DISENGAGED) { @@ -282,9 +262,31 @@ void NvgWindow::drawHud(QPainter &p) { configFont(p, "Open Sans", 40, "SemiBold"); QRect max_rect = getTextRect(p, Qt::AlignCenter, "MAX"); max_rect.moveCenter({set_speed_rect.center().x(), 0}); - max_rect.moveTop(set_speed_rect.top() + 123); + max_rect.moveTop(set_speed_rect.top() + 23); p.drawText(max_rect, Qt::AlignCenter, "MAX"); + // Draw set speed + if (is_cruise_set) { + if (speedLimit > 0 && status != STATUS_DISENGAGED && status != STATUS_OVERRIDE) { + p.setPen(interpColor( + setSpeed, + {speedLimit + 5, speedLimit + 15, speedLimit + 25}, + {whiteColor(), QColor(0xff, 0x95, 0x00, 0xff), QColor(0xff, 0x00, 0x00, 0xff)} + )); + } else { + p.setPen(whiteColor()); + } + } else { + p.setPen(QColor(0x72, 0x72, 0x72, 0xff)); + } + configFont(p, "Open Sans", 90, "Bold"); + QRect speed_rect = getTextRect(p, Qt::AlignCenter, setSpeedStr); + speed_rect.moveCenter({set_speed_rect.center().x(), 0}); + speed_rect.moveTop(set_speed_rect.top() + 67); + p.drawText(speed_rect, Qt::AlignCenter, setSpeedStr); + + + // US/Canada (MUTCD style) sign if (has_us_speed_limit) { const int border_width = 6; From 67b601e0efb5f33697cadadb50d32debb4325d60 Mon Sep 17 00:00:00 2001 From: Anton Rudomanenko Date: Tue, 21 Jun 2022 16:23:43 +0300 Subject: [PATCH 108/302] replay: handle missing socket while replaying route log with --allow flag (#24933) * fix: fix the problem with replay routes locally * fix: Exception with --allow flag in replay.cc Co-authored-by: Anton Rudomaneko --- selfdrive/ui/replay/replay.cc | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/ui/replay/replay.cc b/selfdrive/ui/replay/replay.cc index 5eb7469c92..cf7520b361 100644 --- a/selfdrive/ui/replay/replay.cc +++ b/selfdrive/ui/replay/replay.cc @@ -360,7 +360,8 @@ void Replay::stream() { setCurrentSegment(toSeconds(cur_mono_time_) / 60); // migration for pandaState -> pandaStates to keep UI working for old segments - if (cur_which == cereal::Event::Which::PANDA_STATE_D_E_P_R_E_C_A_T_E_D) { + if (cur_which == cereal::Event::Which::PANDA_STATE_D_E_P_R_E_C_A_T_E_D && + sockets_[cereal::Event::Which::PANDA_STATES] != nullptr) { MessageBuilder msg; auto ps = msg.initEvent().initPandaStates(1); ps[0].setIgnitionLine(true); From 95d8517a81d23e0c385b5f931e7e89a3d3e52b17 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 21 Jun 2022 16:26:40 +0200 Subject: [PATCH 109/302] car_bug_report.yml: fix labels --- .github/ISSUE_TEMPLATE/car_bug_report.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/ISSUE_TEMPLATE/car_bug_report.yml b/.github/ISSUE_TEMPLATE/car_bug_report.yml index 23527c3a43..7f368f11b4 100644 --- a/.github/ISSUE_TEMPLATE/car_bug_report.yml +++ b/.github/ISSUE_TEMPLATE/car_bug_report.yml @@ -1,6 +1,6 @@ name: Car bug report description: For issues with a particular car make or model -labels: ["car bug"] +labels: ["car", "bug"] body: - type: markdown From 0e0b5c4e24a8da64362c8dbf851dbe0f806916c0 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Tue, 21 Jun 2022 12:07:00 -0700 Subject: [PATCH 110/302] Revert "Rocket league model (#24869)" (#24936) * Revert rocket league * revert ref commit * New model ref commit --- selfdrive/modeld/models/driving.h | 2 +- selfdrive/modeld/models/supercombo.dlc | 4 ++-- selfdrive/modeld/models/supercombo.onnx | 4 ++-- selfdrive/modeld/thneed/compile.cc | 2 +- selfdrive/modeld/thneed/optimizer.cc | 8 ++++---- selfdrive/test/process_replay/model_replay_ref_commit | 2 +- 6 files changed, 11 insertions(+), 11 deletions(-) diff --git a/selfdrive/modeld/models/driving.h b/selfdrive/modeld/models/driving.h index a691051636..97e65fbc0e 100644 --- a/selfdrive/modeld/models/driving.h +++ b/selfdrive/modeld/models/driving.h @@ -245,7 +245,7 @@ struct ModelOutput { constexpr int OUTPUT_SIZE = sizeof(ModelOutput) / sizeof(float); #ifdef TEMPORAL - constexpr int TEMPORAL_SIZE = 512+256; + constexpr int TEMPORAL_SIZE = 512; #else constexpr int TEMPORAL_SIZE = 0; #endif diff --git a/selfdrive/modeld/models/supercombo.dlc b/selfdrive/modeld/models/supercombo.dlc index 90f7a2e65b..23f6d904fb 100644 --- a/selfdrive/modeld/models/supercombo.dlc +++ b/selfdrive/modeld/models/supercombo.dlc @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:4c2cb3a3054f3292bbe538d6b793908dc2e234c200802d41b6766d3cb51b0b44 -size 101662751 +oid sha256:027cbb1fabae369878271cb0e3505071a8bdaa07473fad9a0b2e8d695c5dc1ff +size 76725611 diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index 0493398560..9023c18dd7 100644 --- a/selfdrive/modeld/models/supercombo.onnx +++ b/selfdrive/modeld/models/supercombo.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:96b60d0bfd1386c93b4f79195aa1c5e77b23e0250578a308ee2c58857ed5eb49 -size 102570834 +oid sha256:484976ea5bd4ddcabc82e95faf30d7311a27802c1e337472558699fa2395a499 +size 77472267 diff --git a/selfdrive/modeld/thneed/compile.cc b/selfdrive/modeld/thneed/compile.cc index a2f55ffd97..f76c63b2b9 100644 --- a/selfdrive/modeld/thneed/compile.cc +++ b/selfdrive/modeld/thneed/compile.cc @@ -5,7 +5,7 @@ #include "selfdrive/modeld/thneed/thneed.h" #include "system/hardware/hw.h" -#define TEMPORAL_SIZE 512+256 +#define TEMPORAL_SIZE 512 #define DESIRE_LEN 8 #define TRAFFIC_CONVENTION_LEN 2 diff --git a/selfdrive/modeld/thneed/optimizer.cc b/selfdrive/modeld/thneed/optimizer.cc index 39737d3d76..03d20ff386 100644 --- a/selfdrive/modeld/thneed/optimizer.cc +++ b/selfdrive/modeld/thneed/optimizer.cc @@ -9,7 +9,7 @@ extern map g_program_source; -/*static int is_same_size_image(cl_mem a, cl_mem b) { +static int is_same_size_image(cl_mem a, cl_mem b) { size_t a_width, a_height, a_depth, a_array_size, a_row_pitch, a_slice_pitch; clGetImageInfo(a, CL_IMAGE_WIDTH, sizeof(a_width), &a_width, NULL); clGetImageInfo(a, CL_IMAGE_HEIGHT, sizeof(a_height), &a_height, NULL); @@ -29,7 +29,7 @@ extern map g_program_source; return (a_width == b_width) && (a_height == b_height) && (a_depth == b_depth) && (a_array_size == b_array_size) && (a_row_pitch == b_row_pitch) && (a_slice_pitch == b_slice_pitch); -}*/ +} static cl_mem make_image_like(cl_context context, cl_mem val) { cl_image_format format; @@ -138,7 +138,7 @@ int Thneed::optimize() { // delete useless copy layers // saves ~0.7 ms - /*if (kq[i]->name == "concatenation" || kq[i]->name == "flatten") { + if (kq[i]->name == "concatenation" || kq[i]->name == "flatten") { string in = kq[i]->args[kq[i]->get_arg_num("input")]; string out = kq[i]->args[kq[i]->get_arg_num("output")]; if (is_same_size_image(*(cl_mem*)in.data(), *(cl_mem*)out.data())) { @@ -148,7 +148,7 @@ int Thneed::optimize() { kq.erase(kq.begin()+i); --i; } - }*/ + } // NOTE: if activations/accumulation are done in the wrong order, this will be wrong diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 0c4c2305eb..9f9b822693 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -5434b3c1696554e9a889e77f794d80cd1cb0a7ec +df0ce74929dd6b5fa7a55224baefeff4bac6d785 From 1d447441239b3086e1f37185e2e5d210c80c8164 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 21 Jun 2022 19:26:20 -0700 Subject: [PATCH 111/302] jenkins: set successful boot flag --- selfdrive/test/setup_device_ci.sh | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh index 99acc050ea..2e5ffeacc6 100755 --- a/selfdrive/test/setup_device_ci.sh +++ b/selfdrive/test/setup_device_ci.sh @@ -36,6 +36,8 @@ fi tee $CONTINUE_PATH << EOF #!/usr/bin/bash +sudo abctl --set_success + while true; do if ! sudo systemctl is-active -q ssh; then sudo systemctl start ssh From 4efb28766e386de3117819b8a128aa782aaadf2a Mon Sep 17 00:00:00 2001 From: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com> Date: Wed, 22 Jun 2022 01:17:13 -0400 Subject: [PATCH 112/302] Honda Longitudinal: fix HUD max distance setting (#24915) Fix max distance setting on display --- selfdrive/car/honda/hondacan.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py index 6a1fb2e459..5de29b4f37 100644 --- a/selfdrive/car/honda/hondacan.py +++ b/selfdrive/car/honda/hondacan.py @@ -111,7 +111,7 @@ def create_ui_commands(packer, CP, enabled, pcm_speed, hud, is_metric, idx, stoc acc_hud_values = { 'CRUISE_SPEED': hud.v_cruise, 'ENABLE_MINI_CAR': 1, - 'HUD_DISTANCE': 3, # max distance setting on display + 'HUD_DISTANCE': 0, # max distance setting on display 'IMPERIAL_UNIT': int(not is_metric), 'HUD_LEAD': 2 if enabled and hud.lead_visible else 1 if enabled else 0, 'SET_ME_X01_2': 1, From dd67853526cc2cda20edc51c45bd9c65a1fa931b Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 21 Jun 2022 22:40:16 -0700 Subject: [PATCH 113/302] update refs --- selfdrive/test/process_replay/ref_commit | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 8ed68d5bdd..b2623dc8dc 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -ed1dfb8b155ebcd8fdad4e06462b3bb7869fc67b +4efb28766e386de3117819b8a128aa782aaadf2a \ No newline at end of file From f99a091eaaaa65c4a7ec3e2e22e045e6263f6bcd Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 21 Jun 2022 23:39:26 -0700 Subject: [PATCH 114/302] update camerad gitignores --- .gitignore | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.gitignore b/.gitignore index 334b1b4fed..0092c4dc94 100644 --- a/.gitignore +++ b/.gitignore @@ -49,8 +49,8 @@ selfdrive/loggerd/loggerd selfdrive/loggerd/bootlog selfdrive/sensord/_gpsd selfdrive/sensord/_sensord -selfdrive/camerad/camerad -selfdrive/camerad/test/ae_gray_test +system/camerad/camerad +system/camerad/test/ae_gray_test selfdrive/modeld/_modeld selfdrive/modeld/_dmonitoringmodeld /src/ From 789f2d195cee7b7dd8dd07d36a4e2e9b6b442e38 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 22 Jun 2022 01:03:29 -0700 Subject: [PATCH 115/302] compatibility docs: fixup steering torque star (#24940) * Ascent has good torque, hard code Toyota, print all unexpected torque star cars * update docs * Use subtests * hardcode CHR for now generate * Hard code Impreza * update refs --- docs/CARS.md | 32 ++++++++++---------- selfdrive/car/subaru/values.py | 2 +- selfdrive/car/tests/test_docs.py | 37 ++++++++++++++---------- selfdrive/car/torque_data.json | 2 +- selfdrive/car/toyota/values.py | 1 + selfdrive/test/process_replay/ref_commit | 2 +- 6 files changed, 41 insertions(+), 35 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 73ffcc0e0a..de7dbacf28 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -35,7 +35,7 @@ How We Rate The Cars **All supported cars can move between the tiers as support changes.** -# Gold - 29 cars +# Gold - 33 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -52,9 +52,13 @@ How We Rate The Cars |Lexus|ES 2019-21|All|||||| |Lexus|ES Hybrid 2019-22|All|||||| |Lexus|NX 2020|All|||||| +|Lexus|NX Hybrid 2020|All|||||| |Lexus|RX 2020-22|All|||||| |Lexus|UX Hybrid 2019-21|All|||||| +|Toyota|Alphard 2019-20|All|||||| +|Toyota|Alphard Hybrid 2021|All|||||| |Toyota|Avalon 2022|All|||||| +|Toyota|Avalon Hybrid 2022|All|||||| |Toyota|Camry 2021-22|All||[4](#footnotes)|||| |Toyota|Camry Hybrid 2021-22|All|||||| |Toyota|Corolla 2020-22|All|||||| @@ -104,13 +108,15 @@ How We Rate The Cars |Kia|Sorento 2018|SCC + LKAS|||||| |Kia|Sorento 2019|SCC + LKAS|||||| |Kia|Stinger 2018|SCC + LKAS|||||| +|Lexus|CT Hybrid 2017-18|LSS|[3](#footnotes)||||| +|Lexus|ES Hybrid 2017-18|LSS|[3](#footnotes)||||| |Lexus|NX 2018-19|All|[3](#footnotes)||||| |Lexus|NX Hybrid 2018-19|All|[3](#footnotes)||||| -|Lexus|NX Hybrid 2020|All|||||| |Lexus|RX Hybrid 2020-21|All|||||| |Mazda|CX-5 2022|All|||||| |SEAT|Ateca 2018|Driver Assistance|||||| |SEAT|Leon 2014-20|Driver Assistance|||||| +|Subaru|Ascent 2019-20|All|||||| |Subaru|Crosstrek 2020-21|EyeSight|||||| |Subaru|Forester 2019-21|All|||||| |Subaru|Impreza 2020-21|EyeSight|||||| @@ -121,10 +127,8 @@ How We Rate The Cars |Škoda|Octavia RS 2016|Driver Assistance|||||| |Škoda|Scala 2020|Driver Assistance|||||| |Škoda|Superb 2015-18|Driver Assistance|||||| -|Toyota|Alphard 2019-20|All|||||| -|Toyota|Alphard Hybrid 2021|All|||||| |Toyota|Avalon 2019-21|TSS-P|[3](#footnotes)||||| -|Toyota|Avalon Hybrid 2022|All|||||| +|Toyota|Avalon Hybrid 2019-21|TSS-P|[3](#footnotes)||||| |Toyota|Camry 2018-20|All||[4](#footnotes)|||| |Toyota|Camry Hybrid 2018-20|All||[4](#footnotes)|||| |Toyota|Highlander 2017-19|All|[3](#footnotes)||||| @@ -150,7 +154,7 @@ How We Rate The Cars |Volkswagen|Taos 2022[7](#footnotes)|Driver Assistance|||||| |Volkswagen|Touran 2017|Driver Assistance|||||| -# Bronze - 71 cars +# Bronze - 67 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -197,10 +201,8 @@ How We Rate The Cars |Jeep|Grand Cherokee 2019-20|Adaptive Cruise|||||| |Kia|Niro Plug-in Hybrid 2019|SCC + LKAS|||||| |Kia|Optima 2017|SCC + LKAS|||||| -|Lexus|CT Hybrid 2017-18|LSS|[3](#footnotes)||||| -|Lexus|ES Hybrid 2017-18|LSS|[3](#footnotes)||||| -|Lexus|IS 2017-19|All|||||| -|Lexus|RC 2020|All|||||| +|Lexus|IS 2017-19|All|||||| +|Lexus|RC 2020|All|||||| |Lexus|RX 2016-18|All|[3](#footnotes)||||| |Lexus|RX Hybrid 2016-19|All|[3](#footnotes)||||| |Mazda|CX-9 2021|All|||||| @@ -208,13 +210,11 @@ How We Rate The Cars |Nissan|Leaf 2018-22|ProPILOT|||||| |Nissan|Rogue 2018-20|ProPILOT|||||| |Nissan|X-Trail 2017|ProPILOT|||||| -|Subaru|Ascent 2019-20|All|||||| -|Subaru|Crosstrek 2018-19|EyeSight|||||| -|Subaru|Impreza 2017-19|EyeSight|||||| -|Toyota|Avalon 2016-18|TSS-P|[3](#footnotes)||||| -|Toyota|Avalon Hybrid 2019-21|TSS-P|[3](#footnotes)||||| +|Subaru|Crosstrek 2018-19|EyeSight|||||| +|Subaru|Impreza 2017-19|EyeSight|||||| +|Toyota|Avalon 2016-18|TSS-P|[3](#footnotes)||||| |Toyota|C-HR 2017-21|All|||||| -|Toyota|C-HR Hybrid 2017-19|All|||||| +|Toyota|C-HR Hybrid 2017-19|All|||||| |Toyota|Corolla 2017-19|All|[3](#footnotes)||||| |Toyota|Prius v 2017|TSS-P|[3](#footnotes)||||| |Toyota|RAV4 2016-18|TSS-P|[3](#footnotes)||||| diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 45358eb3a4..9badc3ca50 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -41,7 +41,7 @@ class SubaruCarInfo(CarInfo): CAR_INFO: Dict[str, Union[SubaruCarInfo, List[SubaruCarInfo]]] = { - CAR.ASCENT: SubaruCarInfo("Subaru Ascent 2019-20", "All"), + CAR.ASCENT: SubaruCarInfo("Subaru Ascent 2019-20", "All", good_torque=True), CAR.IMPREZA: [ SubaruCarInfo("Subaru Impreza 2017-19"), SubaruCarInfo("Subaru Crosstrek 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), diff --git a/selfdrive/car/tests/test_docs.py b/selfdrive/car/tests/test_docs.py index b4bc14ef00..98c909a9be 100755 --- a/selfdrive/car/tests/test_docs.py +++ b/selfdrive/car/tests/test_docs.py @@ -16,32 +16,37 @@ class TestCarDocs(unittest.TestCase): current_cars_md = f.read() self.assertEqual(generated_cars_md, current_cars_md, - "Run selfdrive/car/docs.py to generate new supported cars documentation") + "Run selfdrive/car/docs.py to update the compatibility documentation") def test_missing_car_info(self): all_car_info_platforms = get_interface_attr("CAR_INFO", combine_brands=True).keys() for platform in sorted(interfaces.keys()): - if platform not in all_car_info_platforms: - self.fail("Platform: {} doesn't exist in CarInfo".format(platform)) + with self.subTest(platform=platform): + self.assertTrue(platform in all_car_info_platforms, "Platform: {} doesn't exist in CarInfo".format(platform)) def test_naming_conventions(self): - # Asserts market-standard car naming conventions by make + # Asserts market-standard car naming conventions by brand for car in self.all_cars: - tokens = car.model.lower().split(" ") - if car.car_name == "hyundai": - self.assertNotIn("phev", tokens, "Use `Plug-in Hybrid`") - self.assertNotIn("hev", tokens, "Use `Hybrid`") - self.assertNotIn("ev", tokens, "Use `Electric`") - if "plug-in hybrid" in car.model.lower(): - self.assertIn("Plug-in Hybrid", car.model, "Use correct capitalization") - elif car.car_name == "toyota": - if "rav4" in tokens: - self.assertIn("RAV4", car.model, "Use correct capitalization") + with self.subTest(car=car): + tokens = car.model.lower().split(" ") + if car.car_name == "hyundai": + self.assertNotIn("phev", tokens, "Use `Plug-in Hybrid`") + self.assertNotIn("hev", tokens, "Use `Hybrid`") + self.assertNotIn("ev", tokens, "Use `Electric`") + if "plug-in hybrid" in car.model.lower(): + self.assertIn("Plug-in Hybrid", car.model, "Use correct capitalization") + elif car.car_name == "toyota": + if "rav4" in tokens: + self.assertIn("RAV4", car.model, "Use correct capitalization") def test_torque_star(self): + # Asserts brand-specific assumptions around steering torque star for car in self.all_cars: - if car.car_name == "honda": - self.assertTrue(car.row[Column.STEERING_TORQUE] in (Star.EMPTY, Star.HALF), f"{car.name} has full torque star") + with self.subTest(car=car): + if car.car_name == "honda": + self.assertIn(car.row[Column.STEERING_TORQUE], (Star.EMPTY, Star.HALF), f"{car.name} has full torque star") + elif car.car_name in ("toyota", "hyundai"): + self.assertNotEqual(car.row[Column.STEERING_TORQUE], Star.EMPTY, f"{car.name} has no torque star") if __name__ == "__main__": diff --git a/selfdrive/car/torque_data.json b/selfdrive/car/torque_data.json index 63ee0e9bcd..4917cba9bc 100644 --- a/selfdrive/car/torque_data.json +++ b/selfdrive/car/torque_data.json @@ -1 +1 @@ -{"LAT_ACCEL_FACTOR": {"HONDA PILOT 2017": 1.682289482065265, "HONDA CIVIC 2016": 1.5248128495527884, "TOYOTA CAMRY 2018": 2.1115709806216447, "TOYOTA COROLLA HYBRID TSS2 2019": 2.3250600977240077, "TOYOTA RAV4 2019": 2.625504029066767, "HYUNDAI PALISADE 2020": 2.5250855675875634, "TOYOTA SIENNA 2018": 1.8254254785341577, "ACURA RDX 2020": 1.3998101622214894, "TOYOTA RAV4 2017": 1.948190869577896, "HONDA RIDGELINE 2017": 1.4158181862793415, "TOYOTA PRIUS 2017": 1.9142926195557595, "TOYOTA HIGHLANDER HYBRID 2020": 2.1097056247344392, "HYUNDAI SONATA 2020": 3.2488989629905944, "KIA STINGER GT2 2018": 2.7592622336517834, "TOYOTA HIGHLANDER 2020": 2.0408544157877055, "HONDA ACCORD 2018": 1.6374118241564064, "TOYOTA PRIUS TSS2 2021": 2.3207270770298365, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 1.46050785084946, "LEXUS NX 2020": 2.29533657249232, "TOYOTA RAV4 HYBRID 2019": 2.4003012079562085, "HONDA CIVIC (BOSCH) 2019": 1.6523031416671652, "KIA NIRO HYBRID 2021": 2.743464625803003, "HONDA ACCORD HYBRID 2018": 1.5904016830979033, "LEXUS NX HYBRID 2018": 2.398678119681945, "TOYOTA COROLLA TSS2 2019": 2.3859244449846466, "VOLKSWAGEN ARTEON 1ST GEN": 1.4249208219414902, "TOYOTA CAMRY HYBRID 2021": 2.5434553806317055, "VOLKSWAGEN JETTA 7TH GEN": 1.2228130240634283, "HONDA INSIGHT 2019": 1.468352089969897, "SUBARU FORESTER 2019": 3.6185035528523546, "HYUNDAI ELANTRA 2021": 3.5294999663335185, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 2.2179616966432905, "HYUNDAI KONA HYBRID 2020": 4.493208192966529, "HONDA ODYSSEY 2018": 1.8838175399087222, "LEXUS RX 2016": 1.3912132245094184, "TOYOTA COROLLA 2017": 3.0143547548384735, "LEXUS ES 2019": 2.012201253045193, "HYUNDAI SANTA FE 2019": 3.039728566484244, "TOYOTA AVALON 2022": 2.4619858654670885, "JEEP GRAND CHEROKEE V6 2018": 1.8411674990629987, "CHEVROLET VOLT PREMIER 2017": 1.5943438675127841, "TOYOTA RAV4 HYBRID 2017": 1.9803053616868995, "LEXUS RX 2020": 1.664616846377383, "TOYOTA HIGHLANDER HYBRID 2018": 1.8866764457400844, "TOYOTA CAMRY HYBRID 2018": 2.014213351947917, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 1.4428896585442685, "TOYOTA MIRAI 2021": 2.7217623852898853, "LEXUS IS 2018": 3.5624668608596837, "TOYOTA HIGHLANDER 2017": 1.9199133105823853, "HYUNDAI SONATA HYBRID 2021": 2.7313907441569554, "VOLKSWAGEN ATLAS 1ST GEN": 1.4483948408160645, "LEXUS ES HYBRID 2019": 2.4138026617523547, "HYUNDAI GENESIS 2015-2016": 1.7636839808044658, "JEEP GRAND CHEROKEE 2019": 1.787264083939164, "SUBARU ASCENT LIMITED 2019": 3.0494069339774565, "HONDA CR-V 2017": 1.9828470679233807, "HONDA FIT 2018": 1.594940026552055, "TOYOTA CAMRY 2021": 2.5057990840460342, "AUDI Q3 2ND GEN": 1.4558300885316715, "AUDI A3 3RD GEN": 1.5304173783542625, "LEXUS RX HYBRID 2017": 1.577216425446677, "HONDA CIVIC 2022": 2.69252285552613, "GENESIS G70 2018": 3.866842361627636, "CHRYSLER PACIFICA HYBRID 2018": 1.5771851419640903, "VOLKSWAGEN PASSAT 8TH GEN": 1.2985597059739313, "HONDA CR-V 2016": 0.7745984062630755, "HYUNDAI IONIQ PHEV 2020": 2.5696218908589383, "GMC ACADIA DENALI 2018": 1.3310088601868082, "HYUNDAI SONATA 2019": 1.9736552675022665, "TOYOTA AVALON 2019": 1.7245149905226294, "TOYOTA C-HR 2018": 1.5895016960662856, "HONDA CR-V HYBRID 2019": 2.0687746810729193, "CHRYSLER PACIFICA 2020": 1.40536880000744, "HYUNDAI IONIQ ELECTRIC 2020": 3.3220838625838667, "VOLKSWAGEN TIGUAN 2ND GEN": NaN, "LEXUS NX 2018": 1.7753192756242595, "KIA OPTIMA SX 2019 & 2016": 3.12625562280304, "TOYOTA AVALON HYBRID 2019": 1.7681286449373381, "TOYOTA RAV4 HYBRID 2022": 2.5518187542231816, "HONDA PASSPORT 2021": 1.5174924139130355, "KIA K5 2021": 2.482916204106975, "ACURA ILX 2016": 1.5237423964720282, "HYUNDAI IONIQ HYBRID 2017-2019": 2.3723887901632645, "KIA NIRO EV 2020": 2.924651969180446, "SUBARU IMPREZA SPORT 2020": 2.5317689549587694, "CHRYSLER PACIFICA HYBRID 2017": 1.167126725149114, "HYUNDAI KONA ELECTRIC 2019": 4.201092987427836, "HYUNDAI ELANTRA HYBRID 2021": 3.7153193626001926, "HYUNDAI SANTA FE HYBRID 2022": 3.3049230586030545, "CHRYSLER PACIFICA 2018": 1.524867383058782, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": 2.5970979517766213, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 1.5460982690267173, "MAZDA CX-9 2021": 1.9514800984278198, "HYUNDAI SANTA FE 2022": 3.5354982200434524, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 1.8902492836532216, "HONDA HRV 2019": 2.1262957371020352, "TOYOTA AVALON HYBRID 2022": 2.4142150048378683, "SUBARU IMPREZA LIMITED 2019": 1.2203463907025918, "GENESIS G80 2017": 2.4086794443413906, "VOLKSWAGEN TAOS 1ST GEN": 2.0031666974545947, "KIA FORTE E 2018 & GT 2021": 2.022553820222557, "CADILLAC ESCALADE ESV 2016": 1.5522339636408988, "TOYOTA C-HR 2021": 1.6519334844316687, "TOYOTA C-HR HYBRID 2018": 1.3193315010905482}, "MAX_LAT_ACCEL_MEASURED": {"HONDA PILOT 2017": 0.9069354290994807, "HONDA CIVIC 2016": 0.4030275472529351, "TOYOTA CAMRY 2018": 1.686123168195758, "TOYOTA COROLLA HYBRID TSS2 2019": 1.9139332621491167, "TOYOTA RAV4 2019": 2.234047196286479, "HYUNDAI PALISADE 2020": 1.8303582523301922, "TOYOTA SIENNA 2018": 1.4752503435300715, "ACURA RDX 2020": 0.40911581320000334, "TOYOTA RAV4 2017": 1.6622227720995595, "HONDA RIDGELINE 2017": 0.8224685813281227, "TOYOTA PRIUS 2017": 1.4548827870876067, "TOYOTA HIGHLANDER HYBRID 2020": 2.0649784271823037, "HYUNDAI SONATA 2020": 2.243989856570093, "KIA STINGER GT2 2018": 1.9531287107084392, "TOYOTA HIGHLANDER 2020": 1.659381392090836, "HONDA ACCORD 2018": 0.40486739531686267, "TOYOTA PRIUS TSS2 2021": 1.861541601048098, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 1.1930739374812243, "LEXUS NX 2020": 1.565268724838564, "TOYOTA RAV4 HYBRID 2019": 2.0915384047218426, "HONDA CIVIC (BOSCH) 2019": 0.4062886118517984, "KIA NIRO HYBRID 2021": NaN, "HONDA ACCORD HYBRID 2018": 0.35128914564548286, "LEXUS NX HYBRID 2018": 1.81821359787186, "TOYOTA COROLLA TSS2 2019": 1.911280958056631, "VOLKSWAGEN ARTEON 1ST GEN": 1.2587939472578302, "TOYOTA CAMRY HYBRID 2021": 2.312510643730013, "VOLKSWAGEN JETTA 7TH GEN": 1.232161945396623, "HONDA INSIGHT 2019": 0.5174836462945298, "SUBARU FORESTER 2019": 2.29255993930968, "HYUNDAI ELANTRA 2021": NaN, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 2.133978602602408, "HYUNDAI KONA HYBRID 2020": NaN, "HONDA ODYSSEY 2018": 0.8254773781363679, "LEXUS RX 2016": 1.0954776820595344, "TOYOTA COROLLA 2017": 2.2012870528168964, "LEXUS ES 2019": 2.069508805495439, "HYUNDAI SANTA FE 2019": 2.3763720477660253, "TOYOTA AVALON 2022": 2.531962323786023, "JEEP GRAND CHEROKEE V6 2018": 1.4193323242487865, "CHEVROLET VOLT PREMIER 2017": 1.8576430337666092, "TOYOTA RAV4 HYBRID 2017": 1.7425797219020926, "LEXUS RX 2020": 1.5118835180227874, "TOYOTA HIGHLANDER HYBRID 2018": 1.6872527654528833, "TOYOTA CAMRY HYBRID 2018": 1.6793468378089895, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 1.5614447712441282, "TOYOTA MIRAI 2021": 2.271146483563897, "LEXUS IS 2018": NaN, "TOYOTA HIGHLANDER 2017": 1.6573774863189379, "HYUNDAI SONATA HYBRID 2021": 1.9464120717803253, "VOLKSWAGEN ATLAS 1ST GEN": 1.6867005451451638, "LEXUS ES HYBRID 2019": 1.956450687999482, "HYUNDAI GENESIS 2015-2016": 1.5359761378898085, "JEEP GRAND CHEROKEE 2019": 1.2418961305308847, "SUBARU ASCENT LIMITED 2019": NaN, "HONDA CR-V 2017": 0.2642062271814174, "HONDA FIT 2018": 0.5896345937094754, "TOYOTA CAMRY 2021": 2.1783533980215166, "AUDI Q3 2ND GEN": 1.1582239457022647, "AUDI A3 3RD GEN": 1.598699116126939, "LEXUS RX HYBRID 2017": 1.319771127672888, "HONDA CIVIC 2022": 1.1806949852580793, "GENESIS G70 2018": 2.2496820850331134, "CHRYSLER PACIFICA HYBRID 2018": 1.294798200968084, "VOLKSWAGEN PASSAT 8TH GEN": 1.247540921731637, "HONDA CR-V 2016": 0.6991119250342539, "HYUNDAI IONIQ PHEV 2020": 1.9062392690595655, "GMC ACADIA DENALI 2018": 1.2986994230652662, "HYUNDAI SONATA 2019": 1.257445187146704, "TOYOTA AVALON 2019": 1.664577368475227, "TOYOTA C-HR 2018": 1.308490445144888, "HONDA CR-V HYBRID 2019": 0.4693072746041504, "CHRYSLER PACIFICA 2020": 1.1712413003138664, "HYUNDAI IONIQ ELECTRIC 2020": NaN, "VOLKSWAGEN TIGUAN 2ND GEN": 1.1573057001955744, "LEXUS NX 2018": 1.9457312007432144, "KIA OPTIMA SX 2019 & 2016": 2.0928228595938845, "TOYOTA AVALON HYBRID 2019": NaN, "TOYOTA RAV4 HYBRID 2022": 1.7647290773049569, "HONDA PASSPORT 2021": 0.8248357750132685, "KIA K5 2021": 1.4628018983720577, "ACURA ILX 2016": 0.6330753921140401, "HYUNDAI IONIQ HYBRID 2017-2019": NaN, "KIA NIRO EV 2020": 2.020186575503497, "SUBARU IMPREZA SPORT 2020": 2.136786720514988, "CHRYSLER PACIFICA HYBRID 2017": 1.0642918033307907, "HYUNDAI KONA ELECTRIC 2019": NaN, "HYUNDAI ELANTRA HYBRID 2021": NaN, "HYUNDAI SANTA FE HYBRID 2022": NaN, "CHRYSLER PACIFICA 2018": 1.3654603720349934, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": NaN, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 1.255230465866663, "MAZDA CX-9 2021": NaN, "HYUNDAI SANTA FE 2022": 3.3823387508235827, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 1.544104124172169, "HONDA HRV 2019": 0.7492792210307291, "TOYOTA AVALON HYBRID 2022": NaN, "SUBARU IMPREZA LIMITED 2019": 0.8127509604734238, "GENESIS G80 2017": NaN, "VOLKSWAGEN TAOS 1ST GEN": 1.6590543949912684, "KIA FORTE E 2018 & GT 2021": 2.3970573789339786, "CADILLAC ESCALADE ESV 2016": NaN, "TOYOTA C-HR 2021": 1.3559230155096402, "TOYOTA C-HR HYBRID 2018": 0.8910235787356033}, "FRICTION": {"HONDA PILOT 2017": 0.2168217463499328, "HONDA CIVIC 2016": 0.28406761310944795, "TOYOTA CAMRY 2018": 0.1327947477896041, "TOYOTA COROLLA HYBRID TSS2 2019": 0.21792021497538405, "TOYOTA RAV4 2019": 0.12757022360707945, "HYUNDAI PALISADE 2020": 0.13391574986922777, "TOYOTA SIENNA 2018": 0.1853443239485906, "ACURA RDX 2020": 0.18058553315570297, "TOYOTA RAV4 2017": 0.14319170324556796, "HONDA RIDGELINE 2017": 0.2380553573913589, "TOYOTA PRIUS 2017": 0.2079869382946584, "TOYOTA HIGHLANDER HYBRID 2020": 0.14038812589302646, "HYUNDAI SONATA 2020": 0.08266051305053168, "KIA STINGER GT2 2018": 0.11909534626930472, "TOYOTA HIGHLANDER 2020": 0.14658637853444048, "HONDA ACCORD 2018": 0.21616610462729247, "TOYOTA PRIUS TSS2 2021": 0.20613763260512002, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 0.16250373743651828, "LEXUS NX 2020": 0.14404022591302845, "TOYOTA RAV4 HYBRID 2019": 0.1319247989758836, "HONDA CIVIC (BOSCH) 2019": 0.2575217845562353, "KIA NIRO HYBRID 2021": 0.14468633728800306, "HONDA ACCORD HYBRID 2018": 0.21150723931119184, "LEXUS NX HYBRID 2018": 0.16117151597250162, "TOYOTA COROLLA TSS2 2019": 0.21045927995242877, "VOLKSWAGEN ARTEON 1ST GEN": 0.17828895368353925, "TOYOTA CAMRY HYBRID 2021": 0.16283734136957057, "VOLKSWAGEN JETTA 7TH GEN": 0.19508489725001105, "HONDA INSIGHT 2019": 0.25750800088299297, "SUBARU FORESTER 2019": 0.11783702069698135, "HYUNDAI ELANTRA 2021": 0.09377564130711125, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 0.14740189509875762, "HYUNDAI KONA HYBRID 2020": 0.0863709736632968, "HONDA ODYSSEY 2018": 0.2125595696498247, "LEXUS RX 2016": 0.21475140622981923, "TOYOTA COROLLA 2017": 0.12325064090161544, "LEXUS ES 2019": 0.12757526660498053, "HYUNDAI SANTA FE 2019": 0.12230125806479573, "TOYOTA AVALON 2022": 0.11030226705639488, "JEEP GRAND CHEROKEE V6 2018": 0.12871972792344108, "CHEVROLET VOLT PREMIER 2017": 0.16697256960295873, "TOYOTA RAV4 HYBRID 2017": 0.14074453855329072, "LEXUS RX 2020": 0.2249895411716623, "TOYOTA HIGHLANDER HYBRID 2018": 0.16692807938039034, "TOYOTA CAMRY HYBRID 2018": 0.13418904852016877, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 0.19324413131475543, "TOYOTA MIRAI 2021": 0.20035237756713503, "LEXUS IS 2018": 0.073103111226694, "TOYOTA HIGHLANDER 2017": 0.17502689439420385, "HYUNDAI SONATA HYBRID 2021": 0.09518615688045734, "VOLKSWAGEN ATLAS 1ST GEN": 0.12761803335799474, "LEXUS ES HYBRID 2019": 0.1682771025433274, "HYUNDAI GENESIS 2015-2016": 0.10254237048034251, "JEEP GRAND CHEROKEE 2019": 0.15702739382013717, "SUBARU ASCENT LIMITED 2019": 0.12936982863095342, "HONDA CR-V 2017": 0.22518506713451308, "HONDA FIT 2018": 0.10803295063463647, "TOYOTA CAMRY 2021": 0.15512845523424743, "AUDI Q3 2ND GEN": 0.14083949977629878, "AUDI A3 3RD GEN": 0.1611945965384188, "LEXUS RX HYBRID 2017": 0.19322020114452776, "HONDA CIVIC 2022": 0.24279247053469405, "GENESIS G70 2018": 0.06869638264150804, "CHRYSLER PACIFICA HYBRID 2018": 0.13887505891474383, "VOLKSWAGEN PASSAT 8TH GEN": 0.21714039653367842, "HONDA CR-V 2016": 0.41726236462791455, "HYUNDAI IONIQ PHEV 2020": 0.13800461817330806, "GMC ACADIA DENALI 2018": 0.3447163106452739, "HYUNDAI SONATA 2019": 0.15371520337813344, "TOYOTA AVALON 2019": 0.10392921606262978, "TOYOTA C-HR 2018": 0.2015190716953846, "HONDA CR-V HYBRID 2019": 0.19595630321202379, "CHRYSLER PACIFICA 2020": 0.14337114313208268, "HYUNDAI IONIQ ELECTRIC 2020": 0.08104502306679212, "VOLKSWAGEN TIGUAN 2ND GEN": NaN, "LEXUS NX 2018": 0.1471001686544422, "KIA OPTIMA SX 2019 & 2016": 0.11703652166984638, "TOYOTA AVALON HYBRID 2019": 0.10863628402866225, "TOYOTA RAV4 HYBRID 2022": 0.14334213238415072, "HONDA PASSPORT 2021": 0.19826160782809032, "KIA K5 2021": 0.1027179720106188, "ACURA ILX 2016": 0.35663988815912573, "HYUNDAI IONIQ HYBRID 2017-2019": 0.12332151728479951, "KIA NIRO EV 2020": 0.0892074288578785, "SUBARU IMPREZA SPORT 2020": 0.15841234487251604, "CHRYSLER PACIFICA HYBRID 2017": 0.1345638758810282, "HYUNDAI KONA ELECTRIC 2019": 0.08503096350356723, "HYUNDAI ELANTRA HYBRID 2021": 0.09887804390243872, "HYUNDAI SANTA FE HYBRID 2022": 0.11171499761140577, "CHRYSLER PACIFICA 2018": 0.13611561752951415, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": 0.10502695501512567, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 0.21818156330777305, "MAZDA CX-9 2021": 0.1793735649504697, "HYUNDAI SANTA FE 2022": 0.09184808719698756, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 0.14050744688135813, "HONDA HRV 2019": 0.17840321248608593, "TOYOTA AVALON HYBRID 2022": 0.16159049452515487, "SUBARU IMPREZA LIMITED 2019": 0.20322553080306893, "GENESIS G80 2017": 0.07934444681782107, "VOLKSWAGEN TAOS 1ST GEN": 0.18276122764341485, "KIA FORTE E 2018 & GT 2021": 0.11406160665068436, "CADILLAC ESCALADE ESV 2016": 0.15063766975884627, "TOYOTA C-HR 2021": 0.22798633346500694, "TOYOTA C-HR HYBRID 2018": 0.2036375866375624}, "ERROR_RATIO": {"HONDA PILOT 2017": 0.6158457247286419, "HONDA CIVIC 2016": 2.0785618623350928, "TOYOTA CAMRY 2018": 0.17356565057429169, "TOYOTA COROLLA HYBRID TSS2 2019": 0.10094741777075293, "TOYOTA RAV4 2019": 0.11812042718338775, "HYUNDAI PALISADE 2020": 0.30639442561268304, "TOYOTA SIENNA 2018": 0.1117307389748361, "ACURA RDX 2020": 1.9801454495960717, "TOYOTA RAV4 2017": 0.08589486116378196, "HONDA RIDGELINE 2017": 0.4319851914417577, "TOYOTA PRIUS 2017": 0.17281316158588575, "TOYOTA HIGHLANDER HYBRID 2020": 0.046325388721577, "HYUNDAI SONATA 2020": 0.4109860794021653, "KIA STINGER GT2 2018": 0.3517628781488943, "TOYOTA HIGHLANDER 2020": 0.14155072865224166, "HONDA ACCORD 2018": 2.510398061115294, "TOYOTA PRIUS TSS2 2021": 0.13593456264106363, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 0.08794943266738546, "LEXUS NX 2020": 0.3743942573190866, "TOYOTA RAV4 HYBRID 2019": 0.0845492503791727, "HONDA CIVIC (BOSCH) 2019": 2.4329816697390063, "KIA NIRO HYBRID 2021": NaN, "HONDA ACCORD HYBRID 2018": 2.9252406767451804, "LEXUS NX HYBRID 2018": 0.23060712246809048, "TOYOTA COROLLA TSS2 2019": 0.13822363784977285, "VOLKSWAGEN ARTEON 1ST GEN": 0.009661691674299285, "TOYOTA CAMRY HYBRID 2021": 0.029451711159377333, "VOLKSWAGEN JETTA 7TH GEN": 0.16591473170144055, "HONDA INSIGHT 2019": 1.3398692842898896, "SUBARU FORESTER 2019": 0.5269683780697442, "HYUNDAI ELANTRA 2021": NaN, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 0.02971857401969039, "HYUNDAI KONA HYBRID 2020": NaN, "HONDA ODYSSEY 2018": 1.0245957242729038, "LEXUS RX 2016": 0.07392586589971588, "TOYOTA COROLLA 2017": 0.31336988069649124, "LEXUS ES 2019": 0.08933657038050916, "HYUNDAI SANTA FE 2019": 0.2276812089092099, "TOYOTA AVALON 2022": 0.07120118798045925, "JEEP GRAND CHEROKEE V6 2018": 0.2065164316228118, "CHEVROLET VOLT PREMIER 2017": 0.2316223989408518, "TOYOTA RAV4 HYBRID 2017": 0.055653752888652736, "LEXUS RX 2020": 0.047792182371008345, "TOYOTA HIGHLANDER HYBRID 2018": 0.019259474082467202, "TOYOTA CAMRY HYBRID 2018": 0.11949733140330816, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 0.1996863736436734, "TOYOTA MIRAI 2021": 0.11019259478417197, "LEXUS IS 2018": NaN, "TOYOTA HIGHLANDER 2017": 0.05279963713251727, "HYUNDAI SONATA HYBRID 2021": 0.3543918194389536, "VOLKSWAGEN ATLAS 1ST GEN": 0.21694647502209782, "LEXUS ES HYBRID 2019": 0.14775474433507507, "HYUNDAI GENESIS 2015-2016": 0.0814892037361157, "JEEP GRAND CHEROKEE 2019": 0.3126997097753535, "SUBARU ASCENT LIMITED 2019": NaN, "HONDA CR-V 2017": 5.652613829506629, "HONDA FIT 2018": 1.5217432826711779, "TOYOTA CAMRY 2021": 0.07910435053686729, "AUDI Q3 2ND GEN": 0.13535089102138698, "AUDI A3 3RD GEN": 0.14353941401245793, "LEXUS RX HYBRID 2017": 0.048663813961824696, "HONDA CIVIC 2022": 1.0748206908458815, "GENESIS G70 2018": 0.688303429295532, "CHRYSLER PACIFICA HYBRID 2018": 0.11083725786301112, "VOLKSWAGEN PASSAT 8TH GEN": 0.13315924904555493, "HONDA CR-V 2016": 0.488871482749128, "HYUNDAI IONIQ PHEV 2020": 0.2756096845519595, "GMC ACADIA DENALI 2018": 0.24055364003040136, "HYUNDAI SONATA 2019": 0.4473315280277132, "TOYOTA AVALON 2019": 0.026428086100632363, "TOYOTA C-HR 2018": 0.06075105822970755, "HONDA CR-V HYBRID 2019": 2.9906016360828276, "CHRYSLER PACIFICA 2020": 0.07748732608487266, "HYUNDAI IONIQ ELECTRIC 2020": NaN, "VOLKSWAGEN TIGUAN 2ND GEN": NaN, "LEXUS NX 2018": 0.16318394527060903, "KIA OPTIMA SX 2019 & 2016": 0.4378756841929454, "TOYOTA AVALON HYBRID 2019": NaN, "TOYOTA RAV4 HYBRID 2022": 0.36478548056633514, "HONDA PASSPORT 2021": 0.5993860184637646, "KIA K5 2021": 0.6271500841947655, "ACURA ILX 2016": 0.8435442647921855, "HYUNDAI IONIQ HYBRID 2017-2019": NaN, "KIA NIRO EV 2020": 0.40355577782011604, "SUBARU IMPREZA SPORT 2020": 0.11071291640854522, "CHRYSLER PACIFICA HYBRID 2017": 0.029812269495458284, "HYUNDAI KONA ELECTRIC 2019": NaN, "HYUNDAI ELANTRA HYBRID 2021": NaN, "HYUNDAI SANTA FE HYBRID 2022": NaN, "CHRYSLER PACIFICA 2018": 0.01705753895996445, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": NaN, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 0.05790668871480552, "MAZDA CX-9 2021": NaN, "HYUNDAI SANTA FE 2022": 0.018126919430513307, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 0.1331760659016062, "HONDA HRV 2019": 1.599688433820939, "TOYOTA AVALON HYBRID 2022": NaN, "SUBARU IMPREZA LIMITED 2019": 0.2514545160390271, "GENESIS G80 2017": NaN, "VOLKSWAGEN TAOS 1ST GEN": 0.09725484306423876, "KIA FORTE E 2018 & GT 2021": 0.20381871942480628, "CADILLAC ESCALADE ESV 2016": NaN, "TOYOTA C-HR 2021": 0.05016813984196128, "TOYOTA C-HR HYBRID 2018": 0.2521485862766935}} \ No newline at end of file +{"LAT_ACCEL_FACTOR": {"HONDA PILOT 2017": 1.682289482065265, "HONDA CIVIC 2016": 1.5248128495527884, "TOYOTA CAMRY 2018": 2.1115709806216447, "TOYOTA COROLLA HYBRID TSS2 2019": 2.3250600977240077, "TOYOTA RAV4 2019": 2.625504029066767, "HYUNDAI PALISADE 2020": 2.5250855675875634, "TOYOTA SIENNA 2018": 1.8254254785341577, "ACURA RDX 2020": 1.3998101622214894, "TOYOTA RAV4 2017": 1.948190869577896, "HONDA RIDGELINE 2017": 1.4158181862793415, "TOYOTA PRIUS 2017": 1.9142926195557595, "TOYOTA HIGHLANDER HYBRID 2020": 2.1097056247344392, "HYUNDAI SONATA 2020": 3.2488989629905944, "KIA STINGER GT2 2018": 2.7592622336517834, "TOYOTA HIGHLANDER 2020": 2.0408544157877055, "HONDA ACCORD 2018": 1.6374118241564064, "TOYOTA PRIUS TSS2 2021": 2.3207270770298365, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 1.46050785084946, "LEXUS NX 2020": 2.29533657249232, "TOYOTA RAV4 HYBRID 2019": 2.4003012079562085, "HONDA CIVIC (BOSCH) 2019": 1.6523031416671652, "KIA NIRO HYBRID 2021": 2.743464625803003, "HONDA ACCORD HYBRID 2018": 1.5904016830979033, "LEXUS NX HYBRID 2018": 2.398678119681945, "TOYOTA COROLLA TSS2 2019": 2.3859244449846466, "VOLKSWAGEN ARTEON 1ST GEN": 1.4249208219414902, "TOYOTA CAMRY HYBRID 2021": 2.5434553806317055, "VOLKSWAGEN JETTA 7TH GEN": 1.2228130240634283, "HONDA INSIGHT 2019": 1.468352089969897, "SUBARU FORESTER 2019": 3.6185035528523546, "HYUNDAI ELANTRA 2021": 3.5294999663335185, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 2.2179616966432905, "HYUNDAI KONA HYBRID 2020": 4.493208192966529, "HONDA ODYSSEY 2018": 1.8838175399087222, "LEXUS RX 2016": 1.3912132245094184, "TOYOTA COROLLA 2017": 3.0143547548384735, "LEXUS ES 2019": 2.012201253045193, "HYUNDAI SANTA FE 2019": 3.039728566484244, "TOYOTA AVALON 2022": 2.4619858654670885, "JEEP GRAND CHEROKEE V6 2018": 1.8411674990629987, "CHEVROLET VOLT PREMIER 2017": 1.5943438675127841, "TOYOTA RAV4 HYBRID 2017": 1.9803053616868995, "LEXUS RX 2020": 1.664616846377383, "TOYOTA HIGHLANDER HYBRID 2018": 1.8866764457400844, "TOYOTA CAMRY HYBRID 2018": 2.014213351947917, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 1.4428896585442685, "TOYOTA MIRAI 2021": 2.7217623852898853, "LEXUS IS 2018": 3.5624668608596837, "TOYOTA HIGHLANDER 2017": 1.9199133105823853, "HYUNDAI SONATA HYBRID 2021": 2.7313907441569554, "VOLKSWAGEN ATLAS 1ST GEN": 1.4483948408160645, "LEXUS ES HYBRID 2019": 2.4138026617523547, "HYUNDAI GENESIS 2015-2016": 1.7636839808044658, "JEEP GRAND CHEROKEE 2019": 1.787264083939164, "SUBARU ASCENT LIMITED 2019": 3.0494069339774565, "HONDA CR-V 2017": 1.9828470679233807, "HONDA FIT 2018": 1.594940026552055, "TOYOTA CAMRY 2021": 2.5057990840460342, "AUDI Q3 2ND GEN": 1.4558300885316715, "AUDI A3 3RD GEN": 1.5304173783542625, "LEXUS RX HYBRID 2017": 1.577216425446677, "HONDA CIVIC 2022": 2.69252285552613, "GENESIS G70 2018": 3.866842361627636, "CHRYSLER PACIFICA HYBRID 2018": 1.5771851419640903, "VOLKSWAGEN PASSAT 8TH GEN": 1.2985597059739313, "HONDA CR-V 2016": 0.7745984062630755, "HYUNDAI IONIQ PHEV 2020": 2.5696218908589383, "GMC ACADIA DENALI 2018": 1.3310088601868082, "HYUNDAI SONATA 2019": 1.9736552675022665, "TOYOTA AVALON 2019": 1.7245149905226294, "TOYOTA C-HR 2018": 1.5895016960662856, "HONDA CR-V HYBRID 2019": 2.0687746810729193, "CHRYSLER PACIFICA 2020": 1.40536880000744, "HYUNDAI IONIQ ELECTRIC 2020": 3.3220838625838667, "VOLKSWAGEN TIGUAN 2ND GEN": NaN, "LEXUS NX 2018": 1.7753192756242595, "KIA OPTIMA SX 2019 & 2016": 3.12625562280304, "TOYOTA AVALON HYBRID 2019": 1.7681286449373381, "TOYOTA RAV4 HYBRID 2022": 2.5518187542231816, "HONDA PASSPORT 2021": 1.5174924139130355, "KIA K5 2021": 2.482916204106975, "ACURA ILX 2016": 1.5237423964720282, "HYUNDAI IONIQ HYBRID 2017-2019": 2.3723887901632645, "KIA NIRO EV 2020": 2.924651969180446, "SUBARU IMPREZA SPORT 2020": 2.5317689549587694, "CHRYSLER PACIFICA HYBRID 2017": 1.167126725149114, "HYUNDAI KONA ELECTRIC 2019": 4.201092987427836, "HYUNDAI ELANTRA HYBRID 2021": 3.7153193626001926, "HYUNDAI SANTA FE HYBRID 2022": 3.3049230586030545, "CHRYSLER PACIFICA 2018": 1.524867383058782, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": 2.5970979517766213, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 1.5460982690267173, "MAZDA CX-9 2021": 1.9514800984278198, "HYUNDAI SANTA FE 2022": 3.5354982200434524, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 1.8902492836532216, "HONDA HRV 2019": 2.1262957371020352, "TOYOTA AVALON HYBRID 2022": 2.4142150048378683, "SUBARU IMPREZA LIMITED 2019": 1.2203463907025918, "GENESIS G80 2017": 2.4086794443413906, "VOLKSWAGEN TAOS 1ST GEN": 2.0031666974545947, "KIA FORTE E 2018 & GT 2021": 2.022553820222557, "CADILLAC ESCALADE ESV 2016": 1.5522339636408988, "TOYOTA C-HR 2021": 1.6519334844316687, "TOYOTA C-HR HYBRID 2018": 1.3193315010905482}, "MAX_LAT_ACCEL_MEASURED": {"HONDA PILOT 2017": 0.9069354290994807, "HONDA CIVIC 2016": 0.4030275472529351, "TOYOTA CAMRY 2018": 1.686123168195758, "TOYOTA COROLLA HYBRID TSS2 2019": 1.9139332621491167, "TOYOTA RAV4 2019": 2.234047196286479, "HYUNDAI PALISADE 2020": 1.8303582523301922, "TOYOTA SIENNA 2018": 1.4752503435300715, "ACURA RDX 2020": 0.40911581320000334, "TOYOTA RAV4 2017": 1.6622227720995595, "HONDA RIDGELINE 2017": 0.8224685813281227, "TOYOTA PRIUS 2017": 1.4548827870876067, "TOYOTA HIGHLANDER HYBRID 2020": 2.0649784271823037, "HYUNDAI SONATA 2020": 2.243989856570093, "KIA STINGER GT2 2018": 1.9531287107084392, "TOYOTA HIGHLANDER 2020": 1.659381392090836, "HONDA ACCORD 2018": 0.40486739531686267, "TOYOTA PRIUS TSS2 2021": 1.861541601048098, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 1.1930739374812243, "LEXUS NX 2020": 1.565268724838564, "TOYOTA RAV4 HYBRID 2019": 2.0915384047218426, "HONDA CIVIC (BOSCH) 2019": 0.4062886118517984, "KIA NIRO HYBRID 2021": NaN, "HONDA ACCORD HYBRID 2018": 0.35128914564548286, "LEXUS NX HYBRID 2018": 1.81821359787186, "TOYOTA COROLLA TSS2 2019": 1.911280958056631, "VOLKSWAGEN ARTEON 1ST GEN": 1.2587939472578302, "TOYOTA CAMRY HYBRID 2021": 2.312510643730013, "VOLKSWAGEN JETTA 7TH GEN": 1.232161945396623, "HONDA INSIGHT 2019": 0.5174836462945298, "SUBARU FORESTER 2019": 2.29255993930968, "HYUNDAI ELANTRA 2021": NaN, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 2.133978602602408, "HYUNDAI KONA HYBRID 2020": NaN, "HONDA ODYSSEY 2018": 0.8254773781363679, "LEXUS RX 2016": 1.0954776820595344, "TOYOTA COROLLA 2017": 2.2012870528168964, "LEXUS ES 2019": 2.069508805495439, "HYUNDAI SANTA FE 2019": 2.3763720477660253, "TOYOTA AVALON 2022": 2.531962323786023, "JEEP GRAND CHEROKEE V6 2018": 1.4193323242487865, "CHEVROLET VOLT PREMIER 2017": 1.8576430337666092, "TOYOTA RAV4 HYBRID 2017": 1.7425797219020926, "LEXUS RX 2020": 1.5118835180227874, "TOYOTA HIGHLANDER HYBRID 2018": 1.6872527654528833, "TOYOTA CAMRY HYBRID 2018": 1.6793468378089895, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 1.5614447712441282, "TOYOTA MIRAI 2021": 2.271146483563897, "LEXUS IS 2018": NaN, "TOYOTA HIGHLANDER 2017": 1.6573774863189379, "HYUNDAI SONATA HYBRID 2021": 1.9464120717803253, "VOLKSWAGEN ATLAS 1ST GEN": 1.6867005451451638, "LEXUS ES HYBRID 2019": 1.956450687999482, "HYUNDAI GENESIS 2015-2016": 1.5359761378898085, "JEEP GRAND CHEROKEE 2019": 1.2418961305308847, "SUBARU ASCENT LIMITED 2019": NaN, "HONDA CR-V 2017": 0.2642062271814174, "HONDA FIT 2018": 0.5896345937094754, "TOYOTA CAMRY 2021": 2.1783533980215166, "AUDI Q3 2ND GEN": 1.1582239457022647, "AUDI A3 3RD GEN": 1.598699116126939, "LEXUS RX HYBRID 2017": 1.319771127672888, "HONDA CIVIC 2022": 1.1806949852580793, "GENESIS G70 2018": 2.2496820850331134, "CHRYSLER PACIFICA HYBRID 2018": 1.294798200968084, "VOLKSWAGEN PASSAT 8TH GEN": 1.247540921731637, "HONDA CR-V 2016": 0.6991119250342539, "HYUNDAI IONIQ PHEV 2020": 1.9062392690595655, "GMC ACADIA DENALI 2018": 1.2986994230652662, "HYUNDAI SONATA 2019": 1.257445187146704, "TOYOTA AVALON 2019": 1.664577368475227, "TOYOTA C-HR 2018": 1.308490445144888, "HONDA CR-V HYBRID 2019": 0.4693072746041504, "CHRYSLER PACIFICA 2020": 1.1712413003138664, "HYUNDAI IONIQ ELECTRIC 2020": NaN, "VOLKSWAGEN TIGUAN 2ND GEN": 1.1573057001955744, "LEXUS NX 2018": 1.9457312007432144, "KIA OPTIMA SX 2019 & 2016": 2.0928228595938845, "TOYOTA AVALON HYBRID 2019": NaN, "TOYOTA RAV4 HYBRID 2022": 1.7647290773049569, "HONDA PASSPORT 2021": 0.8248357750132685, "KIA K5 2021": 1.4628018983720577, "ACURA ILX 2016": 0.6330753921140401, "HYUNDAI IONIQ HYBRID 2017-2019": NaN, "KIA NIRO EV 2020": 2.020186575503497, "SUBARU IMPREZA SPORT 2020": 2.136786720514988, "CHRYSLER PACIFICA HYBRID 2017": 1.0642918033307907, "HYUNDAI KONA ELECTRIC 2019": NaN, "HYUNDAI ELANTRA HYBRID 2021": NaN, "HYUNDAI SANTA FE HYBRID 2022": NaN, "CHRYSLER PACIFICA 2018": 1.3654603720349934, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": NaN, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 1.255230465866663, "MAZDA CX-9 2021": NaN, "HYUNDAI SANTA FE 2022": 3.3823387508235827, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 1.544104124172169, "HONDA HRV 2019": 0.7492792210307291, "TOYOTA AVALON HYBRID 2022": NaN, "SUBARU IMPREZA LIMITED 2019": 1.2203463907025918, "GENESIS G80 2017": NaN, "VOLKSWAGEN TAOS 1ST GEN": 1.6590543949912684, "KIA FORTE E 2018 & GT 2021": 2.3970573789339786, "CADILLAC ESCALADE ESV 2016": NaN, "TOYOTA C-HR 2021": 1.3559230155096402, "TOYOTA C-HR HYBRID 2018": 1.271271459066948}, "FRICTION": {"HONDA PILOT 2017": 0.2168217463499328, "HONDA CIVIC 2016": 0.28406761310944795, "TOYOTA CAMRY 2018": 0.1327947477896041, "TOYOTA COROLLA HYBRID TSS2 2019": 0.21792021497538405, "TOYOTA RAV4 2019": 0.12757022360707945, "HYUNDAI PALISADE 2020": 0.13391574986922777, "TOYOTA SIENNA 2018": 0.1853443239485906, "ACURA RDX 2020": 0.18058553315570297, "TOYOTA RAV4 2017": 0.14319170324556796, "HONDA RIDGELINE 2017": 0.2380553573913589, "TOYOTA PRIUS 2017": 0.2079869382946584, "TOYOTA HIGHLANDER HYBRID 2020": 0.14038812589302646, "HYUNDAI SONATA 2020": 0.08266051305053168, "KIA STINGER GT2 2018": 0.11909534626930472, "TOYOTA HIGHLANDER 2020": 0.14658637853444048, "HONDA ACCORD 2018": 0.21616610462729247, "TOYOTA PRIUS TSS2 2021": 0.20613763260512002, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 0.16250373743651828, "LEXUS NX 2020": 0.14404022591302845, "TOYOTA RAV4 HYBRID 2019": 0.1319247989758836, "HONDA CIVIC (BOSCH) 2019": 0.2575217845562353, "KIA NIRO HYBRID 2021": 0.14468633728800306, "HONDA ACCORD HYBRID 2018": 0.21150723931119184, "LEXUS NX HYBRID 2018": 0.16117151597250162, "TOYOTA COROLLA TSS2 2019": 0.21045927995242877, "VOLKSWAGEN ARTEON 1ST GEN": 0.17828895368353925, "TOYOTA CAMRY HYBRID 2021": 0.16283734136957057, "VOLKSWAGEN JETTA 7TH GEN": 0.19508489725001105, "HONDA INSIGHT 2019": 0.25750800088299297, "SUBARU FORESTER 2019": 0.11783702069698135, "HYUNDAI ELANTRA 2021": 0.09377564130711125, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 0.14740189509875762, "HYUNDAI KONA HYBRID 2020": 0.0863709736632968, "HONDA ODYSSEY 2018": 0.2125595696498247, "LEXUS RX 2016": 0.21475140622981923, "TOYOTA COROLLA 2017": 0.12325064090161544, "LEXUS ES 2019": 0.12757526660498053, "HYUNDAI SANTA FE 2019": 0.12230125806479573, "TOYOTA AVALON 2022": 0.11030226705639488, "JEEP GRAND CHEROKEE V6 2018": 0.12871972792344108, "CHEVROLET VOLT PREMIER 2017": 0.16697256960295873, "TOYOTA RAV4 HYBRID 2017": 0.14074453855329072, "LEXUS RX 2020": 0.2249895411716623, "TOYOTA HIGHLANDER HYBRID 2018": 0.16692807938039034, "TOYOTA CAMRY HYBRID 2018": 0.13418904852016877, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 0.19324413131475543, "TOYOTA MIRAI 2021": 0.20035237756713503, "LEXUS IS 2018": 0.073103111226694, "TOYOTA HIGHLANDER 2017": 0.17502689439420385, "HYUNDAI SONATA HYBRID 2021": 0.09518615688045734, "VOLKSWAGEN ATLAS 1ST GEN": 0.12761803335799474, "LEXUS ES HYBRID 2019": 0.1682771025433274, "HYUNDAI GENESIS 2015-2016": 0.10254237048034251, "JEEP GRAND CHEROKEE 2019": 0.15702739382013717, "SUBARU ASCENT LIMITED 2019": 0.12936982863095342, "HONDA CR-V 2017": 0.22518506713451308, "HONDA FIT 2018": 0.10803295063463647, "TOYOTA CAMRY 2021": 0.15512845523424743, "AUDI Q3 2ND GEN": 0.14083949977629878, "AUDI A3 3RD GEN": 0.1611945965384188, "LEXUS RX HYBRID 2017": 0.19322020114452776, "HONDA CIVIC 2022": 0.24279247053469405, "GENESIS G70 2018": 0.06869638264150804, "CHRYSLER PACIFICA HYBRID 2018": 0.13887505891474383, "VOLKSWAGEN PASSAT 8TH GEN": 0.21714039653367842, "HONDA CR-V 2016": 0.41726236462791455, "HYUNDAI IONIQ PHEV 2020": 0.13800461817330806, "GMC ACADIA DENALI 2018": 0.3447163106452739, "HYUNDAI SONATA 2019": 0.15371520337813344, "TOYOTA AVALON 2019": 0.10392921606262978, "TOYOTA C-HR 2018": 0.2015190716953846, "HONDA CR-V HYBRID 2019": 0.19595630321202379, "CHRYSLER PACIFICA 2020": 0.14337114313208268, "HYUNDAI IONIQ ELECTRIC 2020": 0.08104502306679212, "VOLKSWAGEN TIGUAN 2ND GEN": NaN, "LEXUS NX 2018": 0.1471001686544422, "KIA OPTIMA SX 2019 & 2016": 0.11703652166984638, "TOYOTA AVALON HYBRID 2019": 0.10863628402866225, "TOYOTA RAV4 HYBRID 2022": 0.14334213238415072, "HONDA PASSPORT 2021": 0.19826160782809032, "KIA K5 2021": 0.1027179720106188, "ACURA ILX 2016": 0.35663988815912573, "HYUNDAI IONIQ HYBRID 2017-2019": 0.12332151728479951, "KIA NIRO EV 2020": 0.0892074288578785, "SUBARU IMPREZA SPORT 2020": 0.15841234487251604, "CHRYSLER PACIFICA HYBRID 2017": 0.1345638758810282, "HYUNDAI KONA ELECTRIC 2019": 0.08503096350356723, "HYUNDAI ELANTRA HYBRID 2021": 0.09887804390243872, "HYUNDAI SANTA FE HYBRID 2022": 0.11171499761140577, "CHRYSLER PACIFICA 2018": 0.13611561752951415, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": 0.10502695501512567, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 0.21818156330777305, "MAZDA CX-9 2021": 0.1793735649504697, "HYUNDAI SANTA FE 2022": 0.09184808719698756, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 0.14050744688135813, "HONDA HRV 2019": 0.17840321248608593, "TOYOTA AVALON HYBRID 2022": 0.16159049452515487, "SUBARU IMPREZA LIMITED 2019": 0.20322553080306893, "GENESIS G80 2017": 0.07934444681782107, "VOLKSWAGEN TAOS 1ST GEN": 0.18276122764341485, "KIA FORTE E 2018 & GT 2021": 0.11406160665068436, "CADILLAC ESCALADE ESV 2016": 0.15063766975884627, "TOYOTA C-HR 2021": 0.22798633346500694, "TOYOTA C-HR HYBRID 2018": 0.2036375866375624}, "ERROR_RATIO": {"HONDA PILOT 2017": 0.6158457247286419, "HONDA CIVIC 2016": 2.0785618623350928, "TOYOTA CAMRY 2018": 0.17356565057429169, "TOYOTA COROLLA HYBRID TSS2 2019": 0.10094741777075293, "TOYOTA RAV4 2019": 0.11812042718338775, "HYUNDAI PALISADE 2020": 0.30639442561268304, "TOYOTA SIENNA 2018": 0.1117307389748361, "ACURA RDX 2020": 1.9801454495960717, "TOYOTA RAV4 2017": 0.08589486116378196, "HONDA RIDGELINE 2017": 0.4319851914417577, "TOYOTA PRIUS 2017": 0.17281316158588575, "TOYOTA HIGHLANDER HYBRID 2020": 0.046325388721577, "HYUNDAI SONATA 2020": 0.4109860794021653, "KIA STINGER GT2 2018": 0.3517628781488943, "TOYOTA HIGHLANDER 2020": 0.14155072865224166, "HONDA ACCORD 2018": 2.510398061115294, "TOYOTA PRIUS TSS2 2021": 0.13593456264106363, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 0.08794943266738546, "LEXUS NX 2020": 0.3743942573190866, "TOYOTA RAV4 HYBRID 2019": 0.0845492503791727, "HONDA CIVIC (BOSCH) 2019": 2.4329816697390063, "KIA NIRO HYBRID 2021": NaN, "HONDA ACCORD HYBRID 2018": 2.9252406767451804, "LEXUS NX HYBRID 2018": 0.23060712246809048, "TOYOTA COROLLA TSS2 2019": 0.13822363784977285, "VOLKSWAGEN ARTEON 1ST GEN": 0.009661691674299285, "TOYOTA CAMRY HYBRID 2021": 0.029451711159377333, "VOLKSWAGEN JETTA 7TH GEN": 0.16591473170144055, "HONDA INSIGHT 2019": 1.3398692842898896, "SUBARU FORESTER 2019": 0.5269683780697442, "HYUNDAI ELANTRA 2021": NaN, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 0.02971857401969039, "HYUNDAI KONA HYBRID 2020": NaN, "HONDA ODYSSEY 2018": 1.0245957242729038, "LEXUS RX 2016": 0.07392586589971588, "TOYOTA COROLLA 2017": 0.31336988069649124, "LEXUS ES 2019": 0.08933657038050916, "HYUNDAI SANTA FE 2019": 0.2276812089092099, "TOYOTA AVALON 2022": 0.07120118798045925, "JEEP GRAND CHEROKEE V6 2018": 0.2065164316228118, "CHEVROLET VOLT PREMIER 2017": 0.2316223989408518, "TOYOTA RAV4 HYBRID 2017": 0.055653752888652736, "LEXUS RX 2020": 0.047792182371008345, "TOYOTA HIGHLANDER HYBRID 2018": 0.019259474082467202, "TOYOTA CAMRY HYBRID 2018": 0.11949733140330816, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 0.1996863736436734, "TOYOTA MIRAI 2021": 0.11019259478417197, "LEXUS IS 2018": NaN, "TOYOTA HIGHLANDER 2017": 0.05279963713251727, "HYUNDAI SONATA HYBRID 2021": 0.3543918194389536, "VOLKSWAGEN ATLAS 1ST GEN": 0.21694647502209782, "LEXUS ES HYBRID 2019": 0.14775474433507507, "HYUNDAI GENESIS 2015-2016": 0.0814892037361157, "JEEP GRAND CHEROKEE 2019": 0.3126997097753535, "SUBARU ASCENT LIMITED 2019": NaN, "HONDA CR-V 2017": 5.652613829506629, "HONDA FIT 2018": 1.5217432826711779, "TOYOTA CAMRY 2021": 0.07910435053686729, "AUDI Q3 2ND GEN": 0.13535089102138698, "AUDI A3 3RD GEN": 0.14353941401245793, "LEXUS RX HYBRID 2017": 0.048663813961824696, "HONDA CIVIC 2022": 1.0748206908458815, "GENESIS G70 2018": 0.688303429295532, "CHRYSLER PACIFICA HYBRID 2018": 0.11083725786301112, "VOLKSWAGEN PASSAT 8TH GEN": 0.13315924904555493, "HONDA CR-V 2016": 0.488871482749128, "HYUNDAI IONIQ PHEV 2020": 0.2756096845519595, "GMC ACADIA DENALI 2018": 0.24055364003040136, "HYUNDAI SONATA 2019": 0.4473315280277132, "TOYOTA AVALON 2019": 0.026428086100632363, "TOYOTA C-HR 2018": 0.06075105822970755, "HONDA CR-V HYBRID 2019": 2.9906016360828276, "CHRYSLER PACIFICA 2020": 0.07748732608487266, "HYUNDAI IONIQ ELECTRIC 2020": NaN, "VOLKSWAGEN TIGUAN 2ND GEN": NaN, "LEXUS NX 2018": 0.16318394527060903, "KIA OPTIMA SX 2019 & 2016": 0.4378756841929454, "TOYOTA AVALON HYBRID 2019": NaN, "TOYOTA RAV4 HYBRID 2022": 0.36478548056633514, "HONDA PASSPORT 2021": 0.5993860184637646, "KIA K5 2021": 0.6271500841947655, "ACURA ILX 2016": 0.8435442647921855, "HYUNDAI IONIQ HYBRID 2017-2019": NaN, "KIA NIRO EV 2020": 0.40355577782011604, "SUBARU IMPREZA SPORT 2020": 0.11071291640854522, "CHRYSLER PACIFICA HYBRID 2017": 0.029812269495458284, "HYUNDAI KONA ELECTRIC 2019": NaN, "HYUNDAI ELANTRA HYBRID 2021": NaN, "HYUNDAI SANTA FE HYBRID 2022": NaN, "CHRYSLER PACIFICA 2018": 0.01705753895996445, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": NaN, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 0.05790668871480552, "MAZDA CX-9 2021": NaN, "HYUNDAI SANTA FE 2022": 0.018126919430513307, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 0.1331760659016062, "HONDA HRV 2019": 1.599688433820939, "TOYOTA AVALON HYBRID 2022": NaN, "SUBARU IMPREZA LIMITED 2019": 0.2514545160390271, "GENESIS G80 2017": NaN, "VOLKSWAGEN TAOS 1ST GEN": 0.09725484306423876, "KIA FORTE E 2018 & GT 2021": 0.20381871942480628, "CADILLAC ESCALADE ESV 2016": NaN, "TOYOTA C-HR 2021": 0.05016813984196128, "TOYOTA C-HR HYBRID 2018": 0.2521485862766935}} \ No newline at end of file diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index b1c6da922b..32f66b6fa0 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -99,6 +99,7 @@ class Footnote(Enum): class ToyotaCarInfo(CarInfo): package: str = "All" harness: Enum = Harness.toyota + good_torque: bool = True CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index b2623dc8dc..05d016911b 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -4efb28766e386de3117819b8a128aa782aaadf2a \ No newline at end of file +2d736ca51acc1ac06216631b0529b50d9a6d2170 \ No newline at end of file From 88f246b909e3e111ac84e964bb811efefd923163 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 22 Jun 2022 11:45:38 +0200 Subject: [PATCH 116/302] ui: change alerts to Inter (#24937) * ui: change alerts to Inter * fix up test --- selfdrive/controls/tests/test_alerts.py | 17 +++++++---------- selfdrive/ui/qt/onroad.cc | 10 +++++----- 2 files changed, 12 insertions(+), 15 deletions(-) diff --git a/selfdrive/controls/tests/test_alerts.py b/selfdrive/controls/tests/test_alerts.py index 2bd904b575..79c56d6bc0 100755 --- a/selfdrive/controls/tests/test_alerts.py +++ b/selfdrive/controls/tests/test_alerts.py @@ -48,20 +48,17 @@ class TestAlerts(unittest.TestCase): # ensure alert text doesn't exceed allowed width def test_alert_text_length(self): font_path = os.path.join(BASEDIR, "selfdrive/assets/fonts") - regular_font_path = os.path.join(font_path, "opensans_semibold.ttf") - bold_font_path = os.path.join(font_path, "opensans_semibold.ttf") - semibold_font_path = os.path.join(font_path, "opensans_semibold.ttf") - - max_text_width = 1920 - 300 # full screen width is useable, minus sidebar - # TODO: get exact scale factor. found this empirically, works well enough - font_scale_factor = 1.55 # factor to scale from nanovg units to PIL + regular_font_path = os.path.join(font_path, "Inter-SemiBold.ttf") + bold_font_path = os.path.join(font_path, "Inter-Bold.ttf") + semibold_font_path = os.path.join(font_path, "Inter-SemiBold.ttf") + max_text_width = 2160 - 300 # full screen width is useable, minus sidebar draw = ImageDraw.Draw(Image.new('RGB', (0, 0))) fonts = { - AlertSize.small: [ImageFont.truetype(semibold_font_path, int(40 * font_scale_factor))], - AlertSize.mid: [ImageFont.truetype(bold_font_path, int(48 * font_scale_factor)), - ImageFont.truetype(regular_font_path, int(36 * font_scale_factor))], + AlertSize.small: [ImageFont.truetype(semibold_font_path, 74)], + AlertSize.mid: [ImageFont.truetype(bold_font_path, 88), + ImageFont.truetype(regular_font_path, 66)], } for alert in ALERTS: diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index d92cf36b89..98b70c6b6e 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -146,18 +146,18 @@ void OnroadAlerts::paintEvent(QPaintEvent *event) { p.setPen(QColor(0xff, 0xff, 0xff)); p.setRenderHint(QPainter::TextAntialiasing); if (alert.size == cereal::ControlsState::AlertSize::SMALL) { - configFont(p, "Open Sans", 74, "SemiBold"); + configFont(p, "Inter", 74, "SemiBold"); p.drawText(r, Qt::AlignCenter, alert.text1); } else if (alert.size == cereal::ControlsState::AlertSize::MID) { - configFont(p, "Open Sans", 88, "Bold"); + configFont(p, "Inter", 88, "Bold"); p.drawText(QRect(0, c.y() - 125, width(), 150), Qt::AlignHCenter | Qt::AlignTop, alert.text1); - configFont(p, "Open Sans", 66, "Regular"); + configFont(p, "Inter", 66, "Regular"); p.drawText(QRect(0, c.y() + 21, width(), 90), Qt::AlignHCenter, alert.text2); } else if (alert.size == cereal::ControlsState::AlertSize::FULL) { bool l = alert.text1.length() > 15; - configFont(p, "Open Sans", l ? 132 : 177, "Bold"); + configFont(p, "Inter", l ? 132 : 177, "Bold"); p.drawText(QRect(0, r.y() + (l ? 240 : 270), width(), 600), Qt::AlignHCenter | Qt::TextWordWrap, alert.text1); - configFont(p, "Open Sans", 88, "Regular"); + configFont(p, "Inter", 88, "Regular"); p.drawText(QRect(0, r.height() - (l ? 361 : 420), width(), 300), Qt::AlignHCenter | Qt::TextWordWrap, alert.text2); } } From 963de402115a4eb8eb7944c5f5233e47dea31543 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 22 Jun 2022 11:46:00 +0200 Subject: [PATCH 117/302] ui: change sidebar font to Inter (#24931) * change sidebar to inter * clean up metric color rect radius * fix text placement * simplify rect placement --- selfdrive/ui/qt/sidebar.cc | 39 ++++++++++++++++++++++---------------- selfdrive/ui/qt/sidebar.h | 4 ++-- 2 files changed, 25 insertions(+), 18 deletions(-) diff --git a/selfdrive/ui/qt/sidebar.cc b/selfdrive/ui/qt/sidebar.cc index 312d8d8a59..00e72b352c 100644 --- a/selfdrive/ui/qt/sidebar.cc +++ b/selfdrive/ui/qt/sidebar.cc @@ -4,13 +4,13 @@ #include "selfdrive/ui/qt/util.h" -void Sidebar::drawMetric(QPainter &p, const QString &label, QColor c, int y) { - const QRect rect = {30, y, 240, label.contains("\n") ? 124 : 100}; +void Sidebar::drawMetric(QPainter &p, const QPair &label, QColor c, int y) { + const QRect rect = {30, y, 240, 126}; p.setPen(Qt::NoPen); p.setBrush(QBrush(c)); - p.setClipRect(rect.x() + 6, rect.y(), 18, rect.height(), Qt::ClipOperation::ReplaceClip); - p.drawRoundedRect(QRect(rect.x() + 6, rect.y() + 6, 100, rect.height() - 12), 10, 10); + p.setClipRect(rect.x() + 4, rect.y(), 18, rect.height(), Qt::ClipOperation::ReplaceClip); + p.drawRoundedRect(QRect(rect.x() + 4, rect.y() + 4, 100, 118), 18, 18); p.setClipping(false); QPen pen = QPen(QColor(0xff, 0xff, 0xff, 0x55)); @@ -20,9 +20,16 @@ void Sidebar::drawMetric(QPainter &p, const QString &label, QColor c, int y) { p.drawRoundedRect(rect, 20, 20); p.setPen(QColor(0xff, 0xff, 0xff)); - configFont(p, "Open Sans", 35, "Bold"); - const QRect r = QRect(rect.x() + 30, rect.y(), rect.width() - 40, rect.height()); - p.drawText(r, Qt::AlignCenter, label); + configFont(p, "Inter", 35, "SemiBold"); + + QRect label_rect = getTextRect(p, Qt::AlignCenter, label.first); + label_rect.setWidth(218); + label_rect.moveLeft(rect.left() + 22); + label_rect.moveTop(rect.top() + 19); + p.drawText(label_rect, Qt::AlignCenter, label.first); + + label_rect.moveTop(rect.top() + 65); + p.drawText(label_rect, Qt::AlignCenter, label.second); } Sidebar::Sidebar(QWidget *parent) : QFrame(parent) { @@ -57,26 +64,26 @@ void Sidebar::updateState(const UIState &s) { ItemStatus connectStatus; auto last_ping = deviceState.getLastAthenaPingTime(); if (last_ping == 0) { - connectStatus = ItemStatus{"CONNECT\nOFFLINE", warning_color}; + connectStatus = ItemStatus{{"CONNECT", "OFFLINE"}, warning_color}; } else { - connectStatus = nanos_since_boot() - last_ping < 80e9 ? ItemStatus{"CONNECT\nONLINE", good_color} : ItemStatus{"CONNECT\nERROR", danger_color}; + connectStatus = nanos_since_boot() - last_ping < 80e9 ? ItemStatus{{"CONNECT", "ONLINE"}, good_color} : ItemStatus{{"CONNECT", "ERROR"}, danger_color}; } setProperty("connectStatus", QVariant::fromValue(connectStatus)); - ItemStatus tempStatus = {"TEMP\nHIGH", danger_color}; + ItemStatus tempStatus = {{"TEMP", "HIGH"}, danger_color}; auto ts = deviceState.getThermalStatus(); if (ts == cereal::DeviceState::ThermalStatus::GREEN) { - tempStatus = {"TEMP\nGOOD", good_color}; + tempStatus = {{"TEMP", "GOOD"}, good_color}; } else if (ts == cereal::DeviceState::ThermalStatus::YELLOW) { - tempStatus = {"TEMP\nOK", warning_color}; + tempStatus = {{"TEMP", "OK"}, warning_color}; } setProperty("tempStatus", QVariant::fromValue(tempStatus)); - ItemStatus pandaStatus = {"VEHICLE\nONLINE", good_color}; + ItemStatus pandaStatus = {{"VEHICLE", "ONLINE"}, good_color}; if (s.scene.pandaType == cereal::PandaState::PandaType::UNKNOWN) { - pandaStatus = {"NO\nPANDA", danger_color}; + pandaStatus = {{"NO", "PANDA"}, danger_color}; } else if (s.scene.started && !sm["liveLocationKalman"].getLiveLocationKalman().getGpsOK()) { - pandaStatus = {"GPS\nSEARCH", warning_color}; + pandaStatus = {{"GPS", "SEARCH"}, warning_color}; } setProperty("pandaStatus", QVariant::fromValue(pandaStatus)); } @@ -103,7 +110,7 @@ void Sidebar::paintEvent(QPaintEvent *event) { x += 37; } - configFont(p, "Open Sans", 35, "Regular"); + configFont(p, "Inter", 35, "Regular"); p.setPen(QColor(0xff, 0xff, 0xff)); const QRect r = QRect(50, 247, 100, 50); p.drawText(r, Qt::AlignCenter, net_type); diff --git a/selfdrive/ui/qt/sidebar.h b/selfdrive/ui/qt/sidebar.h index ab3e990e61..98ae6564d6 100644 --- a/selfdrive/ui/qt/sidebar.h +++ b/selfdrive/ui/qt/sidebar.h @@ -6,7 +6,7 @@ #include "common/params.h" #include "selfdrive/ui/ui.h" -typedef QPair ItemStatus; +typedef QPair, QColor> ItemStatus; Q_DECLARE_METATYPE(ItemStatus); class Sidebar : public QFrame { @@ -30,7 +30,7 @@ public slots: protected: void paintEvent(QPaintEvent *event) override; void mouseReleaseEvent(QMouseEvent *event) override; - void drawMetric(QPainter &p, const QString &label, QColor c, int y); + void drawMetric(QPainter &p, const QPair &label, QColor c, int y); QPixmap home_img, settings_img; const QMap network_type = { From 05e7ce731f4259a569f5d28392a0d576e90dec1b Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 22 Jun 2022 11:46:16 +0200 Subject: [PATCH 118/302] ui: change set speed, speed limit and current speed to Inter (#24932) * ui: change set speed/speed limit to Inter * switch current speed to Inter --- selfdrive/ui/qt/onroad.cc | 28 +++++++++++++--------------- 1 file changed, 13 insertions(+), 15 deletions(-) diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 98b70c6b6e..2759416236 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -259,10 +259,10 @@ void NvgWindow::drawHud(QPainter &p) { } else { p.setPen(QColor(0xa6, 0xa6, 0xa6, 0xff)); } - configFont(p, "Open Sans", 40, "SemiBold"); + configFont(p, "Inter", 40, "SemiBold"); QRect max_rect = getTextRect(p, Qt::AlignCenter, "MAX"); max_rect.moveCenter({set_speed_rect.center().x(), 0}); - max_rect.moveTop(set_speed_rect.top() + 23); + max_rect.moveTop(set_speed_rect.top() + 27); p.drawText(max_rect, Qt::AlignCenter, "MAX"); // Draw set speed @@ -279,10 +279,10 @@ void NvgWindow::drawHud(QPainter &p) { } else { p.setPen(QColor(0x72, 0x72, 0x72, 0xff)); } - configFont(p, "Open Sans", 90, "Bold"); + configFont(p, "Inter", 90, "Bold"); QRect speed_rect = getTextRect(p, Qt::AlignCenter, setSpeedStr); speed_rect.moveCenter({set_speed_rect.center().x(), 0}); - speed_rect.moveTop(set_speed_rect.top() + 67); + speed_rect.moveTop(set_speed_rect.top() + 77); p.drawText(speed_rect, Qt::AlignCenter, setSpeedStr); @@ -306,23 +306,23 @@ void NvgWindow::drawHud(QPainter &p) { p.drawRoundedRect(sign_rect, 16, 16); // "SPEED" - configFont(p, "Open Sans", 28, "SemiBold"); + configFont(p, "Inter", 28, "SemiBold"); QRect text_speed_rect = getTextRect(p, Qt::AlignCenter, "SPEED"); text_speed_rect.moveCenter({sign_rect.center().x(), 0}); - text_speed_rect.moveTop(sign_rect_outer.top() + 20); + text_speed_rect.moveTop(sign_rect_outer.top() + 22); p.drawText(text_speed_rect, Qt::AlignCenter, "SPEED"); // "LIMIT" QRect text_limit_rect = getTextRect(p, Qt::AlignCenter, "LIMIT"); text_limit_rect.moveCenter({sign_rect.center().x(), 0}); - text_limit_rect.moveTop(sign_rect_outer.top() + 48); + text_limit_rect.moveTop(sign_rect_outer.top() + 51); p.drawText(text_limit_rect, Qt::AlignCenter, "LIMIT"); // Speed limit value - configFont(p, "Open Sans", 70, "Bold"); + configFont(p, "Inter", 70, "Bold"); QRect speed_limit_rect = getTextRect(p, Qt::AlignCenter, speedLimitStr); speed_limit_rect.moveCenter({sign_rect.center().x(), 0}); - speed_limit_rect.moveTop(sign_rect.top() + 70); + speed_limit_rect.moveTop(sign_rect_outer.top() + 85); p.drawText(speed_limit_rect, Qt::AlignCenter, speedLimitStr); } @@ -343,10 +343,8 @@ void NvgWindow::drawHud(QPainter &p) { p.drawEllipse(center, inner_radius_2, inner_radius_2); // Speed limit value - if (speedLimit < 1 ) center -= {0, 2}; // Make sure dash is centered if no speed limit available - - int font_size = (speedLimitStr.size() >= 3) ? 62 : 70; - configFont(p, "Open Sans", font_size, "Bold"); + int font_size = (speedLimitStr.size() >= 3) ? 60 : 70; + configFont(p, "Inter", font_size, "Bold"); QRect speed_limit_rect = getTextRect(p, Qt::AlignCenter, speedLimitStr); speed_limit_rect.moveCenter(center); p.setPen(blackColor()); @@ -354,9 +352,9 @@ void NvgWindow::drawHud(QPainter &p) { } // current speed - configFont(p, "Open Sans", 176, "Bold"); + configFont(p, "Inter", 176, "Bold"); drawText(p, rect().center().x(), 210, speedStr); - configFont(p, "Open Sans", 66, "Regular"); + configFont(p, "Inter", 66, "Regular"); drawText(p, rect().center().x(), 290, speedUnit, 200); // engage-ability icon From 1908b89e29a968a3f1b8dd8cdd8213570e02c186 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 22 Jun 2022 20:41:24 +0200 Subject: [PATCH 119/302] remove Open Sans fonts from assets (#24946) --- selfdrive/assets/fonts/opensans_bold.ttf | Bin 224452 -> 0 bytes selfdrive/assets/fonts/opensans_regular.ttf | Bin 217276 -> 0 bytes selfdrive/assets/fonts/opensans_semibold.ttf | Bin 221164 -> 0 bytes selfdrive/ui/qt/window.cc | 3 --- 4 files changed, 3 deletions(-) delete mode 100644 selfdrive/assets/fonts/opensans_bold.ttf delete mode 100644 selfdrive/assets/fonts/opensans_regular.ttf delete mode 100644 selfdrive/assets/fonts/opensans_semibold.ttf diff --git a/selfdrive/assets/fonts/opensans_bold.ttf b/selfdrive/assets/fonts/opensans_bold.ttf deleted file mode 100644 index 7b529456032abf9132194ddaac62d2d163247c38..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 224452 zcmbTe2VhiH_6L0LYtu75lb)GO3L%7$gd~QRA%qZ;5Ym7Qgcu-HrHO!mktQ7sh$3C2 ziO6bT5s}3L2#AQR@^@J`vVdJda1jw9dHH_#%}fAy_y7OCZ<06nmHXa3_w;k_c|#~6 z#ELJ0bjqvf+vnMk$GZ@IP$?ny$NS{<&L{Ew>x8f9gkDj7O8ZynvW!_c#&z;gpNavw zK}p@;#PMQ6_!IprQqs1Le<_3zdJxxZM~ojf>9xQ7dY2H>eq3KXV%ph zkocrYkByx4fu{KpLLws2|2AQ`qoGavmvydq*x2n?qEX`nA*XU3TUh&9(np`&)wk@@ zu28Q)Uk%~dS$uGxdPU1FLbNOH>g5?)cJ+Y|zm1*YcaxqiD05<8*3?7X^+JE)nj!hd75|fOc$<)SeZ+h?6*5Tcl{& zMxIu$;HsR2zR0c#HR1s@PQnXk$PwiXFu}2{kWA%Ik_BQCNfuU-Dpdx_0jA427g@j^ zKzo367ph4PyT+B19Bwt~&K2OE5)y=Sh1h0bEAek`v~}1Dux0t%T-Kl6i{q-mhWSXU zWHL%zfSJ~kgJLL|E?y-Eg<06@aD19fm!io*K9b~eJ6p$yr8vKU98@hM2c@~#YS3Tu zw*|O1hSUgKNus1DuQ9x-4&%84F>@K)R+7r?Bn^OBk2YP%C2GE~wOMGQ#lmM~plBjn zgh*12wputus`*foh_NIwmu%rClhxeh)_UQVvcE;uM7FT=!cC?B7IqK6m2Bbfpq)Wd zaBaP?f)MF*ViUFyE!*e6BUyX`i5AAtlW5Bs4g$ExegigkZZbAW>GKsC2iP3aE>g#X zKZL9Pdw_d(P9Uv!`0;=h&*9Z11zT4(7qI}abtjV#bkmPT-h{s4Sp1+#O2(H&Faspmu{L177eFN=?`;Wmt>^#S92d_e& zl(GNVb|q5VHPD#hl+pG6R&|O@SDnNBAcIT}{Ot&TTOmL$nQZ*m7Bb7^hRN>zts=*u z-~Zc|$-5$ROx{7?fZQ|LWAcB03z^yi9z7o50mk!;?*emcgSCkq5|oXGqy38M0%0?) zq&p$kP2{YwpKQeOd0{g-Bra(EfXSVxZQUfj*1AauMcdeVLW*o%EETq%;B#9~DY6D# zC)5Mqd5}xSGk}fJo{i0D%IK%)FTb7xoaOAAcnjwtJHk8AwZIjdpL7{`hmKQmWV}=e z9Rs;kWGor@o=i#@O?hl$B54qD4m8;!EF+vEE4a=#;~cIFH=rk2%XsE0Q7iq95s6(_ zo~{eC`|^uY|i7rJB%L` zJwmb>&#Gi%QVYI5iXF%X|FgL=y%dhtk1r__ILEV~|B0AFYNR!|2b*%wEn-saf*+3o zTq!aPT#0yQ09R5D?m0)stGAGY>L0NG3Gm0xv9U@>fw}>0dFw4jH-T@(NZ{}sa9Bzr znH)>a;4OyRV>pKmb7lA?(h;=9%5k-rg?+zG5ypeJ!H?2>;0pFYoQrEYWR?p3RhO~< z8m^teeLr9eC50*h?K>EQ=?ta^Ftz|a!(@o@A7uO+Cg-Yfz#WeJ(TBmn#sDt12s^3*SHXdG$vN2mo50g-~ag`*89wMQ9gKrb!V7FalmXJYa@f;a0ohMVZ zInYV)518M;-GGmPO=y74(aO{L;batemiYnYDmP$RMRFzPKO~Ywbv9Wfg5Hc*0rM!> zqb}IGVjGOD7hvzo0lCgF5w@H{kVP0LJ<#xjt!ZBq&!wl>fV1GSMoWbV*pnoOX82%Zq z#3qcb2OVUR&iGI94gB^*YLp+tGpq2-8R{*VJ2q)OfR@q<^Z3Itm4#xIZLhfEd z`#IYbc>!N5^ap>b_d~zh;EN0geSrhjdhq=y(EU7)VJp;Hj0=8~CISb|#HPl*DlM)D z;dnBMRx#bc2JWoR~H^`%u1z2++AATFH=)+MMo9TXd{DBtt zG8}1D&_7Zo{FRAhym*$(V)D;q5bZ&+60))e{SE>)f6Md}(=$xgL8pUaA;#QKOiWiO zb{cXnUBG!J`~GLC3jy00=nAI8|KL-o{PqR3ou=rJC1ksB7C85}fw2O3L7!~MLbjsc zzyodVA8cM{V*~e%=8Jw-mAi#Hv_&=phpSjV}d+fgkO{bIh_LfE(6X^$UKmNb=|M%-mW*A=od)s#KKQ>{g|C_JW_*5M%luI2klD~5$!MXGSlgWX$Bp?d+(2St8~-`t zy^CZN|1;t{=xA&#hI3&1xA;v;1zj&g$NPOW#s6hK@O>NNs)MlSC(yo(b_=!^Y;WM0 zM|&FW1Z;a?Ghv@vH(~!^Ym09q2gx$BM^Unfe+k8&9+vM(v?s_MB9VMjK>CuW$Z2wx zCeSoGjE9h1D+DLz}Yg@poQFX3I`J>g^FtZ0p*Q8`fyqE1GA81=8HU!s1G?&s7w z?anA?j5FTZ$(io#;_T+kb53&3aL#sacfRc0;}Ts~SFp?JigCreI=X6NxELwM7-NYE zi;0R!iYbVxjTssD;ax#)ZEb07#eAHY2eb+Ki2Rkdqv>=wt;0OF(AP1KJ6wn|j}w^3 z-!Tu;Hjk&3c|3!8tmn639-yW!aT}^p+c>&SXe1Mi+LOo&I*5xB2hh}=0t6Y z`XK6b)QzZ{msNfg z)~{NRa;IC55`s3l^=NA&d6(=X!&>_?I<~Hn7syY`(^|*0j%Xd;I+ToV&1?B9akQLm z`Iu;0K5jYF`g_Y6d7ccOZCNjewX7pV*2}tv}@IuKz0N z>senJzRbOR{qnWTKVAOu^5x5yE;n8N$K`XEPhbAv^192@E+bQPIpnhLvgXSPm*h)# zFWtQK!KJuMF_*$FgU*^P8#L%5xdXY$<6gLH6N z74}!;xxLQDpOpQ6%Dxb<92juma^VgIDh92ycVqsvF-v>b0!F%5r|sqLHBy`0f$Y`l zu&cvfV>|bxy|i5qs_by>dUx5&5w(F0i<$NwR@YcsR@FN%+~x8ncj(&~ij>W7R$uj5O4(}~pe$YgQ*Cy%f+;zjMs~Y)XxOXYvd+E|ejpn4rM0Z|e z;>@o@fTNL(9o%`n8J4<0(yB&^^M{s&H|8(* zHkxY3&@KQ~nRjm+u@i49LKLj@$K6xXawu2M_qqmkH1UL=x6a)g z7+*H5an5jX*EmKPx2ZAcR=CT()M9pKrvOIubpq(Vbz_~4Vtk{-?z;a5@FcrsDZW6G zpj*D?r*I4qZ?-tI-FOUpPH%VbTL1sFF(DYy2}Bnp`52+Hs?n1NjCqFnnWXpLPARx! zSS<)PmeIAWsxieqsnO=n^>GnSFtB=$t*BCN@ty76XzSI8Y`p)j#+2T;7p&iVDdV*N zx1^i{QqEoO9n%Hly34BGBI&J{_I7rL|2ds>Cf+qjnTE?b&%0f z&Z=-%qsI$w@Vcu;dKrrXn~9eI8a_Y)_^Pt1sKQ-THn<8L;PNV0*ah}DA+Gly9^G-iwYVoN(r2$DP{^-;Js`H8vB7qnu?-p4-h?MZ-y;H^692boL&Z z=kLdkA9yGZ__$sLfu~9A5YOpV5blCHP(H~WI9zu62gdDcMt}l#ja`CD!(}yixfeU< z!+Qu55NDNpq}%Hr<81VlRxuPY^e7bZBSWE&kAg*&Rrep=hb*9pxNup)oFAEu`AKa! zWXNsoqZ|it4gPxYa^JvZ=Tf!1sA4Ijgxmi>0?7L|62|VHhs>BZv;^ZAH}tgA1o2md zf9YP2hY3Do4(C#L-@2vlimGl(Z|I)-@R@9E3n`*SmAT0spaygIy6NJwy&k%_VsO=4 zCipvxE35W#l)jiRYgKPK3GparId+zvWL=!>fIX=k2Wq8%_*))A<|tPM<%DuP z;vgl;IbSE7qh!QE&UenF^xGS+4CFyTKjNU^yW$BvLBKh+@7x^aoR@v}5{6NaR`jSn z8jqecaN&CaH6X*8L-0s7l>Avw4K#c&?gETBeUQ%CtMP>Uddxu&kJktB05txg2Mn(I zv!38K*P8SOoYw}rXoE^SMIH>NJ=U?sA`1)(UcBpq>CHlD%iKDY;dEr zxRDGPJfvzbrO$X5tXM&EBa0f-DykZtk=~-lI_#Jt_Xd+(@02M?_-CIfHB%mEt@6co zlut+vVtEIm(F6FNDjpEekOw|O4bIPk?|PM;zV|KL*go#EH$T^UMQ&)lBp=2Zi;QUb z|IdeIo$&dF+`^h)5;;fqQ4agq$WP=Vd}u-|l^(Ig_cxHtB-iOo`aL&^Tg<(|eaSod zB7O{C&u``r^Rkd6%n&Y%?ZpM+B}psQOP{OEsshzy)eEYl>L~SV>KmGJ&2yU5T1lIs zU8;Ro`?D@wH&{1A_pa`azMFoQ{u4v2;c3He!^I$T(D?7?j+rJ972Tu+@;1C^M z919#99aln<@K+u3YN!xe8~RS@S7EhbFNB-IM};2>KOcTEVtmBY5r-mfMs|#xAGtH~ zdXzgVFY2kNSEDXRXG9l8*G5l^{#*2S(YKu%XPC2tv%7PnbC>fi=ZDTF=TA=AWkl4K z=9=eP?b_~o!*#-S-t|LFXw0;jMKNn*UWxfj%t!7Z_d@p?_fGc#_X+oT_xG`LV^_p( ziv3gU+p!cKzR>i#(w>R!++^2D0#{ClCIsV!Bt?_@3KNkN#@n0wONa&wX zn=mP1Zo;aBO$o0g97^~wp()`?LUTJqyQp>@+vT(?YFE+jy>_3pyWH+ZB9~}Qj7{v6 z*e$VN;?TqiiBBaqB)*u~n0O@dOyY&aYwcTgJ9h23J0&fpS4u_7!zquXJejgQWmC$ZQr=1VIOQKH-=_T5N!7{H zDY8??PC1>P>hyW1A3NPi)uo1~c1Z1(T9W#3>g3e~^-hu6u3w zrQM(H-rPgzk=0{QkNrKGa|&{v&H1M%)HBHQPS4n$(|Uf^^Shq6bJe*axrw=5bDz)M znfqIAYcEx=&|a=y3wvG4i_go-E6AIfH!tsG-r2nKz1#Kf)cfh)U+0JCcgP=>|6=~j z`LE}{ng4G7$^5hV=li(&B=$+|Q`cuxpHB;H1w#v7E%?4~*S?$j{@nL=;o!nI3;$LW zQ`EkwzUZID*5cUWA;m8gf7vg%UsS)me#QMN`_1Y%zu%AjZj{883@uqz@@aoZ|Ka^N z_5Y!?SLv$Kt!2it=(6!;Q_Jeh8p>WM`=z{Z`HSU^tO%{>QPIDmwqkO{yo%>4 zc2>Mu@j=CfiW`-x%B0HT%10`fR=!$!X@Ge^&jAYu+!$yXSTpeVL3EI2P}ZPPgB}~y zFzEd%W7X4Dt={?G=D~voe>9}skWNDu4%swh|B%x|zO3$1J-vEk^*^hB85%ou`OqUn z&)2l8sjXR4bFSuM&6S7k59d5Q?BV$j?|k@++UVLzwQtvcJ*;@xy8r$+{OXA65#vWp zt)q2Cb??-jt-DlrweI#vVPuz)vqv_Jd~u{as&-W4Xw_)b=+MzIqf18Djh;Gs;pjD^ zcaBLM^Yoa%k8L;hnX%W#WsaLa?)oFukNoY?{*Qh?e$IqW6Ru6TH9?+OG4Yj&Hz#$Q zR5Gb{(hrj-PyYI`0Z{L^9^W>#)6~bOzA^R6w2*0q(`HTEGkwz&-Jf`MM%au;XS_SJ z{mfTqeml!G>#12yPv$+j=gEUlzF!|y@2%hW6n)D3)WO-}?84bAXP=)FGRHgT?YU8N z_ssLmE1p+1Z^gW0^G?rK%^y5}*VFXrp-*pp`l|&g3uZ1jy)bNH`NG8uc=@jazm6S?9AupB?$^>D66VZ+T99 zuI{;$&%2(V_Wap332SDq`QQb^3uQ07xz@h6-P*2e`>d^4Teo)V+C^*Et$lUv+iTCR zy}b69b>h14b)DAbuB%)(YTXm-maf~l?zMIAt>@MUua8;ZaedDE()GjEPhLNN{qyTz zUjNqm)9Wv+zrKNP2;R_sL)Q((8>%+cZJ4y-$qg$uY~Ikg;pm3{+3@X#+Z(kTBQ|#2 z*lXjUjbk=Gv2n@9bsKkY{L99VHh!`3`;9j@kxlwdk()Yh%Gp%9Y1pR8o91m=y=nWV z{hQv~^wFljZ~A)EubZXKj?D?1(>K>{es=ST7Y#2CeR1WBN4FTZRBu_i<&7=>cuDRBr_!4%NWA!hB7WSMcDiY<<3%tnj zoLVFBDng)2)6Eu|oo!Axr>AzZy3DRDY)AOM&2Nt3X0$9458NpnBYexAGqv>_dQN$c zk;Ho}yjIHzg2_x(234ikVC8s{lapj7%Ja1n}so8*p(r(15O)4}rA z!2>IXRF_v)({K1s?tET3u&TWO5HA~J0l$;a^}`zO(FrOf1=SL#;_>kGGihdu$9|NS z+KD3D>B2@gCLT}Z-o}@Bpyg-I#5VREfqasy;`qv&}B1XSw9h(SsCf}V229lqBya0e1bib+JYS!l92c9*(Em*4*IpW*NGiponG?I zTQwWEAKTGSK9`rbSf0>5Z!SIc;t}haQ(_raC*?{sGpyvzMXUZ|Tlc)S{6|la{CUxY zr$@K%68*b_d#6Ko)Dsvp6q0UTT3H@i8k0^wI+myg(Vnx6=Jyb zD3vPB;R*}Z#>S?kn8LyYlc{|_uSpPG#a_Wm!O}TNBm_chA=x1*Y?caXvlTI88o|fY zeu{(W=#kpVE?rL}`gEo}VxKB)esAu`r$);AyY!-?3$lCldw5{=#y;HIH# z5B+J?^y6On%G864k+rG!)S=bOzn1=nM;#94~N8S)5Vk z;8PTelJMyV1RJDWKFrNPe*?xm2p5AHQ})PP_T5ob}djdV)QH|fVmUYAqxVvhmN*5a$rBP@@UfxGa(98WZVM zm%QiVR~wgHy&%7qK*uLaHhJZk<`DV(44N&UnobkL?u?<6Fm@IBO2`(D6CJd^NiAtK zJa|iQ&}mS;$CDHc!Zd(yI1GuwTp2EK5A>edO`GI;I=_j|m+PCjx+c0%p4o&|5X?xv zO;3|+SnaaE3DY5pDqbWhClvG_g@%ulc(*0XMNfBr@{69aH01n;@)fGR%CJm#aRa%n zkOcD^xChk_0K!jhYlh3-oeQPA?%cs?#bVKHKpyPTN&s5JS9P*+^fB(+o4eYR<8 zz$i7e*&_;k6FyJjtq6~v0!|Lg^*qlp(YeoVQtG07Udu)K3g==L6L)Z=u=T1?fT&xC zIJ=$4riYT2NJyy0-ruWH@y7mM)LjPTugwC3FI+LiY_ho02sJ^JGR-C?M?%3}`EHBc zdWQ-vlyAuxI^ogUVULWj;hN;R@=E$7okHi+iSiuz8TpqVu2L;ET)6@a%mDl)fJRH& zd#oB1f2b+d>D6EvLC{Dv1k+&B&CHiVK*&E6aC26cq*5i&biPDB&5Qk_c0Ete%Y4bQ zwf#aC9ir3md(_DFVCIOwQ68V!O804#Jc^DkKB7`&t4D=umSVAfGwU3@ub8!pcPd-D|LpalF-f- z6&nTIhd4qUrCxmqHSi%J+E|srq&4;TY8gpj@Iqk!QXZ}ussJ8vY8aY)e+rruBgcRh zTrtehfmUo9?hIuIG*cyHy3z!}v2)Gd1M=O2MzLI(MZ%RV8JPnKF9dPu@p&cIx`sN|b4E#0^|eR;Xwt`JNb~ir1hp zng{a}yH$h{vQp71mV&jdyiq0b3Ry7$*lohJ0b_QCb|2Dxz{4pp1N9J87t`c!2`n+W zQU0`LB{!EwHp($tULDt2zDZN$PiV?{zOi}i?H*UHfkJ%(onM{z3@*VE@sC;&1G#B>OA z8HpdU&Wz43hEC?5@>!YOsQb4~wGYiPLKlrg8>tSmmXEW&F)nd-zYgZ+-rwe0>ddzPn)7 zBeQ0fP2bMAIZKhW{ZJkqJ;Bgo9Hk;Bs?<>9JXhl7p;REo3a17@WRye zdZG_6^Xfy1yUdFa;vPf6R2Q)V$77sCeQxt%l^aqjT~N5C!TtD>!jCvSH1h# z{-%%qQh&6t|Ncid9ld*aVC{&qUQ=_2b03xEb$d9iV{J}vyx4*CJm_5rdWRBJ^?96; zqE)YVyNQ*=Czzb2UXzIr4i4+@4Oa2$()+bBW6l7%F(FGfi#R~-n1l=lJd+l9KyYda zh;E5frs12EP$)kqH_Yo*S-s(dacX^+wU52~1=W4K^_O`q*J~dgURSfQp3j#{<$*!B z?L&^eT2uV%Kdw;oTKVFUr=J}6_#DQQhy|9)YEY@Hydc4cvuaJ1Uad)x zV41;TY&6r+G^R{opdE^Z=IfmgVbXOb-j1b@}HWbaEc1nfp=4k$MOC`7GG(FHjfBsoMCV$89RYkYLLt%Wa zBC#Gb+#HxXwOEQm5rn9CKAxE}l=%pL*qNI^u~qSx*(3S5Cb%h0O-$PEL6_vQa0C!R z)KC`=f0j)Rav_6IYW;@a0*k~rG0zj@ z3=4y51fDGhOMHTnPz_Ir+Z|cybz6>N{ec`^voOHRDWW}ge`S_ z3cGcacenXJ92wO*N;(NW(V65BuO~^Boo%yOGcpWat?jG^-WBRf4n=I`=^3of$`Z8Q zVMDd1_K~SVY&^6b}akL3ordP zZ>N0njC@u8JSF+PA#^3J`;D&tX1}~&-hFO%!v)<&Mpt~W4sjTKXCS>iF3!NKDT-Hh zI?xj_1!90816S-d7nyO7mz!I`8S^dm21jcd6wPTt1} zbQUMI$gAVju8p)>-Yy=#lgHK4&!3E)BO{B$qoRxmH(`&Bumw)o@Y(9Hc$O`f%2+lO;z%FW_|y+`KnGHauEulV2+ zKc!@FW#5+L^8Dc=4?yasLsNeO`3NSdo)DGQieTK}upwtr>@^E2Q7aaEwTj=)TrU0X6?wsckQwCjIRy6&4$g#? zb;4P9xy|WLajHC0eo`JzPt#F!x%`e?yJG=;4?f5X@*MGiyindj&o>uf#*AVdM$?hr zo>;sQKn#*rOQ~Mc6npg&sKitbhk0{6)fRhMuzsI2qPV63DExl35^%Ag%O!Bl2l&F4 ztMs~T=4=>Nepi+kG3|y?c^RW>NM}!&n&)-!Cn(jjLGK%nMK=l)Ff({>6eTiH2C%#6 z5As<)zvT*rj$;EXYVlD~OaK+bNUrG8j0{8evtd!-GsZ6POKb2Q=%1kYF(w za}z;S#YT@pHAI4c4%0ge1*?w(RPfZ3+SULJ6t~acBy>h>uYyyl*QAG)}s{cXL%wt6alS4 zEeN8hSM$Z*Vl`E(MXkhBu}xqR3EV>jQ^1Vsfj@DSe7far`9qq?^`aTv^p+*aHXP%+ zGmPg#O*APZrFk4!3q`&`q$t_c8#IC-@mii|q{Up>##E$#-inq-aFk_EfT2>E9b8k( z=zaURb^G=;mh=0{8ym};OHdR?TgS-d^cqGmkZ9yHI5oU*7%ku#MkVL{Hk1NpD~nT@ zr~+^k7d^J5Gd+D+Q$codch7VlY#;#m*j%vQ<=yfY zjTM=Qopi7S*M6sbk=JYFMZzq3>(rJiK(JM)xl_pPPn|<;cNh6N?G#`!l1xvi7F83H z!2r#|iwGJ_I$i~gQdNM>Sf~cX`FKFF2@3Ao0O3G6@svERciC+7i z*+!<}c4OvhINZ=Sf<|K}K|w~N%>b=#Fc?iHb+OmP!wUTuZPR97M176? zk=zb9X|-Xz3MK}C2r3{&Q~@6++7xV?touC`h8s==-t}vt2l4afURokxQYlY9IH(ER-D51-pWvkC6|5-0Hq9gzl#g(u6bH@rIN_+UqHu;7rtl7HO)+?fHR z#&;UpuyA21Rek^1*~xWN*A-UP#8+%MvzD$o@pTn-=4O`kOX}4lFX!>~qmTYGGxcAc z;>&XryJr^;KhEG!1V6I8uL?1h1$K|8REmeHGo};;zac%2R|= zZ2PfRBjZ`GLB7~K<`xp?F`Fs1>C|egMFTAZUh<2UFDL02EwfD$z&uRz`T}6HShGsL z_7_xte?T)9Z(0kJ(Ok0i<~-`U%fHq<_m#~r?&j+;67w+AF_MmD@OVz65n-?mU}pBp zfX44pw(%>YJfk}EAzc*s%go~MAfIcLUz1HVn_3;IlFs8xQ8usdccxwSx4tn{hcQMZ z%Pwg(Mw?ZnBqT&M^7@E~$jE5DP8Stn6?J@w(MXk*FyIHO^WF^oTGQv~Go8i9a|zIJ z%$cG}X;GNdt$53vaRiv#7&@*e!{r{Bn3=s?;P0bYrm!6mkw=WcNC zx7^@@T9SM)V5O01Ip}vJRz-Mic&$qmHCniE0FWZF%~YH(S>iYGNGUMJP$U#%f-9(t zn@v+OM7aEs98OF5YHo1z{Fakk3a@x>5J4pes3BcFk!peRDiuc8>Qop?U>+(*;kNi4 zMP)(9=fd5Kx_nb)DL(|iE@ATB_qexP1`1&Tv?Ps(khTQ z4>(fbQw86gOTN-_(VsV`Bpu^Bl<~1XgCv9oQ&kgHEF?7mfG_iu+R2e_#(JvRm45Le z{aTKgELNWToq4oG&8da%;ycJOBztT~D~OVS41*fiKpU0FNq7=VkfQoWA%mhV!2(to zdpD*`53Houufu)+o>TJ&nhUx4EqF15wl>R$`I6QG#7tOgLhgc7kfMkmle!ESU();< zj}@ln=#5`n_?%xMxxgC{9vxA6;5%uw;v6iyhh6ZwdSM^3)KYvre7s$#YikdW9&wc4!@E%NI1qRnQ^_uAmo ziP8C9F__pDo9YXel*PS!?ki(G7R|X3Zc9oQ3sE#%&Ge@cu%M4Lf)ai6qq?g5ZJYnn zTfg5u`r5)bMjp9x`Dgi)X$$5(H*WUYVMPab?|VffrS2~Kc;x#Zv^Y56xN7j+nIi%7 z7Qnn8>s1!4zvp^fkv#9xm~=r7hfe3z6P;aSl86-6$14RBYacIu6y#oTlO5t;gi{iU zei=!#z+r{8aI2UfU_-jqfrPLU1+Wm54?1z_yOYN!+0%cZse1h*lO~Vh9(lZG;v`{; zd|LiRz9Rp%VHOs+*7RPx^X9TGuKgSTv}4B(@JV&+RsI4pUv_9$J4<{y5U>P`x;|dK z>}3RG!2!tpOv^AQ!ZBj0U&TzBO|YNHzgMM!MMU?KYlzOmnPT*hdL;TAxmhQYYKi$3Vzz4V8-+w zet;ndgC~Z=f)S$L^mt}p+#qZMU}B3AiWTL!UeQt{iw;0 z+3;?ek%H&9*AJ(oe!seE$1jVw1(4&1a=4Ng42NZK^A;6XbRzZsM>BYPyGeEK|NA z|CNT`{)wtvQpA<>M(!V8dVpU)Yx3k-&E@b`%t)@K%Qvn)H}Bc@9j~@aU=k1O&QHbL zs&>-N6J_H#71T|z1Fp71q&5oJY(|}_j~72WqsRtaUnTDJSx)9F`SWVfCeSHB9&&1+ zFvB3~H?;C?`RuM;htF=FRZ?BjvkO)8GnyCiGgg*_$u6GU|k>8R({_(e` zW~Ss9=2wlrb|Gc1MNXJ8e*2*bQ#Mylo>(zpVCl|XLd}NcqM`dw@nUR;+|BFW|NFMp zBNs>7hNOE2B*yQ0?9C6%!d)S!U~oxJr~Z7uA>+mk`4F_*0G}# z)f!E(QLtEqK3FSwbsiv<+%o^kQ7gd1>z0= z#9^}c^_qyr$U=0e7e-xWxe<**Nsv#8)0Kq=#aop4z<~KvEA#vI>qApNo}>&b+d_Y~ z4y+V*-%Z?iMD++8ok;@2<}J)9i1hWi1=vnxt|d`41!)ZiwOXq+>Igfl4hlk9lbtuV z`6gf*-#npoeW+zD>YBAjC}yib@Fpcxu{&?}Sh!H;o#+7Qy6?nuvM!mWG< zGp6xf5|+qk%LYvyC!hTx(VV<{!d-88^6L}cIVOKxHfYjBZpDlldyco<5NaCw4ccBZ z@Ywm51a@xAYXO|^0^By1zXS&dE8yAodW?mr+BUCypzm1dlfVBszct=ReE0m-4F>V^7Or>>0iQ>0||8PUe*a^N~CjVnSmyNRWqxJB(4m zdW%KH^o^eM@#@=<_it9$w?-WoFtP~g9DW-d>_}$?l;+NCjgXu8_@m;)S?3=SPF(ut zB-<8Ml9<{MxRa*WvY>fX>dPl?}fipr3Vrq^!~>3H)@xYGM&4 zXHodc%+!)W6q&ySAKWiRJ`Sg84qmZV0S@O)JrW&p8P9H$&wiI|?7UZ)qLIJUu36M_ zQm8pxGlg+2^M3YV47NHNErlYOCkfFuTRhR*qV>_*NJnJ8*J0wd`Ck43Tqv{(aFnuc zfm#T*fRn*&Is6V^Ebp_R01AGZBZ}kqT)#GRPtkzS%64{mbnx66S>OH7hwoNbK3lwK z(CYa!yU^l2`(4iFcA2%Y$=UIl)zb$(zpd(v*p7V@yLHW|euBZ90(i6Vs~~oQniIX+ zXtY|jYR;@S2RpPDqb1*K&>M{+NCyvCQQPT9l=Np{;hxz>=7hwh!QEi4FSGPn>2{XW zwgq$3OD8?H^Uar^-BooAA@j+;7u{c_zx5UuK6ljBYu~hd)3XPIVLfCHIX*~wnkR%a zn{BpW#Qt`R#>k05VvsVn;$iq=uzMl$13ov1*%>2PbQ|kUH$3LK{OyX&3L&<=1 zC%DgBrZ9o$g6?i*cn!DG{*UJ9uI7%C1+1{#VO{iXej@HXNu3VLOa$PyMyph(mTxdB?XUlUL zm7rl5m4dMX5~s7-OvqmeSWVDqLQKrD!6}OnY&T)u7dkPVEj58`J{Q1ewG=Nvfk?3r zKH)aAB#MuSEN1hSA!KFIl5^o&N#{IE`^X7B|MgP;;;f!!Gh!^D>$37mqla))?^<7f z&3wZ!q7FqQN+k)u8_;Q({O~G)6^ZIl5vEm=2nZaF9FElaUS^_wxkXsq$91`L*L`1j*-fA^~ zn_>-me>ksjsxpFaFFl>%9yU1xD-{{6m;teY-HdQA*luU4)(**~(evw{ns@Z(h$89h z9}DYl9;HEps;^g-t7(sQ^_ThlJo&T3F?#o2jr>_&KL2Gsetd}1lX42TRSJSHVnfX# zk4ipBRZfa86vvpzCeV{jO;XTp7v_K{o>yZIF>DUeaM$t6UFujYtGc73f`V+K&5oS1 zKPU1Z=YYa2$(?~kdNW(BXVuWCddXn*ZDtm^+TpQs>hiZ=9#J%H%2!fh-OKNk&00`D zKY7w)8DDaFeQ1(y;3H;z%wd|8pT}R$m@+{=s;#WNUOtS`vWiO(vXLRQlPph&M9ey( zs#W_hx|8y^<;5NzpGxdAmJHNfS4Zv!AM_Pq^Y zYjNRzK(S}7XYbu(SwNoxYdB3w;#su&k26hR&enwI^ZPB3?;IUHI}8xa|5?eA3w_4g7{9g06GJXAtulCNkT6U0K|eN{;qoE4PDB1jGtp~EOi zb|rGRvr2U?U9SG*+`gR)Sm-|E@t?|{uA9AdUt?E#2XAafMDN_J>3JnG_T^XQx1y8f z?wZ4lJD_vM0lG+1<>_Fw=s1nR5EdNFg_uGt7E@HTJ|r}x%&Q3vC03XwBMKrzhzNim zD4_Bc!TDa9U@BCh4Z!v5pL+o)Oq5Lpzk+d71}Y4}P~72T$A)g2Qc_8$%S&G1KEC_? z=zjb5eIuSO|JLKJIMURxyF_lj-QlsiRZYiEeGZCECbHlXb_1UYh>>GVdaFisgmG#t z%EUzAr(oM9I;^HJPOlNwD!V;e6$kD)fm{)^xsnrSl|M?p!P+@1Ag zRfH#~60+j6d}dAYs1Ik(T|IlqxUoZKubG>XQUC1hheuAStY0-d^X&N2vWb)XmrUf& zje2e(4ta~tM*Cp=PJzp6exeb%b_p=0_@oKR9aVG`qXB<%!b$Dvavdmak1*erGf zcv~alJr*s?um+=Af(wCea7Y%br5ptflt&d!kTIy-t1=q()Gp~CsE7?kIHrrX_iwz(9<1NlhR79d5KEzdo6>((v#@^8QW_Kv)Wc4H~q7W=-X z`z~C-7k35qO!qX7inu*SPLdGjvv+Tlw{M_(l=n&QEjch1gy9u6#1v8UC-Us(PnhpI z4!+N9DG}8+50L?$_FA*UEQ%dtNJ2zJx&tp~bm22It)Z!@?XB&D;-cevjNwDx}KXv-qvJ?47;|7<$x%A?^$4f>oh|A#P`p<7y`TYFN zmG3yyJ9bJfO!mAoes4v)v4zjQ-v4Z3_SA$<=`n?ymh~FbG25G0lN!_?ICKcN`QwrR z&&Pp^eS<~MI3gs}$n$m$tL*Yk2bF2ci$RKJ@x5&nci%pB6nS!sihFvB=<2d=J^Ph- zx|NCbJ@X5@ck7#xx;tCR=1w!0k3F-UMr_?q z!?$ghzuvlC{$?A0sdPZ1nYL+ZH%*0 zxSzR$sFHLL7ph{TLR8e@h%%|L=A(*=aT^VWXr0bV!;y;?tkI|_$WB4hoEbd!Ud(-J zmYu?M!4STAW@Y)3%FM*r&B}WrP+lsDON~x?vT$nsj<-h4E?bZG{nHqDMS%rAhvQI-2AaFbR)+!S=t9pFwi>B-WYb?bGS;uzS1AI+NS5&N--G z2=lPTC>0hPQO^Y+kiPRRI=~_!m!07fvYVRk@Rx7XN1F(KGt2*W16C+Z%;j(6N4=jT zM|o25TSItVf|$()yt1TH^XiWA0p^5)F&G59ptft&`1>zB3PRl@T^p-{Wqow@WeHU5 zl{IK1WCq$6k^e8Q6&5u7B=1Z4hN|CqMV=jx#jYW z?A)H2^2Ps?b7|`x$tFnB1xRgRH3sgSkDy>ghFj_GO+hc&PASnpAIdX-A_(w^z;l7CbP3! ztB1Zc_~a_j;OZVZHPztLDv&N){%je!<8ES?qcW zr;wT*A)26Q4ppH}V8)US?6j$V-xyi&D44arS466EaqqOuxHKxeQ@gSevsS;oWOL2j zv9y*e+|^X)O^a_=wRY};sRPzbeHdeQ<+8a0s1J=JJv@;%9S3)ZI3=gfBDuP2!R1e6BjJSKrktYw3HuVkxz(G7#i|0V@9MSzZxgOzddz|E|G-)t zFL+Rjh1Wsnu(h}|3?OrQ*eSLamx0&V5O1iEj>w?{JKyaid>;P6NPFiqY0MX4xh^ER zS;f64T8FhsO_&9%Z2&z~_qmO=h*4BEQ?u8-(MObXLvIirRe>HL(g2OqEHu8Cr%ajYE}`M2 zom+cU{{8enzUQjtW~ub|Mn2tg=Pngk9(O92NY5eO&=I>w0|Tt*HI-hx{^iSCE8YXs z^NM?~yh_E2&AD>{cOGk}O~{BNm4P+E&K`%!!17oyEH;zLU^7@XLF~mcq{G1v024ft z{iGjU#xdYkR zsv#4svPOCTNkB>G{qH|TF`-}*!MIRi0Sx6sjPL!YxOA@I8ZU--Dj83c-{lJFJCh!c zZQp%1JUjfF^UvI6SWV`YM0*T@x4VpRN?;`Ky*}zwrV5f3cSO9;LFO*M`Qo~_{=9AN zA=%xtpdcrwprEHv{pyk9FTZm1_|CeKBkSr$jQE4q8|-PXL*@q+^C-f@60{mCB|-O$ zo}d^zD&p;C7(b?8*xdfB(L0ic>o9ou21B4y8uh!PuMyVEE1GDq{9_Ypy`+2l$a!>~ zPOEA4bU8ch-Y&CU9g#nJ7TAs_vpz*Ck#lfRyi~_OiC`)fxH|83kCcZW4RoI%^&i*5^tKhv+IDkrjyMVphQeGxSXIrYb$Sr~pNjn%et%Or!b#dk;w7F<%d#&@i52 zb-4;0$|$(%?-BOkC=A;^IL0YGnB*n-=nktkm+A$RupYK2(t|Q=qS2t5oTaxzQ_}9e zi_H{z7WD-%Q0aT*&(_jpnz|0&MDp|US^3-=?i@{CFMmdp*5L3HTtyca15a<=DSn5D z+X_7zL$W;)j_3%RO&b9->W&SLa)lZ~S>Y^?pAq;&ou@w>WGa*yQWJY;j-`cs1v4yN zL~RbrJUX#+0!4|jue$j7vcX#ipJ4UHC!Vd`Qg!t1XAjXkm19w0{B63dFCIgu_$rNi zE_!tFQM|T+V&nY!G4qeg3*UX5yP5p^uluLAm=l0sr7lyU(L;VJCMgu4ZMyG|J*Ls1 z|GfvOxZc;p8K9Bx8H`50QN}4fm_)Sm(Fl;>BghIQ-4sZsfoe>XQ?t?qGQ+e4tB+=p zU8X0(jO77?29;`3uwdxt)!6%a1r2H!RXnRx_oX(G*Hm)2idAP8J5U&HM=qf)N)vXY zV)o8DR$#wRruvq=x>e82Ui>7_eREsJs|ep*le>+b`N$Z6#p<-gF{ql!AeEjZWEfou zD5mKc78I1#F(oB4D9oiI2??q&KBRqm`##=ul43W96nf46^}ov%@NoShB(t6j zz976Y#1{X2j$y!k!vdkN0>vMED5V>n*=t?G<@TOJPy3AAXUC@h@YRTw-7=8)y2s~%ed8#1lg105dxjNv>C`?rymPxD!)KQ4c`Y*LMr_)w#Pn|M3#ONO z#-(PJcI;L*w)QU8$WMK>m+5Y$mQHeka(S4(M0#z5OZaCl$?UhTf4n|z{C~Rc4BStP zersj-cY5&tptkGf$Xeif!h_d^z;!YXo-~u~hm;P?s`?<<7wADtQP{+K#QS+QFE$B4Io_-ab-pPslt z$^S#ymjFglWoy^1s;*ws`;yMy>8ykhl8^*sYxWRG*dh`{R7Cbw1Vlt|5D^s>5kx=- z5fK?=5D^h^0Z~Lm29@D4=r}$_MFBTNgmmTq&aLWB2lc)GC4_XUt8d-q+;h+RooF#) zzxMAMuq)ba`W<&XaPw_q_=JmX6(@La9zV0;wPz^$u)bIK+V^f=80n^-J&ka%VQ2CS z#1vV+=32xdvLDV&yMtC8et(Mc!<_ckPI9)8pX3xjF^W?|wMGrk@zu(St=5(A&w|$+ ztNCZ|vwkN2eqqbc(`sw&PoP5(Ygrmw?WQ$&?kBtlKjRfn9Tg!wcm}h@+E|9u_rruc zW;OL{c}LSdxZ}I#J6J#UeeDjH-bT|GxMLa24S9n0lnML};#WbfC*VdrmP842$$3_! zBPyc=0%-=5WR*nGm6m3;7G}F#1wkQM#6`F>lSRKDu>uG;g>Ws}b9*<~{gT+P0pK9b z2Ip7|pr&DgRES(O4n~q1*Sol#R68#6@~iyZr{G4yXENn~E=Kk(9bB&VM&wg-ibljxBEP3RC2R9IXtOFzEPMZEaod9{>dE*>xWQ_M82T4Kt143V1u>yGg>}@R#5A~1iVj_ zRHCmRaG-=wkpq1I{K0`WY!z|)ElAv!5qq63qy-V$3T{t^F6jPz0ci3yDGRnGLxQC| zF?$^O(b0u9-Mja#>DH}ZP4^zv^cyfPC%^CCudZ+J!F7_{uXa$M-h=A!+!0MX5RJ5q zOAXzBkZy3YxvL7yX4T zS{rGJy~s@HMSrb@)L1Vd!y0DtnSk7gXY?1w@fJj1LJLYR??oSc)+n}@FcnxekUwdR z@N+zZ>-_vNz)}z1RUq6DDYZ+PmO#*Hv-v!MK&w1SDm14cWgv{mMmTnB8axgK->zgI z#OAbwph6rZ1kgtjHQeUeeB5xw5^s~WITkUGpqjjj3OEYD14*^~UFbZ!_~s|?{Abd0 z6_$YdHgbT<)~vZ0v5o6LWxRazqNzhhds!9}Sqe+4AGq-5@&ivjb>MP6qUh(YOxt$X zeb22}Nh2jWA2BjmhXOuFwN1Zjv+PKiBY703a4sjX+RL=oqPFv6EpQ6gTBvLK_K#ZN z6t1;U$Jgn~7W&5fFo2b?3gRxF7JcCBL@f}tbk*93Q`|1>2IOLCZSdUyBM*8vLM@Py zC4lSrB){HO@Z$R4G44bgNB@|OBfc-`)Ju@RSbvy|Fz!%{xYnyF_b&c!SnL-GB2IdbVtV_LYm^#t>Ua`;7?i$0# zU!;$Jo%Zawm1rGFF2>Dhxu1SV1zRFmcd&5S0$K2HM2) z1m@3BkE~q_H%mwLZMz%E0`G|ffBO4AwM5=RyV^Zu=Y|gtV9lC-%R^KvG|Ah8 zb+s6BDqUX=E(0t=T&JfSg<2823iA$>1If(yLa|2as?GyrmL1Bt5Wgl~AX2a+xP|(z zHfPPJ74{+0f*++;Uc;_J!tq`%$do!D&3eoj!^Kf+= zB3@5EHJIjvPLQsA>^L<^-e`J5n|phV2d%^EoHvq;G(f*&EW4lhfXxP;%J~4bgK+{? z0e7Jt8fOi)ev{gfGBmW$(yTNY_^j}!8eZ1!h8L$jo7wa3U;Fmh!P7k zi)Q3=3W(OUHUmIl+jA9C$D<{khHrW@9GAObbHrY+3K;PJu3po3vdV{Ms*U0xcBXLu zRPoJd4Wj1gpW^AzcO5)PBfu1B59+8ZcadTM(0kMb4IF0+^u@-v$d0dX9nP zQU^F}B3GqIxur}2-S!D%Cmzl_!cO;|`Ko%P&-7hb<@H5xPm7LYpW>HPtgkL?({z49 zW#H0ePi=LR6IK`cDOs%sX?F;l(P^CCaqR;uYXHiG)&{5Si*d?EUW)cfjj}a*N_--u zwsYDO<5Jr?&W~eHR9Js(3_LF-#(fl=OzW{?`RLIl^aZnamgaI7b~T}0q`(UhcAJu& zQWEh0lGBiSWKVTl?0$!o41c9tM<~hHtWLa63#;q^DNwh!`&)589D5I5zHl+Ip z;wL`06!4QlvlP_YXl2AWCGZybxuCUBC%nzqR&3b+*8$+Nl(H**8haHW67zYA>!;f69nF;l834*he55ZR67k1C3bo7a^vZJN>xh z59dDjxmUUJ@{9u;AIp2N7>H2Y*bvsG^W9--blefRYvYzJ8@k<|7hYtxvisnTn8+5| z%^G-;bm;QW=YK=e>-`=-w{@H`&IJW!3PqTuX_2c++S(Cilb2^|+cw?nZI@*-m8bcF zCBB-5k`lq`Yz?`^DcXT8UWgo2rx1kU6@lb^8ssYtuZR}WgEjasPHiN{Xy!87BBZ}$ zQNV31af?E6DUlXYC|V%5(wxtktpJ{o8(KH2KdxAMY5m1T3`t1S-tF`7_ve{2>Nl=f zG;#OnL9bmN6Hos7cH|vqwojbtU9;u^W_p47Sn+_`wUlpbn!gkYw=l8x((}Rg&6qQF zp3YIKIS+%tNjywgrcqtoX9A8QE$0+-HST~$3>E^861TAt2ScO=s17Y~4z`1HFq}@5 z2ZihST+7qRknlwCuyXB*=`pT31W(-6{6yCOasEVqjE8YN6W-@az0Y;L1=cp!0%_1& zcnhd~Lw$x!jXt;elNR7R)n$^3#1{57x4`;we*+FH-QO@0oCugI7#;dRK4vzGkD4sj z$jriZJegmI)Ps4xqR*^~?klHQ5EF-fD zSFh2oen3~@dXVSv8PX)G{!L$LGn5p28f9edR|>SxaT&pm%qYkRL70Jw6ym5W4xT}7 z2S5h{m<<9~5Ts-^nxJ?9B@h088|BGpFf0_VqABnR#RRYgw1XA0Jk$&vt@I7mgV0$n zUexeee*IOfSAq5gkQTsq;OW#q${5QKu8Wko%wBJDTAJCK;_y3?%%b1y&&;w1yn)^g zsa&;4wjqqi<#i}XA>$qq$`apuWp_yK;M+0&LeD7UK|XqrxSm#qO$kMVr%810ENG3RTwc@MVy?7W= zCL0XVA#peH7Wg@$wNM-LVaDS~cnka-(ORg5NQf4aW0a}&fi!2Wg}Og(fuAE<3w2r_ zTDE{NrC1B7dW}(#^-t>rdAqc6khe=~V<6-Vxp5_h_!Nz z(>%3eWJ82KpkiuAbG-3(VB-T~kJb*iQove4J-`k`KA+YDe*Gf9PTOt|r~RvVoBh~y zZ4ERxJU+>@<@i&fw&SV&xG0G^jPEtHk>~@4{lcrY5nqKXY`(hvg2g>dS_?zbyH4~B z#NoL0(Q5__8X2Ztp3Zv;gE8m5IvGhBjh8rYm~^&h(?!MogzAexvha-isJNcJN-1REGDv!WV55 zvLjB59oU&kR;1rIQan5AP$_b9@%sF$=mvjFcdGjJVM^a zK^f5I+gRNa17+#-jpQJPAq856&0w)0KPNo}*{$}J6yR6{kn#(37}(4;v;`+n^Af^R zG#OtvDKrNnlF-)zDZ)oKMDg^VZ4ml8&fB!<@B3Cxs~+5S@|R!Ed0`(?^*2k?ffw=G zcHl)U>3xc99^iwEjGGbZO|kdI!t6*#mq89FUSnE%aws|3DhSyH5oPgCa$;*VMV2ByHGFoOX9paOA;h)9zh7eagd6(gc>aZB_X{;OrPm_yi`8 z@2S2$>FxznCf#-Sc$&!KcI}9>;merI`NF*#Ul29xp%}OB^GE{D7dB~ku%q}8ERfw| zoPkFI@itcLca-v7EycMY_xkZRcH<847H9%!K~n_K3pj=nBpk>am#J?fAa69wH@NyP zJ}m5(Pss2#zzzWaCE@i!P=M+$+8v^K0gMtQWhtluq;E$$g?ZE}kt)(Gs{kYu@JaPg z)Yd(A=(Qf~=FG>dYt!1j*gG}x33hq{65njdp*F}!8*!S21w3B%kDfsB z;D}YouP7%#H950>X{Nd+ebVeh%Lmu5R6?os&z6-eoSS;xkZT$ce4Pr^r@e+P&=Nd5 zaU{qFywU>vod>bkAQ7-sabtA2VarDt^B1`Lf>MMr=S5tAgpQ!{f!(1@#aj!2B3x3Q za`-xZ%(QpW0FSfCFV8@!gevKR?URjLkC-;gC0Aelfm113y=&*%lFDR4j$1CD){#v- zJHczr7Faf#`w@pRS?$ zF%B;CaPM&oVy{W0yS{1mr2j-9MF{`%wWLn)L@^NH)*uhQPMS@6PkAPn$ z2W=j~=)w0?=X|H=T!4I!l=rXG+(e)tK9UsYyEL=Vl)~f_rK#o53um_x*}=>XNh_=m z%_EM3xbA((K8yr<1s3YGa19|xVys2QtKvfmoHX+QlGs0 zMI5-;a~GvAlpR=aKeXAhh#$CIX_*Pq)SybE50wHNFF9@$?YZ{%R0MphsFvFR}(>1EMX21FG@7oiBA4e*hfVm`7G=3?Y7 zOn-NL@(Jv?Wrkm1nJN$-(m(qS|15KqIUJ%G`z+mQ_=VqD^hb9pO5&Z;aeilOq4D=^ zCfxZBVzWBnPS{QcYyJLS>vym$7&M#XE#3>&E1kF4iDl|7zM%EeRtAhuQ~b_%aOWgy zk8skv5zc&x*M+96_1a+eshq5@hEpl)8=`5E=FG_oU2XTAk zjoq*9+4JhFZ%SiSb;*?|w?AFJ{L@d3{3PoRx+5QoLVgi#M!Amx)jIf$;y;exX+wTa zzzCxU5T;-OMc8|i0vudLGHW2yvAHFd1o4c5Cn*aFaqIZb%M(}I%9DU&cYyuC2D2a4 z1M2sdPV)9H|1NA?PRNPU)bt;;rxWrqdeb)E8?p;4H1n8MSnIf@ohl_*fz}gNVCPOU zqLv>}8Zo;9W*3^1Y=NcS;+CPE6X;?>RAAir#!p|`{y5JhI@3TAhsBFg(_m?B<7jDr zqeq&pN}bil>L$RgKQ`>+J#%pm=lwNUMMl(?dCbr{6|D|hR*OJ zex<%AFOqj$?ypfDQ86NE(J}-`v+^Vxh;kF5qc2*#uwp+qR-ImurjbUDT|<~m>~5QQB@t3 zX2~u>%|eGPr==C=I~=WrB5P4?L&$2%@#NGt1Uy!Jn|(4Bw2FBoINVKhFumS)%|c2f zg>#K(*0BmoI!3a0PC0pO5j_mHjZEaQkC7Q02XDF5Xn*SE&C3hb)BfG+H%~pp>@Qca zK*dgGfA}f&o85l(bm8*NJ2u$ap68a|`^@D7pD$#}x;4Ko-LYfoZ)?`6mll35ci6Dx zVT!)T7vZ#GtR3-^2{^2kl~}q|Ari^-84M_JVnyO$x*eq#Ws}QP+u(D#loSsVdx`B( z6*J8ulpv~;35G_5ZB5>1GW_BfbsWEFn68krQvIj;QMvkUIl|jdvh0=HGnqeg>uMI3 zj;mj*7u5c22gGlY3;p(3H*`|ljRp=2!u!MlGwSp%vuh1t+*}?Sm)+45W z-FSJN`tB^t4;E+b@Mkd=%ot`o6E>zo!WYTT$gn8+`4W<&EJevqr_0sKm8xWi!`Xcr z!eQ_);Ho7d4;6t>@b)&3MbGo}c^=y#}{8~${{lh$#h6j8iieXV_K;9GUx;OhTHYinwYHA|T8Ikmw$BLag`{S{xN0-hSv1M4_n)~kC^*rFhe?70B z+$;9De*E0Uw~e2AyR`DLHy(bvxcl+qs>(K%<9m<1uuhGt-(UQ2=MU<`*R8xN{L-B_ z&x5$BRmIDN&nizC6)6+ayy39l?@XuA?gE3;neWXLQH86)kq30~yu74fx+TjP%rtfr@Y=)evIc{`%uJIhaXfKW&^*&aU1=7=0t;9C6AvoX^NS>V;V2n)QRd$wg#nI9%J{a;~OhZpZo5Nyy)14 zuTIen(dhuLktBp*k3btXn?1>4MnITZCrYg|oa{KPUJTuj9qrp`(6q^`U*8TyG@)A; zj^`(l^tBGs7h-!LkzC>ui3umz=g`};X>UNmFfx{rk)4u)$ZDfk@aAL-LO4mvWVpak z2h8hEc2_qf`z?m*2Eco8>oj*zquk<^`B2ysL}z?!(0^2y57|#ZT&SSs@&};eG@l_N z9V4hm$4-QEMqFRkZooA&o}N+8g1P;xLOFq3@~1pdcuP@|(k9~rIW%H;O;V$)_wolD z8^?{ZoUyql&1O9owOid^P32?6vIDCCW5jWbc_iIq2A@Y%5&-%d>W)wZ6N;Q7NW+LQ zCm_*j0T?lEg}wr=4|L^rg`5zXLkjEguU@7ZV_3UkZ>&?#VOAgg@^RE~DMHnlrRq!T z682*oc>T+A^YRJ{!?J?Hlr|+90lO%2);0}RkWf)ki4+8CLJjCFDGy*&<|H# z)!*d2hHp`w*mO?HSq#5U9punzV4PJ703(1$uZyqx3mw5o-^Y1*BOY0Da`EGbd-$cC zey@CY*Yb^9^-dvD@hxk;aWxMb$_gFl=*x6joTsiApe zVjDW|U!Wl#0|6hcLRu9@9)y%c$dCb{dn62lk-dX-SoW&6yZ+-Ja%^ z_A^IY=P<0!c$LGrU?8vj!X8j!m^%2`IXKC zzv;gJt(uV?(!+n5u8)4UOE3^BqG6htf*b~Xpe0#(YJ7GHi=ZB#!OXN#THFLyMan?38+ z+dB3vTYnEb`N$WyBRAJ1cKz)2^=mgg{_xb7hHRj@Dg<8=KvQnaRSFoN(GJ8>r`_%m z>`r^{24@R4$d$jut%Clv;D@Lt74nHQ`gR&PZQ`2Op)qWe@})V1Y^o!j&L4A%p30?d zJk=)@M|=o{ve`TyRC@%rpzII;E-dJLH%_?v${4Z$h#EsS#d6>jfLtRkQ=?6+Z2T?r zZb>U*z#I=&mBPKiZNh?^FG_^w{VeBlf|^fNF-=tyPS0NEHYPRC3EE< zz06H`4nC)W=R66d0UKTNv5~_&M3!ud?oiLFUro8~)8RGD{?FZ?Ghv1L<94xb?Xv@J zj9#+6-*_YYPX-HLSi>?OdHD7tbJTC!iSjGQ)lV+}O})IvrDkC!n~q=)9+W3TI)N0A zKsb}Zkf8t#DBBN=t&EV*WJpHo`Bb~jWvgz0Nbkr15?{4e5Fv&OPE{QE2ok58{8rkS zJamQxU?hS(95a{aOZZ#T51Ai^-!ibU1}@!lwZmI!y*rn-yL!sJzqT8P8Gn^sxF^`V zefy5L$dk*b&;690jVfwxq$25D=He$=@8}9?CcB|`7ti@jq6*ck^oBwnMATdsVz!d) zb`%6Kn^S#mH_BNm9tTTyV4v6=etY6_T%mnv3xOr5XeWiRh62TC=IGjcz$N{#ZRtQ* zsnw6vo@pClx$|ziVMu=#>|Z}}^gNau zDLv;MKYq$+)`l5YGx;fW{pf}*x8B3@)f02R)ZB3W1 zhq(;8c04zU&mq^wSK{-qy(3eE-x1GpCVQL6Z3eLFQd9!>^;17}Yzoe~&M7i%JQ>2^ zNGo3;Eg(9~Q1skpb6Q%KJ2L=Ok3hib@k1!@-vD3`w_relE8UdKk41<~34$iA3$Bod zmKH}VWCsWq$iH+z>faE5k!dbZzV(`$`c{?&hg^@6T!++U@^H0=jrj7{!|psL6lM0T zn%~eTI#TA!=6~A6 zInhN)2lxE#=Lv^zM`f-@x3k*+{>!J6re5=)eDICU>h^u8VObESB9>pUYj#z&ZOrY2 zG3ZsgAeA7Z41Z(sTiB=nKWsv=ih^jP7%MLd&ZcjT6z!V=o;(QHlR>1D19jDvnJLS; z*t=nvPX$vjh&q))$$`L5hsTuKzkv*5SHy0{XCWr)(3x3IWyxg3b%l(gsO0PL#%?#t zeaGyT@}(KTX~Zi^w*Y8|YAGxZ$qD$4aS<{QF&BtG!l6Tyr zGWDiSqF?pih>)~vnDuh?&0}u5mPUdVHg3X5+^{`@E&(8pxHD5A0O7+*(r}s;>u3eM zHOAnOlgyIIEyKkStNh7X1%^ZcA_)pm^ZB9;BSwvYDrrV#FmBR&A65a(z&>Rad`MAr z{_e%=s@cIWPc>JLj2`($z47KTH^ZMymSet?sP=orvb+75~5kqOu#9gNGchhC#Q#7beLc83M>NmtQ1p_Tr`xy2XMK+yaWBjSF@i> zTX*?&th*H!HSAoAfYfL|Y=B0iPXN7wDoiH0JWP@iP&G7#Eo^AbOU-pmqE`rbe3fGa z%Ff-6JmmJ#4eC&UU9BGX#3PUH7(fK6R*`?K5fq5U)Ml{RqcJ zAc=Y?R|~b}CrzKH zT-#O}g))Tghg_EF%Qh8C^>3-i8Yij8#DiHYt`j>Vt1%lXTLUilkJb}zyfX5XDjb%! z>phP9^st`zGTx6KyO6t8UaSzFXR0YTWUF1Jx;a4J#d zO>QtEF-Ge#+0VFC!@JC{gFWDkM|bgm?1gAjeXxh0z~3iW1X({O6lD&mpW$bRcoE=* zolu{Re!53Z;;CpV{h*)38IOZ^BTp}q>z7kg$)eyk8Vf@CQUGcMTq*%ePEJN`Lk^(t zYqf&IT+)ZBD28O9k%G>>u$Lh4YrutaC<|v25N#6ercmw+ecJMe#=zONW z{?^Fo6gK_rH%sPz^YNlZAH2DE9!vh)_bgq$Vd<`*;@$bkd*2RVa&h_b8^`@LY)rp~ z*++)dzDxTCH2o>&*+CTm>fb z!4yTBQC(6Ip9ZSi8Mi4qT*cZ&yS#Q>9*Vl9uPv@myd@t(H z4d{;r(H6--xCbTJEU3LMTaEC!$tFX~s(YYGEHBoV|3^ESmX$B8;RbbG^c=B8(Z*_` z-_e4hQ+x^Wa5{fD$MB%KN>FmUQ70M5VHU3&&O*0jg7?nkVc4|#u8pfeF@|yFu|hsX zb@dg8$eKSmI5cYiokun9vBvu?yqenm)K~21Dg68;nIi6+)b8h~VhZSx=DCGmkaiRC zPt2-^a-l?UC?rQXaZVYb1NngM?gjX@!Gruv9JcXFlYEEAhpj0;6&_ zS~&pzI;fqlUh)1T^Ck^jIAlz=sz5UyXK}MOV4oM>+B_tKS#oNxms1*#mWfg7qwbr; zm}c-k6L(GY=YgXuRI$%WaW~-RC`Ks8IJ#gWp02a>n1U8#s2WetjYV^V91NZRr5?Nd zzQ)ooL~n@kbj%FAh6a!YW~Mme2VcZ|pz?;7m)tZk6yM||K*D_D;mnT=DCJb`Lsw0a z8fHjU-&=k7x}#sPicvEMKRp}I!@fPZQydX(oG>v|C{pMMmlnR}{R;bNPW;LPzC`14;ZLdAwQh0YAguQ5IuXELigZ zX`Qf8TYX+{kP-xCl%V6`A4b`a_!OMpF)59c02p`t6pT-e-lxPK5o46ssYju0PGgm$ zk+@J1tsC_CgG;vbkRMkMq3S1k24-~Rv^whMF=J2}7adBFC@9hkmV4|@FCcy;$)iA@ zQGoS~%tfdKx+w8GqGXx?k=PUYb&?*aC^iWaZ8Z^s9V7uFVOE$>t)F8-#5Cu@{U7im zN+8uP%PD@WlFg404j}I-HlXa;JUqq(Ams`2Ogw~xQ>rEsk~WfGS+1GzW84DX4g{VQ z-t@+GqrPckz1U6aa&^<$w|@TH8wbtNd&Jw6H|2xv^Dm86r>jq>E7f`Zm|VMix4QWa zK0i%oOhNe2-SDpsiWGSO3206hgiK!8EyD=`+bP=+fnl?uzc$2SN@lkNc)%E-984bE z!^98Z7{AaKlBf&rvMfQ;_m-Rf&?;7QcZeyd{#|_=XYGy@;QruPVHw%1FH2^fSY2b$ zrl(l{XP(~h93bUZp(t}L>!Q_bC+4W$rmi~w8#{ac(j`G`x&Yq28p};J+#riVej!Xl z2x8#NsLG780|5j9_yoi&_;4JfthQOQiMjy(JE1{m3;HkO%oNyzlE++>bj1wU;s$lI zx{0m3<8EX+SlK7)dyn6C_kz2ZiKWpa;=;0{4<0;$gSu2)JaqJp(}+8Bd=#LRD1?s! z$|U{&NhKHY(_sNPF{z5jlWPlw1R=+k?sOvP-Rblj{ILD{Q4YPj0RX{?)S(&OndM({CtqInisy==F~PCR^2GtabP=>PvUt(b?#z*gE>iSL&xt z0z3nsi=`*_S59p3{Y89|-NhcNNGVV+I7+<(ADugRSoDnggZdGhdK)WZ;j%%6hmKP; z%sR~cA=q&o7)2IpV&_YQEbVi`a+dD%!LKK!d(*u&4e9Bqh@Dmgo0Ao(c2+oI5(xdu zp%8!M0(@L%BP|H<<{%otN+L$PU6^8FD&;NjMjMOYHpBDfR0yV}81LE17+b*09@v z0|8cP8nb>H;6-fVV)`{d5^`M#O+YLeKa1eaA;nr6aVmICEn>9JMV;!okvIG$Me=X> zOkBNN-Tp}QVYW=2Do$I0qbjHIE=>a97#|A9_+X$jL1{!kUC^TQ6@-sDfaOe8givkC z;{v3!9p|y4*bsANmzmRHHQCY6---M@Q$at#(9@X2kA7lr;9u;8_ya1dJ_u}v(d;dC zH;#`l@v|GRN3)J%S1~jCIexy0?iQ<}2l-ELF&S$?aVcSV8VXR2DKFpRq4)`B8r)GqGPc)*UA#oA@B&93#_76eEq_@NR zM|MFi!$<3jd>%Jjs2&oIHv|hZn*|jIj8=;Q-a)|xOoUj6NGNF*_;ryWwx*!_d2FEC zi~YB{QLQ5E19%ek<-@DbX&*rjmX~k}tB9mZi2o#k&tq{r;Q(+tEH)zy=0Fq0^Emla z)~rtZnixb(71pF!u`JL$)pu0C&KmLf9TR$%mUgJ^?3e1KISB52=$WkZ-VJO%vYPme zDh=@52~Qkvr}wIK@lN$NdddV$dYt&*7g}6DKU0l`HYL4M#YG_XLxo`?2^^5bvE$Ee1D31g&<%k|-$(->o)u@o>}*5ynzR3Ud(AHk58aYic5Ifao3cp56P;b|k#I^rGRy~szLhzl#5 z3C~hNI&i^#4wDIJGN|w7w%M|rLYm*BP6CLf|PV0nB0;+h2(ZQ@q z>x6S-H0JIPG%yG0DL8<9QaHX>S{jJpZBEb^5qS|Y>=JFkBE zT~OlKM+&mo7a+zx?c2QiJX@zxpON;Wl|02zyFl_V70SeR6wzUl83>U$fUZ_Hk4o3S zhzG>JjiKM>V@$KPA8kl{SU7btdq%2zsB2%)yhzD&krs=1VLL+9Y`>etKheGtXObT6 zF@`p%XMa1_{OENFb4ndR1w&2u8pB8GA>9kJib}nx>u!LRgE?y&P?gVWMIBD7!{n-I zFwvM3EmH}cPuuV1S&-3a_!TkXMqGKEiNC6z=y&Q`xnk_Ne|!x2N*%aiqq-IwCMtHj zO1-E{UP>`~V!>k}L`WbXHw9VYZF)|Wp}x?)-|bq0w- z=uNCM26}yTITJ2i_(d(n+zcBxcFEF1l1yiTxOKzE7hc3U!23is=CDGbJc_NLkXvY5 z2o&^Sml|QI1r{7xZyiSTicTMzm){d$d_H15U`H_>7gcxk44%Gj+}NYX4$*TlH~MpF zSJi++?ScHjpOz@1v__zeO6^>*Q8Q`!Yln?|) zkxs?Ug1WZF)_-`<*2kyZW>JT;ji!mCXD=Pv@3oO|+X?EA-d^VhE?97A?j2o^hKs>D zzEnR^kI`(v%SrepZg|(A1CnlKf_R+8b*oG#@bH{Y8-n&ot#Tl1i_jqT{_(l_Q=JMy z;rSYtS2>w2TO>*-o78VFe5(GMc90h7a5{7S^DGNSb4N{|I_jorQ%3=6^Q`*8#nW_@ zsDuA`Rz0Zx^6YcZJ^So48%Zm{mz;?eBwY%%os&e-?Y0{XRt6(6WHlBLVc1FnwzLaE z4kUY%!%AD5Tp53+Nm2bNoH`**jiOL|1jVB&^V6Lv2%JL^ll*jRR+hC-Lkb+4H3-hn!ne~WIDZc#1CgNxL?J&CA?!`BCxlhXtXNURNXQgwg z&mPOlrc?R{z6ZdUlASIXol_BnB1tKBa3Z@M_|aCJlup6>zia~91)6<9FKZZce^w$~ zPh6^gtDb_3FND~g%@fDZaIk08Ywc6U4*2Vs2fZu|h{aYctL8+v+vgoxI4`I5w|#YK zg=di}gpz@ET#gZ-mODYf!9=%RGK2wYLu<+Ph#B)&9 z1v-B#(cwx@$H4%=V<4=Uvs_R%VG~0lS#Nj<6>BvCMWllV#aQwmvSn>qiB?_VmO?4i zPU6&*Urj2gRD7<5fEs@A;`eIiwoy0Uwdjp2WL1rKvl}?$<{Xmu+XZelC{l>By&zGm z8xb0*c9fp7rr6Cmr4e7s`K8n5Fb1G7b9tRurp~^dZ#TLO&Dt)LU=MV?rWG?z3@X(bl^+rn?rr#g8bW}YerZJBy$|G56^jq4I_)0|45PAr@7b!1>WO4v}%gs$pEc1SpfsAkmi6A7!$fJzyZ`b@$we|#?gbch{l zcgH8)a#-^5_tfv0-xJOg^Q&0b+{np}HzL$x=Pymdd}h7c zk8=X!muB=Ukip%H#Xg(wtKo#g+`M8XaMw^UKuKt^y(PjlE>de?H z>9{^Y@ri1F64ks!4O!IwvWcktWw2W$8!!>OQjuPI(7rPLIohxd`sg?Cxr1NhbL~a4 zVVyRMvB?x^E~O{=TqX(G5qrxgfGDnbfIhFW2gIhA{ddcG4(QX(^+stUM_8oaKGp}|VK(G#CAFVe+sH7j11Ao+md zDH{+G;s6bKVAMxgh#&Nzkom!A1a7O{YqeXGJT{v<$%Jo%L!hKxbWy{`ZSG}4@A#UK zI2Y?Qw+-QMp4*%2)4QHurT5>L8xW@gwDhGa^>ljxtMo4^q5s>nKowmr5sNc_%0!vr zIrw$z7!B$+^ ztDoNR_^OSN&Lv@H(wwP(;5C4)F#`xIv@3E_9g!JwmLe%4l@$A*z2i;M#^kSNsOo6uLH@ z1LWo*=zU(;ZL$%MR)vVR9>VBIX`3$X%iFi_h1gev!QzB++7l95FjyGQ2#0%AWMxH) zO4HIh<^>U7n~XZCZX>$CzpN|l6Ig@&WO?SkQ|Fspji7~U`4ZGck)9PKNbuT&sFDb0 zK`w+*&mXNRRb;3f7z{3PHSymmHWe)bYe z|6M`c#3Hy?wyoDFM9~+tjX!{^3OE$)lu2m2W&J^M-5(blq>+G5Wr_jFM*u2xHH-iU zn7~wIxQNSeT@q3vV7?+;bFfg8D^8Q9cuil1r4yGm9{V2XHAtDq?db0qu~D+1j-y*Z zRtzc7g4^u&cm*>8109)`49%dW6^P|xJlD)(Dj8&Uq{ozJ`CMYpP926a38~OT%J|16b6r2NwenBK1*S+PQz8r>%b zqhGUK+to`<*)9PgZyO=x!OqL;*yjp!BAvaifQ@h}EiPAfMye#HioUG0v_Qa@m!Fgs z${O5Y38lNz($fYv*r63A13J%J*APe+ls_wMPo>sLtRZ(Ucnu-Cx;Y^?e?ejYRQuA#d3qx%`QwMaett$;ZW@39 zix9}}C_>3QM2K@H*1z=o`F621|@Y^rN;DvtP~ATW%|4bT`h ziyS|vG}AC29ma_D;iH88hX;ol5Qf05EC`G!i{+{z!>6j829H2++@Wk@Ahtvo4dy zes}h$dbm>$qVMkTqbxM+#g2I(QjNnkH#aRaC+JT#+gz?3E5yE>oWekQx+yiaz!nIY zla=(0^uY~Mh9hHshG>eg~*f9UR8U-(7cU$|tJEZ({(m-YO4&xTRGZj%o#y=PmvB((kK4oyNwX8CS=AirYU zPb@h2o6In{L|3eSI_5z`7HKOCkFF{2x_FPRc2;sZhn4to7Sz< zvZY`W(gk!z!jBIy0&Q6OI`iRZXFLY1>1)Ji5|NSOX+UI^LL3qum>3(;yOup}$mB-? zJNMEPD_-8dZskt3xJ#d&ojdpJ(m}SXEg#QeSlKo0mDSWR24{HtcukN5{*8uN7J|~ zE5*Ay)hb7Y~<@VjrruYBm3u$AV zY1-*mq`mj|@2c*~--LC7_GdhYT}m}W30-$&q}b_6@iG($hV{ajmEz6wdW#VO-8vj7 zOb_52=}=a%PYG^k#-pDx0us&mFlcw;JGNRl;`MAy9i|(`!?2s61QGl}5n`l(c@j{q z64y>XqV7^fd$M|-)v!zMWM;WvobTK9MW;uzXSNH*6;N|H@Zhtnl_ZMGyR?vj!On>#X5 zgDF(V$&R33lrENoF1uZ(7)z4-bxP!da`T#znCaXXvn1*cNvidXk%gHQ4xr|9xyMtE zUsYj=&D-?0*zSPX^%Es{glMvo zvJy!4ocEWz(7o8nplu?actgM>-hwS-bcu7G_;JyF=U1%yd2!?0 zr5gt?e0fmys1wV}o*wr6?cwFj@WkJm9(YiVKBKO!=so_f!Zmk@_cLEb_nGQx^!=)) zZrL6!sa{o--s;(f;Dr2yH#j4iaX-&qu4=oH=HB}wM{w~`kb_A&haEOG+l{zT zA=?OqzZ`1@{6bdQ=X3OF@EPUg#2m$#>0Cd3!F%~hgtR5v!|mL}iHH#yU3leYW$r3| z4udhtqn=kk*>m8d6~Fy;e0^Yh<>Ny)Z~XSh==`ypvg~ygy=U~5Rw0=&^3BIbwzA4K zg=Z=|FvoE9-;I^b`;T_*CjHm6RYV&d5WfICC`7~93I9lhl5at@fECCO4kr&`bt{Z$ znM9oCPJ)#}v0xzv5ymb;yUWk(z+Pn|*{;ha;&{+}S2K@xt7ocs;S)s{m*q+VQ zt#MW2p&lJR2=OhxLa}S~sQh5m#?D25ld9FK%~E&q?8e6E)Tj-{CngLNN6Q_gt~j;+ z*j9uBZB&j8cjh+zBsVIbLb|DpBqP~dF&Gh)AyHBbLhCRI%mkm3#^dAsP?x~?bQ{79 zEW*Re#Z@n>=eMz5huOC$?c(Rhq6ZC=NPe2m<{GNxFf_4D$WL{st{nhwL^>QF`Iw_t zMNYRt3S?(z<>W{{AY8S|LRuhJor?j)qezAZZz2-BVy(%*OguMVJ6ibpNc$hsktP;G zB+51tBY^y5sM@)B+uV-J2Q1z3(gWLO%-i(93yq70)#VK=Yu~GvIN_Q>1BbWo*;_pP z;Qnp3*X>&U@S9sVzoLG%xMz>rPM!KP)1oB5<%n`lEvk@#Z*QVK#45f7JSfmQ|W3i%*>szGR6xg|Lz zM(8AR;ZH=TUweM$KcvO?sI^aP9$J0XjSrSlIqe9Hz7RBsUFg$GBRRksdcPqFpt z+4?t5Za%?+L*F{F`6TuPyL2?$gqUxfwu7oJkLTb z)eJAatPqBb{BAq^Tq1q6XHf7e3*o^=6;wK5E^K# zmAzzgCe0I)ZMnD+9Z|ok8@63h(28&K5~7bnu|oU|=dcwP#4I2rx)5e<^9RhHOvxV7 zm`02a(3X}d%tMk5&JYe(ya76^7dwcD za0;g26wHBz%^L_vo*=-`Om@JvN~viOQ-O&DqEwQ788*zY7LiEIh_-!fU(jpqZ>=|Q zd+O{Ie4W(dY-2uQ2^uTe(ue;3`pZv_E?ZQ!<(ffV+fT;ftFCpnm*=louxwqsH?vwT z>>6gF&ZLGMh3zQghGHkJu_{ ztdZ6Vyd4Xa3rSNCa%Os%C*k*>`1_hC_lw~kf8Uv6&1|T-^=@@j$1a^Z+|^T>{P3nX zo?z=YtgpEHnxc{i)boA1R`#6Gy`J`HN37s+%pK4#BS_E^kW>eW!U%ChlrjWbGMW;- zD>OM|Ujt9}vDK_ztrgd*Z=i)8yH-RC!F*_(C%FtrSmC`RA&=sde7RClZV|L}XNJXT zX;Xq=@2sqXg4Co?HjZhY5Eh&FX8uIWLaW0~FSHKESb=WBQ6UADTR3sr<|}~l!33a= zGuDVLTDqx6|9;)WZ#?$Y%YCkyztwwHhmM^V-8{3XxLsaeSu4Y#Ipe#IE^5`eZ|j*W z9=NUBgflmbKoWF?a38WZYh@gOV zESzIaPX}=YyqTsyUNn%nzG8Y*O_(npH$p(Iw^Vd*-?6H9Pq|!ebnNj@TR7^`g-bRc3-{?()vaq$k0Iz!y?U2%ui+d{0W10w zfCiljxjP@)XbBJ|tAJwI6*lNTh-17~m?+#T+#xJs*2v;Wr?v)%qg&@v!B$s))3j+f z+%RdE-2C0n3ZVXnpN?OBjxMzy{B?*GfYc@sy^oH=RI ztXUI>_Ukus;t1RDL4y|EI%0&;?Y0%C2T|hH=1MY_aE z25;js{TFM9-sYPdI)g?_+6~(OAY#}a!@k@KvPCk~=zxF$3m&YJAZmwNfTxI zYx+$h0bQ@4>-f>l?tEPhFqM#XJ(nU8VgdY0IP8g8)quWF8#au3Q5D2e(7acvXC-eM zK45Jp|0Ya*(_nvVabODsxubji+#Rj^0YRsJGPxX^2proZE{+bbgU`O9nMC!ODhTvoi|>7owc31 zckfj7AA5fjS;@Z1llQ4d=?RKDb?T)}P-H~rxYTj-WVR8{uA#>?mN4fW=0G_xXWwOO z*DiZx&FbZEzrFv)9z#ldn&hOO?FTimQQ2A9>0hia%B@i^S;m-#vPaZguD=QVpkCc; z+>Db|LKIjl;ENQxbCHmrk>LsitS+krh?Sz&X^J(V1b|mrP>}6LxLP*85#v%)634&B zn!)U&a|Bv%T~@>uyoG&cmJGxdI0GO}F#ySzuK*Gfd=zb^vq?o#r7ey1jYFmHT6Y`U z_tj?x?Cvvo-SDnmN~`NTruOOGy>E4o>RyVsacJW;(sP$f%DR;fzH`{()$LntA9z(s zMZe0P(`q`ZXS-JS?Gou*twrXDrz!G6ujkjF0AgB1Ug$n(pbZ=G4q3d;7@kxLNe2>U zMLMHAd3K7cow?LnDz$=$tSD{T6u1g1F*{Z5(@^vwEv=osonUSyv_b%eU@t92AVw+E zYMEaVVF?p9kvz`{&~^pi0A#?R>oi-q16(Pluoway(vO&_e!A)NrgNu?{Jb2^6exJg zebQ(C`)}^p`v|)rs&A5P*|B6+^$2x8tv23~cANAe!pTGShOKbgz^x1QJ z+IP5R!PiB_0D)Tj%*KlGMXl1(cMcsntm{2}`VIK%*UXT3>(K|EdP6;_o+Jb{d>ItO zTaa0LN3xO4BLEtcK&AsQ%lMrh5AvG4NUJqj43^pk17(ZxNE8SZ7+edvovzR*yGUI9 zA$q{%LyKl1abB0(#?8F`>h7(B1r;ehc2=tIt3ftUs=xP_ZQWB(*^2USP}e>fJtme& zi?LSas1HUNK3-&JOo~)klAVF%K#DKLB!$CSStbDdnA`wjXqAMLS)q_2DcNaFLZDd^ z1k${81G1O|Lkz+N%ffrCEl^DBX{KYHUGc&2P)s^5U}J*%13aVOeR`^^dTFcjt*UlCRUTdz$ zST5WVub?1AH*qWjj)jg2Sl2Qw3wLOAliabnIyJ82gH289EwFTVK;|9CAjkb9qQBt{ z=uy#4VjZMt^6?__1MXb{_jjQDE64Tc(j(Uz-jAKG8h!c`k^RNG-y!>}t0rAhd;-{G z@;Erz4&d}mLC&_{=MSdXWLT?=sc8rlksT>AyzU6~DEoN7W{>3$-q+zDWh8_XrWSM5~1_!VDfWTE$!PYw>Y~Z}mU+ByAC+JrS@(nco%0x)3n%>p?{s4L(ycPM~%5iX652VWss%mI; zBhypKbR;EFN?L{+DIow#L_T9u#4JlFVHe9_O!jsFMDhv1`yRgiI#z7Yd2nv$%g1)Vg3SGgUfCnBM*`yt^>%g- zn@pAJ4s|}}f8k)+U;p{bMRt~*`>nAJdXMN$!(oHMWvnpu9(gMPs=kL52LyVCeMx@Q z-Lqu%X>dd=PAR21Q22lCeRgyCIrJZ?fz5DdU<(X6Ape0G{KDPHW|dHGZUrlLq+avj z_;!t#y4$`uCll2ZegW;>M+Au zlU{ys-9xoQKYB+z5uHJppQ3%HfBCKcwVTHH8jmzJHTvZf>NU{P5Sexf=P9oILq5^u z;#X!}zMHOG{*QdTDIM+>R35twi@m@aPsnen>y!=H1>TnpsLNz^iO`%6zK_Y}24%0& z7)COjcGAIZ3lTwGx8AZf(66#pcDI_0@r4iEZ#c5Hu+MT^d2UvAV3Q?jDsNXEtmZb& z!-;Kr!6>3dEL6MlGQR5@Pi)*+KX{}1^~#lf>NH*o)G4Y2R=_!BkEYwT*gJ15mJr+) zm=%QIL`hQ^p-`{g5wE05xv>cq$Auox5w8{F^|sbgz8!I6o&~1}J#3s8YdF+6Nx=1i;lI@6@0qJjc{+qM=Fsrt~7?ho!;yh0t*aOa4 zEt81OD?N~=<&i~yVM4h~K_rXQl`;%9J^?&3m`AnOsBft|%)M^HkAj;7qBv&Xpym(n zIVrNOAB={D@K*iv*6p>mTW>{j`^&75*=qjYeNxYB^Ar#_EdxSOi`^{ZxU*=^uDv#%;YUL5-Qzb~u5_F@mHxAtP@%b%aeEI^f2C|@R7 zxH?jpjIb>fhY6r`sxJwYVX?TF3#MO~C4&L8CCTr@1&4uX9`GdbY(*|vXalAbfL@X8 z$;FEhfjc9vq6$iT9DdXo0%GYh;KWAug={8gr^)l#uw7kDW3OZF-u;JqZUfTeqVq@J zHRKUk`6dCEbPZe1vek#9|9+p%Qx}4d;0xJnlmV6^3;?o@+ix(WIT%zd3u4+~+k^0f zq=OWI>LBmhlq8st$sfb8Lhnjo-G`T-q8Z4DLh>H|=^MZo2L*zS1ww@n5z~A-gvAOC z=m5F>O_)1aJm;v3#}hu#Kza0M1P~;T{_4H=zG_^}A%e7i%7%ROGYEc?=L)zDhExX& z1gM`W)K6qRA&eW*y^bU#1R;()mW1;TaXuc5@W)+@B?W0+j0K&Ga_dpDbAD}WI?!G;pB||4aqWd zc##etg4@q6x!hJ6ld9vPaWj=BU^csAG!fbb^cs-8ZmQH!(Ih<|1v&n)C=uY$j)|^L z`p4!Q_uew@;A~|2KN0+Z()^FNW_PfhuTG90zT=vw|KSx!i?d()xFDCqq}8#`dYXSS zyJ~D>{#9GoV>Kv~CLP%gg!Eq=aAx=cVuq+hVE@9Pttg=+UQgR&W!W&lrBj1FWy zrZs0e{MleQX@F)(+{{T#siBQaQZvb&*s~CGVXPPwqE^LIE$QyEI zGN3{Oal#m$m94m7AJ6o_`-3t*!*LSG?t&A@$PUIl*!hqsNu2K8qxgroaGvmh0v;4l z>O(fmwnJ0(@20<{ACl|EGC6W$k?4M%HVq6Nyj7}qf= zvb#G&bNB@`IlD)*D0z8MO_8q(In@eXaI-iI@-zjTBezXtxZ&BuajGns{gH!(k~`oZ z;hkuhEhUiVsZ9rq1G1cuAfrz?>V-#;o>-i|=N~UkFpb1^7&H9+49xKN$V)`&D(-wg zHPf*PYI>^E>EQ;@l&|?V6vwzWVgHc8jC&!CFHiRLqtcW$*M_5ccFnEGxw&4O*MnJC z$r(rIK=LsxNMnZ!XF^@B%v`t2>GHz8M7a}qWajxzb8H<0qs=eLJ9B8vu^5<9K+wca zr=d|iMaX8I*Iz%@e~bR-m-IIfu7%2Eqk` z-8@#AL9m|YL-V^f*&k!cFG7_7$ybo+c4rql9NsK%hNYlDLU2S0RPkbXgKR~%B8VEq zu;u3ZJbsIRcv}J0eo=hcun+f*BEvPzU4%IvhMBG(qauk;KgQ^Ikf{&~ppq`(Me-sZ zjqO#)xauuOepNc$4b5E<-tzGJ9$T-~*I51f%GF!Duh;i43y&V4zcF}B^)l3lL5`(; zPdrm8-dVd=udRCV5xu8adBs$B`_1wK_q1jD3T2t-PGiOy1k2~Z=KpleILgy8<{`$I zT^KVhy8mB|IZ^IgRK0w>{(&W~zu&f`=2BgsRB%Q_Ki1qUcaoU7Q{N!QE&pwqm@{jZ zzOL-I%k(WGG`xSN-dF5Z2e#_($&Y@79SZT~9ALQ=>q$WReR2$Rr-IUo%uK1EpbXI; z`Mz>^JQ25~mX*Pv<1IxNfGQTwm4PZ0jB!>tD~7en#l?8mSBM0(!`m{j+GJ$d%Wyu+ ziJ*QI{iHH7#I-E0Q%hu53J^%@XpjJ`UVPD+6zCd1{EGnOq!(LKgOPuYB!oQj&bk;< zcY>wm0s59-rH%G|V&96GxjgOo7bJ3g7-kF{Z$s{SbH=tN&&7<KSuBg!E`nX;a< zoH1@f*`X)`_`aY#r;OSb7yw}VfO3$a4}$?Dy&+4CX@W&?q-k-b%|XJbO4&zN_73S* z&}ZWLTX#Qo-|mCRfArrIri9nE&D?N9iF;i0li%%l_yQ_oGJafQ+voODBInL^@B-Jvtrkkd<_Dv>p zYifq~?KPkma{V{Oo8m*-nwq?W2M>_Q%{;VCN}gpO;4Y~g)K*g94HXP(D=!a)ybY+@ zVIE(OVb#UN@|?#CUZ-itZ0AL|+%0`TH&{Doe*GWMJ6rw|*uL__SESuahAN+)dES>L zLR=6OQ@^YwR?$3q$d%V!G;`%VoYDT_;tPhhojann+iyy=G4X*?`WqgAD!$~7m2g+Gp)Vlf#<#LdA_H%-}_9V z{9*o6ovc-J#7g~&6A%6I`JD%p_aA-q_fHs>Dho1?AfCYoe;abN=2Pl96#7Mm&Z0aV zsm{xTp$Zj_V5Wi*C3T+tmpui0fvwQfw1En7ZJqnt#WDp0Rr|*m%+J>QxaLlsGT$X$ z%AV8JDs=;rc1xGypS*Fw{P_!r;_=VAh3)D6C`Lq8?b&edAVrqm2v^73MA@>!{+(z4z@s5}bNv-WRD*1!VzD0JHHqP*6xHE&ByxO~i| zgJPCFgD*RN0>?lWZd!ZQ!?NSyjYC66k-wOGWjSP-4qG3ps-X;wB}1U@Ms_x$!6ZZ| zcs0~`bE1NQ(}mz#bjdjNd)iJ>#v0y#oBg333p&~NjVQcQb<1MIW}iE(r8ZO+^TWu0 z02}X{9vCt23NiMkS&cj)E3>mdF|-Uq#j!OAEk_VKJV zp0OOn*XS9uuouy=?o)4sJ)8W*4btpnA`^-^#cCr_Kt@KlFw%$%sav49I8s(OtgXya z0Aovm7Y}(bV7DjBGrTRU&_QF4nvMt-}-j&R$aCY5$YH3wf)a)1MT>kVtQU z7QPNx|`wXpxYGt$Wo zNQE{#SkJOi41c>I)0S28mT2KQ89t(WlIG-i&$J!b+R0Q5hNKx8y7-hC37aP2hdNt~ z!JDKtFFtvVt-Gxe+HN&6`_y;?rTL*O)T_X@r@UN}Y7jvk4urBoNHp)pk=N3EJBo)| z6-2%FjUC{nyKljP4$BS`0rtLSr!tvfWA zzXlduR;+)7-F$*{%M}T#>7P6Pi9ftRI0ud{Mu;df~!K zq@EfCqF5H}6|L(Z)UVZ_d*x_VO-V`35ZJJ88a{L=QWH>KzjaoRWhX{ii%iRPN{QE% zmtm`{tf}Gbe)Ty{XI-eW#sz1lS4+BFC52qJ1a%5&Ysce6(i(H1okUT`NKt^0=sXzW znuNRz=6I}b1b@&#*}RM0Dm`GcdcONCqouj~;EWHB{_QjG+*$q)+fS^#*W0~&ZJ&a3 zMvOd5>(je=p!W{B@reFmu&GDS=8&lR_!|)@A2q5%fB!4}XrEARd93vDE3baAIC4f~ zb3bFXa`blGh+3tCr8a3(a^$cPy?c!wk&Lypj2Mxl78kk0u(*bclt3h+s^ej89fuEw zoi}Xg(ERhx>peIg@7}w2_wN0>nqTX}!DJ@`tb{V!5C9z}Sl-ss(FaHZ;}^|Hhp6t* z+xR|A^#A=D;vNjq{qNXkn-gT}A@i()szf375Tjx_$GD@^G^LP+$-F7vKymMwX*S}H z?REFalo5CKj?u#(OB->|-q33-8*v}qH2Ik!L!UYS{_Qs}aPR!hjA(vCZRW1Nb1&*K zfAOkTU4P>0c(SUls&#PdXg2aj`lO7!gGUW*O&NLnMA*oCO#goVh12E=&rcuysPucO zIh+;i**N9W=3sqLe`4Yd_A%K#O1vI-K~Yl=9FJ$ul5MYj6n5!JoFUts95t||DL%ZV zwqL)N7A273sP-1)aEU|7&dUn~Mx%!GImtSFbmqu22M)B2tiw-ZQ&VGOPg}A$BclN6 zN(Z%-+1%BVAG9lJgW7_SZhfP*zra>Oo}0W56tjS{9gH;tEx(Si6uzuvJcqs9u$>!~ zae$cSCdy(7Wg0jFi>@1{MFYPWC@{XDEKSl>+AfP5&-mJoDJdv7)(cJe(V=MkS(mHJ;IU zS2Qv5|I7n$bPN%z^=n46qeGt8wtWWvZReR~pNDlbY*97R>SVvdi~=eoFKI&;czfeiX&ygV2xiDF0G)z@P=SkV3nX5#5}Q$ zsS^#82*UrQCz^f{)=bRl#8w9a2$oRR)0)XoQlg{^wXvt9%gl*Q`gHhBs+@57Ke$%( zJz)2FJ=Tm_lSTa15A=^$t(QZi5{(-g`Tvnvf3KN$Sz$9I#G>}wa{Kh{>AzE4FCzL4 z?I*v4>b}CddF=M-__uv5>7CHexF$+2M`O4*MXSxObBjKennTB>>S(O1*PKRs^myW-v+PqgX>eW{8kWW?8h z{#wuVYV9)m0j-EL75S+juyQ)G9l4M@IsQT$@-iVq5p-V?Dtu1!m;DIR`p!NENCRUZ zhzyeBPQWK(q$Q$~Vk;Lfzeaz{?ZujIr;J3XC-(c_Z`@wh4nHAcvQPeuy3>@c+Ox~9 z`TW_Gks3k@0Yg|VtoAA;dD&($Zu9cZqWf9;%lL!dwbQap*$1uIEg_a81GU7FdBOwVGa{=a z2V(C1^j2m~yqVYRrg*FzB92_EVy&&Y+ZnMr;-ETZPIGt5d$qB_XDphuuzL%&{G;Vv zixYk_zl6wgH4};sCKCseGo{Gu;B&HWi|!m*9wo^L%Y{E+tZ4|xYZ7wns>SnrTr{`u zuFTqolCy?f_mtbZv8q1Uyy$|)p7Fer#9m2=H!ORREn_V9NtH>LQ-L+w;qd~%?1w_> zuN%x@j9@>_9YvgFBNzmIp_IwZ^1Q*V2m=||c;!>)+Q#;1Dl9-A!m=LDF}5|6QAP-F zIEXjMsW&K2iaqh*lp|tKaCR;dd!3leoFjh2sf(~8?^@A~LQQD-w6d(t>{;g3w1UDW zlC=)lmG&S?bR9Ze0KKzW8i;l9eC)_KB!`TQ*R|Buv$OaDANeF9yyT_kd+Ppq#EHIBO|^;>yA zb(Q+9=gk~fS6AKbrRfv+(U}H@SJ;P$(-3M0{Qon&)lmsd9T z@b;+8w$(*#B{?NIuv`SX#qvtrIfh85+_P4GZt(tohgTjS*Z;*4hgVv@KJ)R*r^o|dIIi%;-RlP|8#YB7 zWqEf%>D9q0T4-FO@!S@C>(5u~<wk&cME5cXR8I>AbvP=rP$VMD zqDfv)W~jWNB-bcs@|Wlv$k>4uFlI)`AdiEo?eW4$*G8tHbdeLRgl3@=L+nuzLg;u2 z(NXtAwC>QiK9{O~Vp-hjM9hWLGUa8+x6k!Zj*o61CbpS1QS9qd2W5^Sas^g+eV(lq z=WjHr45P#O-7*vdL%~>=1;GO-8=GmPf!VR4DlbD-%cPQ>Y0+G6e?%bpz6 z#==VOLBv63p#?D#N>(;jcPZO~pG>!siA5ffalE)1syXkc4G%xbDJE^+HBod#Dq4av zJ0Kak87hGqowfQq=|W0t)`(`K3WBv%-^h^?<@%je%nPNIWSr(iPEd~L$j7cfY|BLs z-$I8aHy7b1t^&IzQKnSHNjPvqO_E%)3xN_YKYY}w*eeLsUyYXVQY<=tP`$zknh2y5 z-fcvL1VT7c`9n7W$KN!&x?02U6FOVRG(xPNf#c%Q9^t9It z8x}IxSRmtzQJpX|vj_*wGNfF;$LIDT>2#sniIBn!H?p_kz+0vh6O4XC=D!w2dumENv(%hsBxPRmeFJOF%{#7H!M6^Cym7zi`YYtKg)1Td2a{ zK5$)bj}4>3i&xyJe7o{MpXKv6`#HUY-XxEjx2S2{oSB&WO-3$fNX2StWwKvRxxd0& z=|e&KqF_*ix_|=pMT!a;W)GKFmZDC5ju#akgB8Kjylfm$#woRIc>i(EvUG48GRi_L z!?>W6F|+^5_%Il#%DisV=uD>yjS$&Y16-<>lCc=uI3BTr9S3Q0=>aRYee>OJ{jFoQ z?&kY1eC5M+lkUAZe&>Rj^6X1B&-8~z7$?Ip-jU_4oRrP0KD@>sD@E zyQzHVMtQ}usjU}3_#kOX#33Vr*DRdJF0&&3+y!$JMd)PH31{#}W~L)63+IjzI6$Z~ z4b>f1CW9j|5MT&&Mzm(+Zn2DPznAjw>#wa@W8J0e8}#<=@@QS2inoH0l^5XqJN;Wx zrrUTc?0YVX3Hm?1l_}hKtMUS}!3;wot+&=7?fS9zj_8xb{YS(h8tZOdvQpWT5=8ve z=HNWPJ;UWH!!b;YrPPJPtGVzu!nRh#1<7!>n=Ae(r2M8jz&f|-bx-O4ghcuu@11@79?^K$+T(Z4T{~pusocQ z>4&%8bV>b^#!Hv$`)V5Wx0FU*8Zz|WC`rjcnhm|u>B#@DH$gkPxox4-RLRKmKUqpXB}7p;_? zOG_YSH~bruAOlfP4zZ$-!)IYvRtV&A!2MR-N7V`32lMd#M*PM~fXaRdCq^a&7vlOV zB^2|bnv)1E!l4E@ja-?w>}-b<=WXCTvbr2*6-1*9B9E){P}yo=tfv@ZfQD(H3>Npn z`a8S3)KhB|Y6=-pZp_kn)F)^$)+XSD`h={^ic3cFCpFWJe30;bBfu~ldHS#?LwObK z&Tu@&;kPjsKt_<(1{Qv$TR8dLsb^-zhcJrwt}$vpC@5^v{zb>^;;)a|_prQye~o0T zSGph>$+SCd*qLV|sa=*UQ`52?cmyTUTz(tUr1-!ENFAAB!y#*n;-<`j2+lGhXqj7S z$)KMUVbCA6dg5*T59+JD0Q zUASEqQ=Son+n1a;BsL;%2xm;?dNm%3h{bHVZHir{h%#06*_=+r<<3A19Hfq0&ah-; zV>S2Frh+13sjn%qLe?^~!`x@1qo88wwA4X_NC=dc4`>KH+9ZlDT(=wfy{L@FGw-gu zK>vhhaGB_}@=GeFA=Jmj)Ftf)j8(&0h57VJlamoAqP`p!w-14@R8R)NQ#rWh&O~x| z8FeP@2(W_E0pjp@GF2IeG>m9BW8pI9ktdTSp)t1*F6cJKfsT^i6hjXwdk6lb*$r5r z$gNqkRNRo7Onv1wSlz6V)vI;=i|yhEnn`))r1qaIU=<@j@K4a}a-^Bb7?MqAd29}( z#mNHF^D=x63xuG6z{V#Y)DzBf`~1k)2u+WAo#kQ;k9Nm~0B0Iyt${>0$qM66O70P1 znEj?T*p32uoqA5nUQd0W+p-Fd*s=OR#By!YUw{p0qjll$e)p=rL*Is@x`pkl#lDO5 z&6e#Xxk0^Dr;&K-Y*fd|u%aBI)9KP^VYEXpB{_|wRDLH(HrO-t89hU35m+p;=p-1njR=ji zxuk3>s#hW3oXa62je}kFBYG6}cp^|%%D7K4VRi#ON&Pf-GldQ>80gGOu^rPjNPMI} z3nu?q-}o}oWJhrxss>`pLL24lqlybu)s{TDS{7aoL5PwIMq#iFWH@D6h{|9c1z~|% zb2FIg1^tGgCjr>$$7`KVy9xbZ`}0NsmS}p~6oUv|#SEdg6QAE88A$n=sV{?*m8fiv z@})o-A=@o>lQ@o?O z4deJnt^|R2INNs2Ocv;;f3jS1vlfj&SjWgalMj+dE4>yq#6hg)8p9!-lCxB_!p&k$3)Z z?Z78aN~=v3^!AN9%8^jD9=+6Zqux$@y7=UF>(8(x5Q)*Z#-zZGDHo`r@KN*+-><8Q5ZGI32;-g zrGnO#!4HgugV<1v2rbn{g~t_@6%arVIQZKNiQ4|gJ~ zN3-SdnAW12p2?Qcx2~9S-8b+*X#cEP(rv)lGv>{lcX7V6rg+PP>v#N6S3hpp3~}PJ zXX1A4?c6aHB7v|JpNQvpKgr*+d;M0+h?T=1di?1JySH3(<#|cchv6UMinl?Wv1EN% z?#_BL`D+f7o-7SA?u$+MP4Svz;6?F2zf^l z%!EXY&~cDW2_6wwwnO#{>_SQX>OeMYUa3K{_m9K0u%G!9>q@H_`B*_|mb0>AhiKJ@ zBb(3HU}nczH}~2(SsXKDD_&0hz*;vc*^p^-$r-5Oft3WSu0SSC4|FWep6Nt6RVmvA z5=D_El#vn00!`a_67vR`p(jM99sA+bj4&;lyU0#cgR>-5f2mb36n*tQ2pijj--S3I zJ^?CM%RTy3^%>MRa8*x%3(i@>Q9_^JL+VgI!26hb}0KJEZ! zkn{!2p@bRBfR2yj=}@7NM$Bz@Q0XWuPF6tCb7ZNC8;T9Kbg3Pk*-JyXr8ZB{pTXCp z=Nb3$%Ur#YLW&hqf|kvqN`GgYz8yb1#ix1?F-G*nk+N2tqxja;Zo=*F%12TC{HUDW zUfW&@)l!9qgQ5)FV@;ZojM)+XX_ZiTm6I}CtitL>;#-f3)HyiAFdR~_ud!d^xHlM z4}SaPk+1bFmK#*LryS5XimB~~_04RSUZJlvB!QiB`MIQ_$Qv(N9Z4L~$&|5W(PVda z2+l&qCM&S9!4xGyHqa3d5(&m$h2nx!&Sp@8MrUi82vV!N`CF_<;kcgqMREa7-aunC z#KVbJtmEteAbNzPu+b?SmxPL{s0WDrW=?xH$WY5hx?~s1Kq2#sU2#HO(0sAsi+0FH zPYjz8_W_wXX+7&;40IyUq^#246L)|;AUjStbd<4czZgp~o9H1vXtkMx8ryUlCKu;? zlBk62bmse0`f^?dtnVmK4ZF!H!jaXoU)2f?zc6~h;d^kpd##0rxa?XRd$&nhu*G#Q zkAvOSu@Vmq0PE+5OW>1!s!HMB|?xg^Ya~Us$y1%Lqdo)%FdJ_;qr4O zS+@B+8kL>kGhJ9ci912Z9d9e4^nrn&AS=DxjXx3j_ zId_#fEE|(GcbbgQ$Ct8V^35pR+f<*YKZhQsYU%x}9u7+N(63>a_V4tN?55m9S_%E> z9>SzCC_nZT&Wf-0E^kG37X7V@1}qojEL3O@vnZq=++m~mUbFWodWT(zbvmfcE7d0b zByC|0fX~9HwXS+Sv|sIuYKrQQ#~g9iGbqx#Mf0uyYy6v^=?AAQ8u8F& z`fJ#E9gKxu-QB)fw#=GcR?|*rG_dkp=tQw5p|T)61zz6uc(Oo0Sy`y=CK-iAX}i@4 zGZ5%h=f_aj%{MEzuKw-AbeMA1&hs$f&8u7VVo=IJDk`W?CQhOXPe-BCmcw^(VKRoK zIk~XX1d%zXMx#K7a9O2PQGi25RqmW*CiWSnnHiaRiXAyCC@)_dg^d~_9CjvH84#kj zA5_CWnGUKU8Zy+8s%Ry$TT{vbg|HK+49Ym(5#y@W8l3}0jxBq6JZPD6y%;ukx&HBX zq&~d5xbFiGHhtyrP7YUzsVJ{JL5x5CPS$_ke&0T){OPW5Cl1uV8romr6!-N@FKyFW zO2(o@?ius1huy{zn(NG*o@>)s?D+&=eQUTQR z5K%+$RNQt1E}2U-sT5f8fM&z=g`oCdLvV~q09kg+O;jt-{iMHNaC!_sM^rH9e_g4+ zyTZV=qZ-A_vrmI&qJdE^y7FwiqiXh zVF!#G*6OlAA&ws91oFyD@&>i}l`LgQTcte-zb<^M?h*uI4Z*=zV?{kJ_D`J=o{&?f zB-nv?qoiObx=2k2ip(E=@{r3wymks%tk|J{vnoXk)yMW3*zZIWeVqtMt0ii{UZX!4 z{C(E4>v)d=ZP&imz7Dqd$FPjsS>8>zqkY#5tzy zN~uajIUpbC1Evfk%id`{U|Wa69VnXDi8W$u`-_(SB63^G3wG0ef0gs|(Z^lw$+uwh z8@W;cWKSnY*j};#lOOCDDP!n@>t7flz~@*8*eMZ3Zqt+v;?gVcy(_x3lti@H0mEeo8_f2_8+#&P~hTy#1kVhHT=20AoNN{)s?AOB7 z1bKs)GE2o$(IX_9v38(ycC7y)Gm|M+INZSzb8Bx{cs98EoWJYt(a9dMrap=BWy;+g zH6j*Sc3!6o{lcwsj_$hv6m_1+G}T0sMf0pXG0WuPLezvEtBEx`7bU)6yc5{eE+hx*Zt#nFRmJT?Wikn>af6$dtCqeb|k$k@bB3!eomQTNy8=zg*6Z}cP4t} z_aiNpOQ13t$}zb;PESjlvykV@D%;_uBHuRgR@wkyEWGJ6ykMzxS9}tkSYT&zLKBCW z@Tdg#u`h;QmYjdd#q%s3H42YE{SW=CyfR_yaodgL&SS5gZ6{`nc6+EI-(jgvA@$!h zR(BwjxSx35#AvFYWUn>?lhXFte`T?L7js2@8lDVwSga9Ag@B`f-)Q~IP8q#1XbsmX zyLF1lsA%}vc8WWHK~g+1#Fv<& zUu;gSg)kDl^N+4u6Mc-lQ`C0dmw=kEE3s^1YC>ONy{0WmMjkdN=9Waomc$uQv&fup ztZ=9A3*xRQc+A96tSPl2NmZ{tp?~w)sRgX{dGh?jW({kmA4fT6B@bu%M<;9Yqzt63 zR;(Tb_!W4vP_qJVV5AarhjQc$*@gwh10m)yPptE1mQ@VHu-+M8SdyV&LX343upk$R z5h2#>4S>D^`lbvoYTj)T<7~*0vBjjX50I`Krru$eW%~V#+Q*_!#r?>YVFbJFY`jYN zjFbg)IX~UP?M-TCvTQ>#`Pl;F>*EpmA0Ybdr4nr|Y^Y z)F`ojKnaFIG|gUwGxU)m+HB=!EZfKK=Gs@@J5bx`)jtuN|5y^sD6gt}Tx>EW+=4!D zU#vUDvAM4fJOSsH9vHrV@EzC86+0m8POlMISCK{ljgd71$v;~u z6E?XSi71dGs&hR`v_Q2axdqgT9K+`t6*-VT*GO&j+Z^-O(1KpGfG2ewuYAWoa{7 z^guJF^R(as#Js3#aX!?RA`Q_x@T%Ig{FIi8_cWCBk=G!o_NnsKET|0i#DW45m1ZI; zoT8y3)(Rb}_2nqB+w?v2*NWT+#5i${ej6f)w(9p=YO~(H{eiui?FBn62geT<&U4Px z=j!+3XOUPfR=51|z=^=FyZ>-MNmv@kV(6?kqo1_8tHpV!k5!~usMs$0DdD(yjvX!% zyQz^z5-O?7M8y+~vxn@E3lkf2qGNGQY=;BN+X-ZWb2W3&PZ*&R>Jf?T55$!c4EzM$09*;sZ9 zvkPpvI~*mjoQe~NXPsWF!d5mI*-Sq~hdUyz({|bj!CncMpUAPGib#1`Dlm%NQmA1y zv;A}BMSbKCsBiu((vr3RapIAg4?XxFZ!J^CVT&uhqEA)-{PKT%J3`p&nl8Fz`uP~5 z)E&0+F_1(B(kR4v78IbbRvGD-iV&_+DA@{N1THAZQnI{suGNaA2gRA$F-aR$)5AnW zo$f5DE~I=jaT^)8IROKzqMXv*+uL_2uj+%o`T1u3+daqsIN{@I_ilOZmCM9WV#SxQ z=u-;x5AXco@{z(;A6vcR`fGq?vYZ^Y>6m%WK_`Yw?;CvUP4Vp}JQ1*N#}ofalp==X z=stEN2#=I%=}a`Y!1(1BKy8Oj{8pv$%WW`zxeaL++8`a3qrD>w^gP|03y zMUiXMtq{$wXDKy`dLqq2g(afdh)E^?fBpbE5tQ?PH-7*yoW_lOrHPw;j2nv*`6X`T z6$Wl_!bsg|Q5w@2Zb{35SIt%eCY^M&G6dDzpJO`t+-T)agHB8glT-qobZ2^fo>~FD zHlh{KV{VFG$rp1Y(W^uijX|$}W_mU1Tc=uJdgT^CuhhaR=lrP+rZjFtnuRv#2_wlZ zX9A#paPCHySTQ?new}w6meK7S z3|qQ&*GcIFYgcHJcRKTw&5&llXdO9te(7-R(t6r$plsIb4P!X@3fRqPnPkWg+iD*F zK4bjw4G}IZN`0ELAUkaJJpND3Il>`&ex?H(5#3GE%~;Lure~C^q_6Re^C^Kis~o$% zPpwAyu;^}zM#fVc`KguCbEkPq(%se_7-wQ4L4Y`uj71O*#DEcU;_d1ziNKyJ-d zY0ukQ5z^llq}v!?xf}IQl$mlX``>ox?RUuJkeh`8Q8iY}9T=a6_}3;CXVGlrbIn2l z9b_*1^`1lRp`QD#a@q;-f9N@{Zibb^8-uSCLqJR(b_B3)1g5{Me`tE)-hc0qXwV-d zFPx}-OWrDWkrz%M@+m6Szy&AvvVMkMPhoEGNbzI=qVMc>q!yFB3S1~~nOhy0Tf{1p zOQ4HhmQu^S@yc=v1uZWV0pn<8Y=SsLlq?fX`WUzY4vpM->n-=p6bJt63%L<4lGSa~ zrcWb!p!I2i4dKcA(Nn~(|Ne*Ec>L-9{iZJvH|q6!-)!yOcgPX( z=tUP#p56~^z*?{E0Ad`=q&mtyS&~tS2s1>A!he?6P@^dIS>Uw764V>BRnzI!LYP1b zC8^vz!%AlOl)jEwnGR2BPgJ9hxLY)D4&GcNrXRm(=%DEf z{;BVI`HkMg5~KdM=Kk_s8}vtw^AY*jeQZLO&}!1z3gBEp5*nMW61b|V3@bPWhD2J~ z**FXq43-aX3tGG|Hc^J$^r#S|4opFTGZDocNhC$CWyAyFcr{0|G^Y_oBf)_pcp5Mw zoaZl(T9hBR-0}FXbIxrW0X%*A)sK6h-nLDQoxNb=U3c#nrJtb=!@MRJRwFM(m&}a&pvy;^G=L?5z$}hlaFe z*s2Sw3(K;~a$DNUadSh0o>T zOkR4mGxvx1#X=^{M21G)89C-+l}1VmCzfKuiLo{w+P`a;SoG~f58i!9)chdw(&*Sk z@#h94e|*s<-mvz89uJ96CO53fIT;?T-@ycoZG z*Y7qPXb6_SQy*e9AfeX`4rv(Fde+;(f&1iF_B$ZM$`MIWF1fTaSD7szaUy~I3RImh zD}yX8Qxx+e8ymY1@13JW#F8QCEkw?~ z*Z1#}B?L0w{9xISzRk#>GlD3bauaXE?B-MTyj+|sLC`3+v^nIxF36x*XDLs~^W~5> zkYmsB`atkbD0EI!^3YjRBhRz3Ds&+b;}%IDGQX$A4x6o*Hp;EN&pP+qvqa;OPd+;$ zw|~ZQ#|2QqmXn~Qh2Z5k_U{pL7rQrlY{A@ekF7Gi8HmZxE=0QLyu1SBxAZ~zbSU{E z2T`|9;mpf-<@q&7OPhvyCRzFK^_aV7kV;CVgm3`^?;&x!h{~;Jqucdg{`K>(WPLVl zyd0a{o=>EK$$sVFftSWmwnfY^?Oncy3@JvmM|p8kQMMoDlTq)n#04uoLU6F^LN{|- ztjNf3HD{F;-_E;lI`>74R!${SV63714`r$R4=LhMn&fAZ#_(Ch3a|Ww82+*FeKPx! z7iT{I?t5=G)`pMZpcdyZpeRV{C=uSI&Nt(k^$clXGWqw|s z(+f+1*KRM!LYOd?(0nTRVo}`|B$Tt5Gx;xiNu8vvpwUMg=cs5Zm+wGrjpuYK7I3Dh z`|HaShCbQyz}>>X@>c!N^7@JGk3&z;;Fa$-=Bq&Hp(pfbF1?Uwl&aK_J_W-ws^wxE zfQUPy(p(K^7(GOpcBcoSL>*L_QeI41#e$c^!@3e8Q6zrkuZNBqJ4`fw^VyMa&9KKb z{q1}G;0sD$4u3>XBIwB=V3m6!@Jf%zmyzLg=0Y3r`F${st1ds1g0{4|I?YihGfGEK zARSYPGqnp;d$RP_Zy7mu%rGbtpM3ePj4-Q7pXwGRCZtrmTqDzsw3*i`Ec1)dWvFy+kOzRFS_N3I&qH5`geT61$ zCitMZjPkNd%B|TH46eHV=ldQL%4Mtn_~xor?|iXz%~waZY`aQiT(Adux<1f%z5djF zPgy2k^w9VLBR*Yx_R#5LkIuYc#s!TL{hJYAy>`n}UR(at7z8M9b zb_m&%vO^d)_04#KZ0dG-I_C<+6NYINZ5wSIO0}UZwwCkmSCNep5wvHeR&?8nR4dA2 z3wFxb{VH-eZACb>oy)DIW;=zcUG&Mf(N51!?Oaad;C8xoZO1Vr-Jd1t{&ZM;sXtq7 z$I|^-VmV;8)9aLWrli|hYArVVQJjduQ8| z?%guW8|Ek*I(m0XJ6D+bA{DvpSKGP5%onN1O{cUoHr=1)>2^9SpG-?AU1idevOL|N z|8PP@X=u(4x56EM0$#urXq$6 zW6?yq_=zPktNq9a{I23ub1akAwphB*-2u^Zfp zn%8&^UMJL!nqhgLxpM;UPvKa7_?r0sVZIMrHEOaD*BV}`=@znN!g}atl%YjhiKp0z zYspJRT#FWougiF%>7Crh{wZdb0Aqt({l|PTu+&P8B2K5asp4<#84+oAj5HG%#`h2YEdTF zA63lDKeZ*`^$luCo=h!Bmo4WO(lwkgwk|CUkfs_f7>h36L9(E83j-eH7Sa{>j20l( zj6Q&Jwiqo`q({RoK&o*cNUD8~@ngJcUBqYuQq5=s-#>WTHXzlEafneU{?MfbeH2xm zGg@GJ-;ttss_ABYkLg|K`;US@Cb8^31AQU>Sk3o0VCE6vftep`-Y+$t#~3Ctf8crM zk4fCa4$luNn<2vv$!>g;`QsRmQsk%jgKM)fwk|NSmCJ3&hSLUf&DGHuTT_fDq;1?r zhx|XajRBJHU$%j&To2Gpo!SE7i+cfl85oz#Q}{A^LHOcc0AH9hY9mcGMlT3o+y;8E z!RW;)Z4kbw4Xi>jZXr#%n18BMXSBfc55lAw03J~v&iEeRN4jp@hhD%Z!h%vS125Dk zz7Jm+<70c7<%cxNjus~9&smWj5TBDKXva$M9)8QmSD>!k=cpo=finZ{UD+<2DT2Er z5`AMLrLUr_W!MVk`Vlx{Ug?AS{Ha3Jmro71A3Ez$DPLLMYdo0nw>)x2VfXz}{w>KT z>Mid{-EAwNJ)w3XsuZH?tPAmW0IC#n>T>)?E^?y9{P^?B`{!SH z$p!b%pCNiStuAUix9Nugo7P+28#;bkzrw5UXnnZ!rSWt9ZHv%*Cu-p3oA1a^W}@IS z<%W@k>_CzEiBXsQ zFxvQGWT%wY!)~wZV9S@=R;Y>oRkeYtoI#To?C&yW+vH2~dtWM-7W+%o6}A>V+%b0a zrV*nqL`Y38P6vdOK24Hvh^QP6Gk>A097SZyQC24sJ3KM^I#LkA`b7!sFbfq8GIr2N zPltUqX|0r@&gSic0X~Ss z8$aK1d&bk7f44W&didO>{>c}`hMs@kIS)Pj#C@rE*lmn=oN&o^m5H)qB)PEy`z|-M zWou4OG2Vy7#;;E_aql)*2d)mYwjvDZP2?ZIv*x68CmN&8w%KYd)U&BLXV93b`i3r@ zv8{;r^MvPSH#ot7L<9JJ4xvM>AgjNK1DuqRWtF*(#$gB+$zNRvb6Oq<+u z(8^oxyzlx(5JF|c)Fn&^bLK5mRj5RD! zl*o&{)hiLG|2RIUf3Kkl@|Nt%eUcRaBh(F$boe+q2g)5qe5@=YQ|r22bhe$6ulz z8!g$4mQ?wF-qIL-xzSQR28n$b&J)yN>=2|GLO8P!-U~N3BwrrfF{g|jjDWz|L;{6a zLn5Zg`ayWZ>noqV0~t${*0t*$wdL!d5sRV6Psggh#IhP~BYRtt($nN4tyG>rV?>)j z=u$?sx$;wPxRi4QC^xKo`Kjg9ijh2X_bAbo)~>zus3 zcZj3HA**ZGy9R2jX>@{iCYHV!T><5;fS=kYB&i6|ZH17dvZ|@AZCX&q-}$X=^eV&X zX8h_f_OpA1CbUWPK~i=ablNwEKKRQmeNQN2{ypRBMvfl6Y3%RT99jMD(WOs3C!_L% zJZJRCZn5O>mRA;!du-F?Pb^!3Z4G&^wp#k5UqN^g>vM4+2L?_Uq^q436(QtG&dVLy z=FGbyPtHOyI<>O0WJFtKP<4-JQ>#+QU}p*{40U!Rrc9kA22(y!)DP+$#AXz&F-8E7 zs3n)YZ^&);$+x@DeSPX(w`|=#Z^5>E{-fpg@i*@m{*Phyt2JGsZy!MvUTyQtg)_!{ z({}NeZav@m?QYOdE=IBh_)`&CiYziX_DVUT;A*D>4pyt*<`Y(*b!1zH&!@QTZUqD2 z;A-{?fnPgWu_5m;)d<|=)Pzll8;q5cH5M6D?TTf|WBSYO*UPty;>YxW!{W#vQ~YJ2 zexq3Ux^lybJKvAKU(xNlDjl0GAx%Y}nk<)qYZ1+uhcIs+j;pHP!LB?-=o)lSHBZe$!Re%Mwa{`%i^|-tv@h-}<|LY=p?HY5L-@-`QXO5;ob7?Ag%q zD0XY4^;JYRaTCJ46&@j8>=YiPO;VNbOr)Y*McEu zncH195*Bv&gbPNrIS3Zn65OxwBw}h^`T8BvG)S!8VzX>M zwrSgUTP?Onl^s(T)c&?P6etXOntHXyCtea?UWkl?rFE6DiTc;FHcy`8G3|Mk< zoEar0@RL@Ds$4iOSXgc!+*a-`lm@pI=D6S{^0=^C8u2LUm=qiiG-isX4mtzHX0s%P zpU8^1U~@rj0Telqk;h+6~9HV<~d=LlsGlf^gHs6f#a{p<^sjLHQ!NLIfi=AFP zwFfdjhb`3nycNqUJ~s*urN56I4u5VJBg9C|3!X4c)#)cvZ?MZfBx9c?*YZ2S&%5#F zZ?S$WlD11ieg!0M1Oro=5|ojIlMbh%t-F36a`NQKS1{#v+CeLK;5&9{04ln(CC!=I z)jfnKzUcJCWhcjXed6RMtf?$8J7x5;j%&FZSi>Ct6Q^LYk}lWD8LvwISKW z*;9!|w`1(b?9GRZf^-?K~gN-Ac7 zf92$zl6{AOrr4L`3QcUtHu^5U^KZ;X3WNV|zH@3D(pvO&6z$-tAGAMLb{O-Qp5g7V zeI85C4s19I?XvN(B<+ey;w;-$NEg>!DOsh;lM4V7kc(ESJHs9fdtp_!N&`R1(@DYYP89vEy7sIC*?q>K5!)Li~&oO+S;R_63 z;{NRAx4g{P`}q15zJ8Uj4{!?y8NR{rEry2}zRmC*hVL?bkKy|a4>SCL-}Mp0j~RZ- z@MnU;#?Zkqi=m6YB{YU!hJJ>*{AoVJVus}mD+!w-$gr00)H94QY-AW?*u=1zpFD%G zAbKzyK;som31Se9S}+X=rU5aAKRut}6owZuT*6N-J^3!4U&ioCzO$0way8$%hT*jg zS2JA0@CJVJCVui}zWy!4TN&QPa5Im38^7yOzGf_o*SLi@`99-9yu;W3&Cl@6i@)&o zR}8;l_$|NdC_ni#&%gEj7^2HsZ1rDD$^OxWH^iA#SG^%oJUllEMT~h z;mx2Hl_jdm5>;i1s!AkLRai=WfW${COH`F5stWyj748r>sVq@di6p8jQO{M0B&sS= z|5b@3stON1L6WGdL=sh%NTR9|NmNxLiK=H*qN)-}R8=C0s!AkLRf#03Dv?B0C6cJBL=sh%NTR9|NmNxLiK%{o6(mtrK@wFJBvDmC5>*u>QB{_xsvwD~3X-U* zAc?99lBlX6iK+^csHz}|stS^*svwD~3X-U*Ac?99lBlX6iK+^csHz}|stS^*s$eX$ zL{$YzR29XP={`wRRggqg1%{oWr?b? zL{(X$sw`1emZ+*ci`tP%qN*}UR8=O4sOcGUr7TfZ znIx(zlSEZzlBg<6R8=O4s>&o$RhcBJDw9N2Ws<0>OcGU;i1swyN=RfQy~s*prg6_Ti`LK0O~NTRANQB{Q`s;ZDgRTYw`szMS~ zRY;<$3Q1H|A&IIgBvDm`B&w>AL{$}%sH#E|RaHo$stQR|RUwJ0DkM==g(Rw~kVI7# zlBlXe5>-`5qN)l>R8=8~swyN=RfQy~s*prg6_Ti`LK0O~NTR9=NmNx~xx^AxWr?aP zBvDm`B&w>AL{$}%sH#E|Rb`2)vP4x`qN)l>R8=8~swyN=RfQy~s*prgS)!^6NmNxK ziJB?ZLj!h6!IK*RYZyiu#u+9sE|+u$@a2-ag~h95HgE5lC+ifo2%h8~7KhLzM?5oB0H z?Tb2w4Gg<6j53TfBuu#kVag?VTw*Y{GaYzzi8%}xaBG+FGYk3CMSOiZ!&ThQJ^ajl z{OK0H-p$v~GJKBjyuhvPIXM9>lYDlGKl7&_aXZGie&*{F40VFC#E@1fmwY}wFJC}! zlrQG%E2uU3O1{2|pShahwS4C~hQDEWJ;NIq{+`}0Z{zF789u@ANxr{}uW8+J$xkzU zp6|cF_g~~U{*mwVSmc-ZdLP4A8U7bPL+gl3{*J%(1H->DZ0ApTbV?RIqcAoVS}9x# z<5cm}lS(eVSIOh+vltF#IGo`KhG#Q8hvB&l&turea6H3_40-kxo;~G4nnPt8!x;=O zVmO=O9ES6_KMNQxWOy_BgQxn9SnjqfP1o5UOh&MGsyr~J|O-&GQ zYJzxE1E%N>@unt-o;Bu8jd@cO#G4v$M^6%OYJzxE6GXil^QI;fZ)(h&8uO;cys62= zn;P?`CKGRJGV!J+6K`rV@unsdZ)!5}rX~|_YM>DGhj~+zi8nQwcvAzl(0$@fO(x#d zm^U?h)z@unsdZ)!5}rY7^~ zm^U@%O^ta|W8T!5H#O!>jd@d3h&MHbcvDk|H#LQLQ&WgHHHCOnQ;0V;g?Lj_h&MHb zcvDk|H#LQLQ)AxLm^U@%O-&)*)D+@PO(EXY6yi-yA>Py!;!RB<-qgS;3t)b?GE^A` z@nj{qhG4zG&H=nb*F;^F%sZ9fnn!WngCVVGmEaos^frdKGrWW0oebAA+`y2yqY~Uf z&%eg-b%t*;B%P-c+(D3Zo=R{BAh?5|o1urHk0EhKC38n5C?CCI%CBU~uLR}Ow|?gP zCm8AknF1?iJAGFseW?<3h$n#&fUk$ zL`)xF6Ey~z>ViylLC9*lLsS=ptR_fQ7lf=PNc0wDdJ94t(>2js5Ym_+(OZz|Ey(m1 zWO@rSy#*nS@hPM+L82%`y%A(;2{N?=!M}8es3i#gB}mi~1pg8wY6*gW2@Z76E7aG3gfC=3L3fBMLfA(TB&rBu??8~KB82?{L86Kf_6P)tDngK2cnecS zh^Zn3ZrY2e;dK zX2LwuFvfz`FcyL|mN1Vc%wq}jSi(G(Fpnk7V+r$E!aSBRk0s1w3G-OOJeCHg=r&xn9V_1U- zk~D}w7ef1tkqBcX!WfA#Mk0)n2xBC|7>O`OB8-s;V>8QzTkL|HmTSvp0Tv!X1WqAZ=FES;h(ouVwAqAZ=F%zaVjz9@5F zl({d;+!tl;i?VczG7mjWH{u63vXbdZ%r^R@dVmv=F%n#kUh9POTG0YD^(r;s!AA&D2 ze3{`Z1bOT+9(#<(9>dsiAI0nNF4@U&EZxEA2$nJ|XBc2u#W2J$%&?YWJ;MmYMusuK zIAcG~*pD;zL((b}u=&#+ z(k&CP{L?k7@zb z=j&YlRzAaGq5*gZ2$FXo!QO!cyaV(u;`f9geoqME_kvTe?=IbzD*YGu2 zrxQvYUz2q@0qZoi5aH`?eBH>`QNAYYbOP3CdZwAL&tTYtVK0XNo20i7kMpYUymimr zXX#UDR#oYy>Tq4OC7IlSF{UqyJ(ky8s39(C1&Ntti2{lJ@c1EYO)7`5>Ov`%G!kM{ zV1wSGSeh*8#mF9Aj#oCWJdzxF7)^zuD8gRF?|~TE1-09iNUIlwp6~aQf4)8I4=MHykHQP3QIeZwKz8pS+?b*cLTHp3Fjw0^XD!1)7Is7zC9soZBeirmv z=-pc7HvT2Q^2+vhY1h2)H^4g-8*G=J8ymnzFby_=&EN!>2Mb0ivryWrx5?v1{V#mU zcKOu!PVo1@cY$|;cY!)bK+n7vd>^R)=U2)Hz&{l3P&vDVzX4iZcSv1_gbDuYXl;ko z)#%u4hjevb_+ilPc1Ot`Q0K_W{up>a_yFm9u|JNT!q$J*>PgpPhd6Ow4PYaf2AjZU zu!SdE!8WiR>;OB#F7Vsr@*S`j>;wD30q_X;U2qUQ3LXQq;4pX+^cv|7DW~x?I0Bv_ z#~e5cj)4=D`5e!94R(jVg!;Dy>`Ck*PyPe;6!s6Wr?Fqcp22<@`xWqq;016Vya-+f zuY%Y3mHq=&Ilcz|2>dblI(P&83Fvv~4r!+GSHWKgZv)+icStk+SGVLHit26uCidI0 ze+&C|Y@O(&zq)1akY*a)_I5}ojc$88q?1P4o^;Z7m6?$q`u(&k>7mnUSJFe-YX54b zYX8QENcm6xl@w3ElH&Q9$FTR?R`1YXrFi_8E`_Hkfu|JAU|B~YQJ@hXro^AS<6wfv+N%3rdf?qj$*`e8ub8+;t zBm5-xr?BBris$qXAe} zlBh>gQQ5rG?d7EQNcb76M^aIl(X~q|Dzoj{B^8y~wt6H{k0k1mL_Ly1N;x41rBdL89Myp3s`zVZ7kEHfd7_A;j z#a%|LM^gJJj8>1N_E8wE9!bm4r&~Reinwe~VOu?tinyF^^++n>vTgN9D&jI)J(AjAVYGTA6>%A@9!W)9Myp3s z5tq^GkyONGw0a~JaT%>1N$tBZT0N4eM-uf&23C)x)&Y!Gk0k1mL_LzIM-uf&23C)x zA}&8;^+*O*k0k1mL_LzIM-uf&q8>@qBZ+z>QI90*kwiU`s7Dg@NTMD|)FX*{BvFqf z>XFnKDsEAaBiFzb8 z>#=S1NTMD|)FY`GkkhRmNySUHtsY6#BZ+z>QI90*kyO0ozgj(#s7Dg@NTMD|ea&~e z)gy^|BvFr~;w9I@>XB5uWZUYI)ar+A`WNbvL_LzIM-uf&q8>@qBZ+z>QIDkJCBMPy zkwiU`s7F%qlGCjoNz@~WdL%=uM>4c}B(*ERX!S^HSAfy#u~RBBFEmR#r4mMK=1%5H zJDDr(WUjQ6xzbMNN;{b=?PRXBlXbkE%sX~6|uYf-UFM#vlMes6s z74)36QVMB&4g3-KWAJtG2KW=uJJTwqkVfxJtCT_-Z}VTJkg6%Iu~G_Y+ikK^3TfLd zvr-Ca+dI}OrI1F)HkDFHqj#xQN+FHjrB*40GCA-urH3Ri~{v+t9qf(kF4yBoX zGwqG`Un$LW%18WWX{Mf$W*Q&z+oYMc{r$9(o>D2zwC#PBmC{W8Rhp?3X{PPp#rE8} zQkv=XcVXWNCP=vpJHmc9_It43i@gQ=eb`&E-;ccw`vchClTazmbS{5{T>)+flVBzI zLGVK$b*HCSN;Cb2`^=0q)ApZZS7Uz^`+ksqhXPcF^gDE*Qkv;sd5&2r&9v>fv{IUB z+saTW&9qIglxEuY9J5lIY5PqMy*IT|nrZY-s!D05(L1RsrJ3jSpOK!I?UH&J9a-&? zdKew&>>|$DMVzyXIA<4e&MxAdUBo%Nh#z(lIqV{4*hRFki_w1<xVl>&sII@co z>`(LsWKk!0{hBfM7VxdYdq}^B^m|y5yN4CIdrHjkJ*>#xBi-|pUcb60xEri= zirT;NgWx*p8%ExLPmK37fB&%l`{CUsAJ(o?VeBoS{y|J<0=ZOs$bApF?;-a+ubJFF_2k`y_c>e*s{{Y^90PjD5 z_aDIf58(X=@csjM{{g)J0N#Iq_doFF`|a@k8Rd&y-lx$GsEz2vf&T=tU7UUJz> zE_=ykFS+a`m%Ze&mt6Le%U*Ixsf|5Ql2RKpI(kgeic%$RMJZZQiWymowv?hRrD#hj z=0_>!M=9n!M=9D{iuRVGy`^YxDcW0#_Lic(rD$&{+FOeDmZH6-m;t4j z`=prlq-cRDT40J6n4$%yXn`qOV2T!)q6MaCfhk&GiWZn+UXx-*lVUEDViuF4Wu|DE zDOzTVmYHHskz!7fqLrr9AH|sZqtObVqTQyLDWsSqq?jF~m=UDH$j>kfND=?1i2PH; z{3)XSl*TMS<2XM>%TLkrQ?&dPEk8xePto#IwEPq;KSj$=(ehKY{1h!eMaxgo@>8_@ z6fHkR%YO)cdkB4d2z`4S2EMFu$syz17g(YG`jYw6q#pS`96&hE`NVE2^Ot z)zFG+Xhk)&q8eIJ4Xvn#R#ZbPs-YFt&}M3AGc~lC8rn<^ZKj4cQ$w4nq0Q9LW@>0N zHME%;+C~j+qlUIoL))mKJ=Ea+8hlrS?`rT}4Zf?vcQyE~2H(}-yBd5~gYRnaT@Ajg z!FM(It_I)L;JX@pSA*{!f$c|NTYGQCzjn-l_R%A-{RnJ70^5(k_NN$C>!mHVCH2x4 zqvs&?iXx2OpH^S;2iR_n^(EfhSzqG)Y4s)EpH^Su{b}{g6zZ8N)H744XQoikOrf5c zLOnBudVQDl^Nz#onVr=$JF91QR?qCLp7^<**;zfavwB4udY*W=K5!&luSmn_?|t?9 znrZa@wEDoirt9@J(`ePI*H=rYdw*Je;QeX!u@e7P>Ze~x{fv&d>WTX5iTCP>^y(F> zINdQ`yw8{oMCo*Uq~ zp~O5lz;gpUH^6fPJU75|13Wjta|1j#z;gpUH^6fPJU75|13Wjta|1j#z;gpUH^6fP zJU75|13Wjta|1j#z;gpUH^6fPJU75|13Wjta|1j#z;gpUH^6fPJU75|13Wjta|1j# zz;gpUH^6fPJU0+IH^6fPJU75|13Wjta|1j#gyy*co*Uu05uO|2xe=Zl;kgl>8{xST zo*Uu05uO|2xe=Zl;kgl>8{xSTo*Uu05uO|2xe=Zl;kgl>8{xSTo*Uu05uO|2xe=Zl z;kgl>8{xSTo*Uu05uO|2xe=Zl;kgl>8{xSTo*Uu05uO|2xe=Zl;kgl>8{xSTo*Uu0 z5uO|2xe=Zl;kgl>8{xSTo*Uu05uO|2xe=cAzlQ2N`fm@=x{-$GG(4x_IStSHCdo6_ zjWj%KP9}e);W-V@X?RYz=QKR0;W-V@X?RYzQCT=~ev7yOEz!n=$?Z{H0NC z#^`AO8Dhw1V*Zl&j8^%K?*zRY`5CS08Sez|0^be37knT1e((d}AA(Q#{c1DDCqeH< zZiTm2cx#2XR(NZLw^n#-EirGc>WPa&^VX_WZl{>HR(8s@vQw^AtK3d8Z>{Qye$u?P zvQw^=opP=4)(UT}@YV`%t?{jw3U94iJJlQ5Dc1^bt?<^WzNYuXTPwV^!dol6 zwZdB~ytT4Zt`*)|;jJ|^Z>{W{QU$_3t9;jLAD?OaJ4 zytTnw8@#o_TN}K!!CM==wZU5(ytTnw8@#o_TN}K!!CM==wZU5(ytTnw8@#o_TN}K! z!CM==wZU5(ytTnw8@#o_TN}K!!CM==wZU5(ytTnw8@#o_TN}K!!CM==wZU5(ytTnw z8@#o_TN}K!!CM==wZU5(ytTnw8@#o_TRXh9!&^JNwZmIGytTtyJG`~STRXh9!&^JN zwZmIGytTtyJG`~STRXh9!&^JNwZmIGytTtyJG`~STRXh9!&^JNwZmIGytTtyJG`~S zTRXh9!&^JNwZmIGytTtyJG`~STRXh9!&^JNwZmIGytTtyJG`~STRXh9!&^JNwZmHn zymi1^2fTH_TL-*#z*`5rb--H(ymi1^2fTH_TL-*#z*`5rb--H(ymi1^2fTH_TL-*# zz*`5rb--H(ymi1^2fTH_TL-*#z*`5rb--H(ymi1^2fTH_TL-*#z*`5rb--H(ymi1^ z2fTH_TL-*#z*`5rb--H(ymi1^2fTH_TPM7A!doZ2b;4UGymi7`C%kpSTPM7A!doZ2 zb;4UGymi7`C%kpSTPM7A!doZ2b;4UGymi7`C%kpSTPM7A!doZ2b;4UGymi7`C%kpS zTPM7A!doZ2b;4UGymi7`C%kpSTPM7A!doZ2b;4UGymi7`C%kpSTPM7A!doZ2b;6te zA6Fxh{!0(^c&goY(mm}4k{))!TNk|PTM8*27rNlB3*Nfmtqb0|;H?YZy5Ow~-n!te z3*Nfmtqb0|;H?YZy5Ow~-n!te3*Nfmtqb0|;H?YZy5Ow~-n!te3*Nfmtqb0|;H?YZ zy5Ow~-n!te3*Nfmtqb0|;H?YZy5Ow~-n!te3*Nfm?K$x_U-F!IGu|Oio)ag=2CxxK zgH2#FI05Ftf>E^-s{DG7%5U`kz2{VZ<2ym`_avm1XMwjz2~Swn_dLxw#P8Lb|x z-eI+q^k3>daNsQhjkEVUI+H*;z*4T%7V_@OAJ8=sgk{PVdPC-XoD=k3=T$9*GR| zxJ=+Z5*cQ5nZSD_GR)~Rf%iycnAv3l?~%v^-XoC-yhkDvc#lMeJrWuANMzU}kqNv< zA`^IzL?-Yai41!rGVGDa=nI<4qc3Pi?~%x`Mi460{40|Lp?2*W*U+5Y23#0c) zWYjxsdyhmW=GEqmz7g2=_x+4|jsD6WiH!P=ZSRrDs0Z2h9*Kd&&9?VQWYptqdyhm$-z<#YBazWJ z3#0c)Wc1C#=sgmd(0e2@%#<^s_ef-zFK5^zkzv-H3B5-m!`wN;+&L4{@0dYnLi!!^ z=nQ)#GND)0GwhMbg#Ln-3B5-m6Z#8&CiEVOOh~U}k3@!9c7{C?8TLqILhq5tgx({O zVUI*6^d5-}dn7XKk$9f}8hf7q8hc)P(pB<2vBC31Q_rivJEZ|^1k+#>*bGj9d9Yw) z#DAU<|9M9I=YuMz^Iv1n^Iv1n%lk@^myQ0fvFGJk<2S^_zeUS7)zD*DEZF-Pz(}R4Q9^~8fAm643`8GYsx9LH?O%L*IdXR6^ zgM6DFjvOoFJDIE+@$41i1{8%P_eNlglu<43o<+xeSxbFu4qq z%P_eNlglu<43o<+xeSxbFu4qq%Sm!MNiHYJk)u zoFtc%aydmVr^w|Lxtt=GQ{-}rTuzb8DRMbQE~m)l6uF!tms8|&id;^S z%PDd>MJ}h6%e+pv`Zc5eYJ973gxp8SeT3Xc$bE#|N63AI+(*cLgxp8SeT3Xc$bE#| zN63AI+(*cLgxtsZQasL=;&DY;LnY&ivW$+h#`#h_uJKDLd?_B+C^l4bma?6tY-cIk zS;}^nvYn-DXDQoR%668rouzDNDcf1fc9yc8rEF&@+gZwXma@G_**mY6GSW% z#3~a+DHFse6Pin^Jeo@y{r!3(@b~Kp%_WWZIv33uo$l|~6Phy$HD}ac#h!j8_Kc1w zCK!g$ug(nz)Cm4Sx76jW#bY`0o-<`vEdHB!6e;)qx@SlhOJpAY3KM((T_|L1^6$( ze*yjr@Lz!c0{j=?zX1OQ_%FbJ0saf{Ux5Dt{1@QA0RIK}FTj5R{tNJ5fd2yg7vR4D z{{{Fjz<&Y$3-Din{{s9M;J*O>1^6$(e*yjr@Lz!c0{j=?zX1OQ_%FbJ0saf{KMDVn z@IMLvlki`J^CFxVVY>+1MOZDuY7th8uv&!GBCHl+wFsX@_$6k($X8%5YC!bTA`im*|HjUsFmVWS8eMcA04c2m@DirP(4 zyD4fnMeU}j-4wN(qIOf%Zi?DXQM)N>H%0BHsNEE`o1%78)NYE}O;NikYBxpgrl{Q% zwVR@LQ`ByX+D%crDQY)G?WU;R6t$b8c2m@DirP(4yD4fnP3@+s-88kErgqcRZkpOn zQ@d$uH%;xPsogZSo2GWt)NY#EO;fvRYBx>orm5XDwVS4P)6{O7+D%itX=*o3?WU>S zG_{+icGJ{un%YfMyJ>1SP3@+s-88kErgqcRZid>;P`epwH$&}asND>;o1u0y)NY2_ z%}~1;YBxjeW~ki^wVR=KGt_Q|+RaeA8EQ8}?PjRm47Hn~b~Ds&hT6?gyBTUXL+xg$ z-3+yxp>{LWZid>;P`epwH$&}asNF0P!YmQOtY&lbC9@@7`<*TE+V8CN&FF7}vr;+R zUi+QZEYB(aCOE5A9izXc&T3W1=x>6vto_bvwZwKFEEuI%dcX9_=x?dB(kml*F%z6+ zCO8}TTk5Q4g8r4irOvYUJImVdY~XK#v(ho6W35>tnc0}XrOs-eX!N(#S)obNFHoU(9K>YQAI+U(Df)IeamPFXr&Y9KM*t z7jyVx4qwdSi#dEThcD*v#T>qv!xwY-Vh&%-;fpzZF^4ba@Wq_gVN?cuF^4ba@WmXy zn8O!y_+k!U%;AeUd@+YF=J3UNb_HBuWVyh|a)Idj0@3vaqU#Gp*B6McFA!Z{AiBOl zbbW#7`U27Q1)}Qp)N2&T_C#tU*x6J<<$~&&N1kfmU;4;C$D+(nkTP$@|q{F zdGeYkuX*yCC$D+(nkTP$@|q{FSIO%ld0iy0i`45Pd0iy0i{y2Yye^X0Me@2xUKh#h zB6(dTuZ!e$k-RRF*G2NWL|&K4>oR#=Ca=rnb(y>_lhneF&C9j+0a+6$c^4FXEbp=&lLDg4K^%Yco1yx@`)mKpU6;yo%RbN5XS5Wm8RDA_i zUqRJZQ1um5eFartLDg4K^%Yco1yx@`)mKpU6;yo%RbN5XS5Wm8RDA_iUqRJZQ1um5 zeFartLDg4K^%Yco1yx_w8vcCAYKiAQt0j9t{|Cn^JHS`j0lvx(@Kttzud)Mtl^x)# z>;PY72ly&Gz*pG;zRC{pRd#@{vIBgT9pJ0%0AFPX_$oWVSJ?r+$`0^Vc7U(41ALVo z;HxE;PZY zYN}KGe=Do(0ACHOv8i?VacuwJ$|^g+S4025?P}=%(_du=_$oWV*Whgp-qzr4jh*vr z@U{kTYw)%PZ)@4> zTZ6YXcFwQC+Zw#B!P^?Vt-;&6df6i->*{63gnqkD&swKvt<$sCHI_NuWBs~DG~4#( zy2i3|LVp8Vr{As9@7C#e>-4*I`rSJHZk<#0);U#gU1u8mZ9Sk*)mx`muG1^m>6PpB z%5{3>I=yn8Ub#-MT&GvA(<|5MmFx7%b&ZTFk48r0d;ES*)msm?V*6CRb)9K!^nVDh zYxMM!K2>jBqo>imZ(XCL@fYAPjT$BOS80*Bk`@`g^03aSdg~~_Its9k0<5C|>nOlF z3b2j>tfK(yD8M=ju#N((qX6sSK9`D9_144x7yJJM9|!+4co2NT<|UCz^5Dd zbOWDmC~i5Yl6a+P1D|f-(+zyOfloK^=>|UCz^5DdbOWDm;L{C!x`9tO@aYCV-N2_C z_;e$%PdD)C20q=uryKZm1D|f-(+zyOfloIS`KWC8bOWDm;L{C!x`9tO@aYCV-N2_C z_;drGZs5}me7b>8H}L5OKHb2l8~AhspKjpO4Sc$xQ&(tOD#KHbEpoA`7SpKjvQO?HiId`hP>AW+KAh2Q?Fst(k~WGZCR?B0|kXgqn#6H4_p3qixSbg!=!x zAaFYoO3#JTK%xGdN%#k#{=Y`H^js)C7fR2C(sQBoTqr#k>YKh$-}Ht0rZ3bteWAYT z3)N19YA3?Op!8g}^jxUEFI3+b>KnRHU(bd5ZZ6b!aG_2K5bE2v@P^UtM5t3zg=OH| zLFu_tsEgZ)>@A@5T(A6sSKM34Tgwk`N^js)C z7fOMH!0kkMAE^I)m;F)jesC|C0`>J)f7NV4s4uoceXAAnHn$Vm{|_iVm#w}pRNoh> z?+exUh3fl4>A6sPE_6Ey@o9)pLwp+I(-5DA?)!SiJ`M3{h)+X&8sgIspN9A}#HS%X z4e@D+PeXhf;?oeHhVJ`%r+pgY(-5DA_%y_)AwCW9X^2lld>Z1@5TAzlG{mQ&`+g9* z?+fkI5TAzlG<4rrihUa5(-5DA_%y_)AwCW9X^2lld>Z1@5TAzlG{mPNJ`M3{h)+X& z8oKWXAwCV=_hs9sq5HnjJ`M3{h)+X&8sgIspN9A}bl=yL_GySuLwp+I(-5DA_%y_) zAwK<8`E*g&ENULAYna~x>T7jyTZz6&3H41%XqIl1XU_?>sw31&i%_dNLapiuwW=f3 zs*X^rI>JU!t2(lqz-CZ8y_KR>9bq0U808DSU%oJERYz!LxJ^78cY@>+XjMlkTGbJ1 zRY$l6{sPphPH>y}H)>T!sBdRNt?C4~c_l%pRUM&Lb%a{g5o#qtco(Qu9obsd5o%RO z_QAyp?(dMrhtj;jI+jO1%OT__h(fAKpsgtrXr$;jI+jO1%Q3XUtnEyp_UR zDZG`c-8$X8mBL#oyp_URDZG`!TPeJi!dof4>27G30p3cz0wdeJmBL#oyp?(dMk(g4 z6y8eVtrXsTkIA{94BpD%tqk7E;7vDXt5jw1Rt9fn@Ky$IW$;!8Z)NaS25)8XRt9fn z@Ky$IW$;!8Z)NaS25)8XRt9fn@Ky$IW$;!8Z)NaS25)8XRt9fn@Ky$IW$;!8Z)NaS z25)8XRt9fn@Ky$IW$;!8Z)NaS25)8XRt9fn@Ky$IW$;!8Z)NcIcCUm4w=;s@&Io?H zPYh7Xhe3}xw|gEc{D_#m-Lp~Q$H8xd-vN8UKCmAg0FQv*1qZ>S;4v@@4udDbQ{eZ& z)8Ghr4*Whi3H}541MnsAW$+d7hu{Tp9=r%@?yvG|4lBG)jeZ2a4*tX#{Cod3_zmzk z!QTR5#wP~ouW&-dayt>r?LILexZN|~;C7!FApBkM_rU}hfsSNu54V6@L7ft&6vsBV zYX_InqyO!mI}07v-0r!vP`lTJ9|9>)_z~S*;lrTT9AtkA zbZN`+emUMR$NS}Yzr4iWFUR}kc)uL)m*f3%uSMvu_I|m~ixArT8Ux7>3iv^w2UVs*NsL}#!Ib;h;u!#sH}s57pW zqEnrPI)hz!Kd952W$(q->CLiJ*gAtI`E8PcHtm+ z6x12)O3@kYLY=`b)EVqToxv{r9;h?eW$O%fq0V3z=0KgnE?Z}?3&$ym&S00VGuVZB zY@NX_yMV1T*ku=aQfIKsp2GeC_B6K6U|0GKw$5Oetuxq#I)h!PGuVampw3{Ituxq# zI)h#4IqV(k3$|aw)*0-we~hg&*k#|q{t5P)OCJ0?@K?cK2XFH;>N|R#S<)TqLAJ|C z*BR`x-;S*_*k#|&ugXE~npTSTNDFlayHIyt3$=SzsNJ(d?Vc5C_pDI6XN7+Z-pxC8 z2D?&p2D?yaunTntyO8#&J}VBHXWgNm>vWyLE?nog8^)NAnquYlV7trYG37Cz*> z6p!h*>gjqLbFn+r-<`7Ge^s0&TYX=DRkUVXXRr%(2D?yaunTntyYNm>XRyn@3tMNf z%hnm}LY=`bd@r`nV3(~k*o8WSU8pnIg*t;>s597wI)h!PGuVYXgI%aI*o8WSU8pnI zg*t;>s597wI)h#KC*YsD?$Qva+=s0**k%7Yw$5Oe{ZZ`uL3%N>%R8hn{%eYKoxv{q zA#7M;zIlf<$LaKCDUa<>@{G=4m+e)BJETIk-{kPqFnIv{4ER~_FTl@%f61?O277R) zMlPdHatrR18XI-eky?*6ErF&b(6j`amO#_ECrf|zD4amk5@=ciO-rC@2{bLC5wKRz zxXmQcv;>-#K+_T$4V`XHOK42AZB0v*Skn?{S^`Z=plJy-ErF&b(6j`amO#@IXj($E z55LEnmeB0OXiekxE}=Dz+q;C;G;Z$_TGJ95k^Q_iErF&b(6j`amO#@IXj%eIOQ2~9 zjmZ9$H7$XrCD614nwCJ*5@=dNBeI{drX|p{1e%ucy%I{XrX|p{gyu?q#+sHu(-IoH zZCle48o_N_(-IoTonlQ(Xf(HNO-pD@w{1;JXk@o-O-rC@2{bK%rX@78JKdU=K+_Uv zS^`bu&N8K2)3~`zXiek(GNCmsq5n@&$T!E3=-orX|p{1e%sW z(-LS}0!`zdH9bT7MAH&zS|YHfCD614nwE%J(-JXjS^`Z=plJy-ErF&b(6j`amO#@I zXj%eIOQ2~9G%bOqCD614nwCJ*5{h%=Su`!7XvelSErF&b(6odiAE#T>5@=ciO-rC@ z2{bK%rX|p{1e%sW(-LS}0!>SxX$dqffu<$Uv;-?-2{esc=ah>zErF&b6eHQTrf~zE zkY0?YCD1f(qf@#yErF&b6hYZ`e3C%ZxSvk8HH};9gx0hKnwCJ*5@=c?w5BCOYg$78 z&tkNuB|>XjBDAI@LTg&WHzo&np=o!aX?LM%ccEz!niipH5tYDsF_PMXcgRXj;T7ZiJ>qXj+7(MQB=trbTF4gr-GkT7;%W zXj+7(MQB=trbTF4gr-GkT7;%WXj+7(MQB=trbTF4gr-GkT7;%WXj+7(MQB=trbTF4 zgr-GkT7;%WXj+7(MQB=trbTF4gr-GkT7;%WXj+7(MQB=trbTF4gr-HrX%U(h5vN6H zT11={p=lAC7NKboniipH5$o6ynidhKMQB=trbTF4gr-GkT7;%WXj+7(MQB=trbTF4 zgr-GkT7;%WXj+7(MQB=trbTF4gr-GkT7;%WXj+7(MZ{?lniipH5tR(;_r2B2J6Yw1_w@LenBNEke^G zG%Z5YA~Y>R(;_r2LenBNEke^GH0?douKD0SQZ3^hT4Q;SRKnN*>c78br$PPqx9nz6 z|NSjn|NSl0e}4z>QEL&(<9d%gZv0P9kxz~91b+{F7kDRl7pVXK)-&$~_21vJ^|NR|op`2SN=N8Jjg>r78oLi)3e#Yh8A~iF*oLi&}MwfF7<=jF!w@}V4lyeK^ z+(J3GP|huCZ+c!W&FFG&Q5!S5oLea87PTnbF6S1?xrK6WrJP$S=T^$Om2z&SoLed9 zR?4}Ra&D!ZTPf#O%DI(tZl#=CDd$$oxs`HmrJP$S=T^$Om2z&SoLed9R?4}Ra&D!Z zTPf#O%DI(tZlj#rDCaiHxs7seqnz6)=Qhf@jdE_IoZBepHp;n;a&DuX+bHKY%DIhl zZlj#rDCaiHxs7seqnz6)=Qhf@jdE_IoZBepHp;n;a{dA3`~%AA+Zz`H-^^%q`}EC> zM*H12GaBu8-^pmS-+d>ekaGGK#reRuC>q^9eT$;e?bEj?8tr%AqG+_=eT$;e?bEj? z8tr%AqG)vc^gV;~LiZ!zGw2kT({~6OT~6O2XmmM!hoI5r^zDI0m(#Za3Mr@W`_tPf zr|z1Sbe)~zv0c@Q+)72?Es zHGqwvZjDijZjBM@))-+6Pqu=(HAX4zpl*$k-3fMqUgfS}owI^<&I;B!D_G~OV4bsq zb~*TVs^& zHSh}g(Y9B@E96bvUJtKO?BU;fRlGv6hi$KoS19(d?G^G0#U8d_#(o9#I(Y>vr4_7{ zRS zx8w@N9=5&GUZL2-w%6M$6noe%2i-C&6nhxm_9_%_7~S?N0=K;i#T&*y2CK{rYqk}v z*;Xj7@Ly?HiYsKR{i}Vd{Tm-5MYqPtcAQ_K$idHeg}g$MgKYH<{gu_-3iT1&zw5uM zr`Yy7e}(#sZQU9p^xA2KdX4P}Terr@_R2$rdXVic*t#`F_EzloWBZFhh5D4!z3y6} zo@M)wu>EbQLXm?p3HsYmg(3&zhd}z2A_tfJBc$Ai{b$&Jj$MuYQEd8`A_u>L{-wyl zHvNm0?bX@}MGm&TT3eyW!M49HRVZ?>4Tp*xY=0U&0P5BlrF<6D ztueAcC%juTAf2vW;@w2PA#_OST?E_>8r;pQ``z-LQdoQUJ&8ks@8i?ypL)`0&Dk!^ zv28DGXJ)irnq%7>ZkOih#2;yn@m_EbXs)(PbIu8M(uhze9td^Ph)^dU2zAnkP`9xN zbsLM&>sr16&^hX)5ur{R5$dE7p-vhR>ZB2&*K@Wr_u0NXao=Rn=Y zB3rky2zAnk@Ep(Rq!HOVX+)@#Mud~tMQWszMwH@}ob6H`+tb)DVS6QKyOhW2uYf-U zFM#u)P8!i)b<&7XCyfZbI=x-WV|)$NNh7koI=x-99-~*Mw`!gvuw?pc$(juiui)`zp5usPnw@Zs`>!cB(P8ty=NYP0nvLkGrG$Q*w*g9!M z_7-fNG$LCkjR@b5t&>J%>!cB(P8t#Fq!FP`8WHNG5ur{R5hg*MG$LCkjR-#kQg>!C z+oeTL_iFQY&0=hOwRyW{F}6R7eLqOQV-~YrTI9cawRyX=$hKFTw@Zs`Td}uGi)?$f zdAqd8Hoa0>WE&2pMYiAMP$!MZJ^<=A7TG#!M5x09%3DluB*Tl3~+TZ?>ap3(gH);y!NC|TmR;al_k zS8I`P%`=)4-~&dXZlyYr0JBHx{7v=;g9JfpS9cjp^4)nxYmx8H zGg^y$cb?H&{Xcf9S}^lV#;l4y}{)6o1UITi+r1&ZEKNl)3a?Y@@;yytwp{~&necTBwFO#^lV#;e4CzaYmsl$vu!Q% zZF;t?MZQhXwzbH&>Djgx`8GYHwaB;W8LdUWP0wg8@@;y?KXt9qBHyNG+gjw?^lV#; ze4CzaYf&{Qc;2_^86B(dRQohKKKE^ULLy|}rYBn*8XZ;oHa(-`N#CYt zbPVa+^o))heVd-qv7&F&TMW4OO6b~g@0HNCAcTaPO7Swd39^p=-yzS3=j0d#{A9 z9rs=dT|4f*61sM~@!f7}w_D2Z6xVJyzS~XhcH_I<)NVJv+fD6uxZa1~tjqi3-yWRM1H?`Z1 z?{-tW-S}=dwX4z|;M$<7L?^ch9dB2urbgX7BJ@aCrTQ9ma*I$Ww+MA|i%=)G2t5*2 zF%ne~6<0A5RWTA(F%nfV5>;t8rk}UYSE2A#XnPf^UWH0mq0dz)a}}Cgh3ZzJw^d?8 zzZDxs?{cXM5};0Qk*$+kggUuJXl<<0UQMU#tR?t1V3RS5> zPpVLoDm0`D4XHvss?d!p@#*KS6;-H275Y$xGE{|6`2ArmsFPb{e?z%&Z<_Ge)N=kr zxf|aqyoWuU_Y$AnOMG&#;*I&>Ua@^n=pC^4if!Xg(!JyQ-jZElJt+-fBbWx8z-BPR zlM~o^uwWE>dcW8+R`?mQXCyCnz~0La*n5NBq*w7P@3_8~9kBPZ1NL6AsuZzm^vv#F z;;4Hy?kE?HFUEI*-f?}eMib+m;9cOm!S{mi1K$sR0Q^Jn3BO;g8lMEcbNE48?}N17 z2ZIB8^1<2ybtqC5-{!8py)w;IpK6VLxXi((oNdDs9YbJD&_{Rpw8^$tT6LQmFN(wc;`Uio^=2p9SGdB4k$f#;;{n>(XDIV$DD!8? z_cOuY>B-Lo|6TYvwR@b}JT-~}9HcG>smnp?a*(N(&d7jXFgg)z1_%>lJZM&AXT}#`R7OD-aSAlNZwc_EN&~3X`Y}j_& zuBC0)(za`9+qJaq+Q4nQmbP6RxNX-4ZrioA?ONJ)tu)7PaNDk>ZPx~F+qHq)c5UFc zT^qP<*V49YY1_4d+jec>wp|;zZPx~F+qHq)c5UFcT^qP<*9LCewSn7qEp5A&wp~lx zuBC0)(za`9+qJaqL$GlO9uA3zbZ|&K7_GX8Xb*?PgKewsA==L&RQC|7dkED%gz6p= z59joZRrip1=n}ej9})vYLaXi}F<`Xn9ufmatL`D{en@q&>#PtW>1J?kmBeF|=$Qtm^+Q_9`A zAG8`grQDrjO?Zm(KSlY!ppwi7U!ZqL^tm zrK-bUb@;0ef7RiyI{a0Kzv}Q;9sa7rUv>Da4u93*uR8oyhrjCZR~`PU!(Vmys}6tF z;jcRURfoUo@K+uFs>5G()VGfM*5R+e3cjlK?Jr7^7KM%mzbKtCIvV_v(uahQ1E5m@D;H%6nsT23Gv-ml$UJfH54?c?{@_aVq;$TW$q*t9pae zUAwR9J+{9Ix^`dH+nn;OQDxA3REBi$HJJPwOnwa}zXp?EgUP3<_0!b)X%z2i@_HHu zo`!+1^UT+I=IcE3b)NY;&wQO{zNuUmgKsJqq26zNoA6uw_FMe+Tm1H0{PtV?_FMec zH}9MaTIJJu;cwW6w^n#-ReM%C?6tyPE9|wxUMuXi%A0yd-ZcIS=yfgMgL5wEP#NZh zj?g-kuh9|Ovy|;w%JwW}dzP|2OWB^KY~6ZhDCpKR!k}Axb_f075xt>1@Xq<}U=;gB zY_I-x2UkeB3VJQBJGcSb5RL&sg+ z;jcR-yiGiJht}%uuoU}t=N|sHp7f0XX`%m*!}kKn4l+&;di8uy;QwFf35Kv;ub#kl z=?Tt&Iq6AHFy`L|)BM#dr9Ht6@A3ZIo?wkmQKt|z#_lm83bE2uretNiLB z_9f7JbbI7A=W-RiM#^>G`5Mps2>dblI(UO8e}cUL-sJgP*#9UVdV-(wo<&mr3HzTZ z&l0#y`WxWC^0t4&UNx#!t31R2J;VUM4MFUwRU1F+x5fT5PyU7Tjd^_UiPe&Fh`)M< z-V=L@l>Y+$73dhgCuZgBiTw>vx|j9DJlF1td9K|P^M3E1nCIF(G4J>8i8&JMiM3!m z=IM$3H_*z~6Z<>T9o6*29Le;=dcf!T>$gEX9`nk4k6N;8cMKcv$Btvaz>_C<+yBJ& zf3oz%PP!$;PVuYL;0T!G8Cpo}EN_?q^Ptz^dt%<*-4pXVd{3;1{R4hQTZ+w){xV#7 z)x9T1`-xq^rp?5>m%ArMJBj)KQ+i^rfeXCn7Wh+pJch4h|IBayH|hVvlm7>M340m) z=h)VSp4bX?@p?{A%x<( z&$xEIsB~{&kMyF_y{L3AD%~5iO827Dy)mnFFDl&|vr6~ItkS(Pt8_0a-5ax-^{U1C zZQsMTvh~KS(!DXObZ^Wm-5WE*y)mnFFI@G;C?|~dqSC!;jef=|-K*AOv`Y8JtkS(P zt8}kgj?pUJ3x~a^bT2C1i%R#R(!Hp3Z)lb7MWuaK|4`tw`h{@V2Zw!d*awGwaM%Zj zeQ?+ZhkbC^2Zw!d*awF`^Iva+!#+6dgTp>J?1RHTIP8PNJ~-@y!#+6dgTp>J?1RHT zM!G&Y?1RHTIP8PNJ~-@y!#+6dgTp>J?1RHTIP8PNJ~-@y!#+6dgTp>J?1RHTIP8PN zJ~-@y!#+6dgTp>J^t}c{f$udC!eKug_QPR69QMOuKOFYMVLu%9!(l%h_QPR69QMPZ z??=!(;jkYL`{A%34*TJ-9}fHBupbWl;jkYL`{A%34*TJ-9}fHBupbWl;jkYL`{A%3 z4*TJ-9}fHBupbWl;jkYL`{A%34*TJ-9}fHBupbWl;jkYL`{A%34*TJ-9}Wl5p8@n| z0R0(2e+IDH(LG-?2i8bFZ-P^1AgY9K6E419$6=LnI{ z5!Fs9L_SA|e2x(L90{xyM^tP7)qCxZsMhC%|A0Ls?;iXg6XuZ`Gg>?Z7H zY|p8WC?4<|zJ~1?$`M5ZPU$4CBj5|9pCJ8zVh>~63rFDp2;;&Ljnt~Oyx{aAwnyh9 zv6m^8J#vJx_y}Y15ys*p8jGF&zj^b&VE-TNCG2JFpJUr=M;JYiX!Nx0(esE#Pum_b zk7&dc1M;Bi68;C$e+Tp^c_e&?{^}b^YK0zu2i4QNgpO(k)yJJ;Js+fx52}wl{R%1e z(ICCs_mAjF^=sqjoKC+Uq+buxuLsqyo&Fp+0DjkRqhAlIU;DQnUk25$)55<8M|p-a z(3b~k?Su5?LD(LowGYzT2kF;?wD!RmC5*k!J3WpJ(#{9ff0c{+uX3cF532v#_J};F z{;MbHzrICfKJYCnLbdQkp?jHcLNR(YKdP3dbo%d6`r}c0;!)bbQM`YYK6q5V_LG;v ztDt+|G4-h-q1OkFF`qrA_H6qrdghqeGky>Jd!tIOU#ZOVL6-iQWj>OnS7y8T8#vC)s?9hT&quO>=Ofv`^O0=e`AAkuX!Lv}8+bmF zRlD+&o{wY$&quPsO`i9BBpY}>l9fLAJ&sYc(g)j~k7NVSN3wzEBiY~$(DRXO@Nd|j zk7SvTWSNg-nU7>qk}OJ+Wj>N+K9WVBv&=`b%tx|lOIF&VT$qn!WB-MBdOnhk{WbVy zmzMcRHuksJo{wbF_AK*}EDE1xK9WV}v&=`bsC}0CNEXe{G9SstJRiw2AIUNw$;O`N zot}?mW1f#>nU7@Er&M3&BiYyx>7I{d89TBu&quP1AlaDbBU$DnS@k~u%JY$|MpC2a zBUz24wml!os>d0v16lfARx0N=c&y1vFV3zqvHs<+AHs<+AHs<+Amib7Q`AC+rEF1HDB+H1Fjd?zjWn9a~JRix%9Q|gQ zk7PBbyB400WTgYjo%u*M^n4`Cd?d?!B#WYEnU7>q)GYInthB;UdOngxU9-$bvdl-a zjFMSttn!t5C>Q1<+0aUxmC~kzq2N0uKMICoKUKdQLV1SJoa6M_}*A4ivtqnyW4r{gH+aXfe&-yKJz zj-#B%;r2MJ9*584#0kgI&*Q`i$B7e;Q;Xwo)&d5O6DPcYroDisy?~~@fTq2GroDis zy?~~@Ae~}cK+}d{V;DAuVPhCJhGAnEHilti7&eAsV;DAuVPhCJhGAnEHilti z7&eAsV;DAuVPhCJhGAnEHilti7&eAsV;DAuVPhCJhGAnEHilti7&eAsV;DAuVdFGx zoQ93l8etcM)6(a8VL!HKcBiG)#v$-H=t$$Vbld6Pr+1oo`*h%_?=)FTGsnap9Wt~=x z?e|a;I6NJjB7FvYnZG*nJgwesbaZ!Gz1#Q`@Fvf^0eU8Qn%Mg^QTJ&WJ{@}eJsoHXhe0 zAUPtC91%#4lIMs(a$>$V$cgzbq2~oTYLuf!IUK7dQgR5rO20KypMNIUZ(DV0E_01un=kKHHeYQP+A5||i zUIRVz8ddKwdj3AD-eKGG_fho@|H||CQQG_{ZGM#b`>0yGo}q=0s)g%GwPdIKjo+Zw zYdekY`TM9^uhTt$A64tM?fLtt+O5&^_fh8WqcP9lN7VwI?)m$uTA*#u-$&8LQM7Rs zZ5&m*Qms+QQReTXw53tz@1tnuC@p7{mNQDr8D;)Hsuaqw=p9kZ1KP=I^8Osek3Da+LY|7}3QT(Z!gei}_$oJ~j4( zM^uY3`PV6qF2(|nfMdZ6prea1qKmP>{{=9{m^h}m!s(Ns0kp5lJ5yhAy3gh2{jwr?yQ5YRXjEQHXqlhu$hcPki z6vq!^#1CUJ&j-h1Z-D>Cdse}9BctsYqwN@x!x)jn7?Hymk;9lG2fcyFVN6Ue2IGue zv?>K5aPUJa`#*U+?<7nwPDmspSj-#C8DBd_)H%`1XPD>jn zY8t1#jiY1ZDA+iW=Qyov9EBN2TgFk9apIzJTFyA*@;Kx2IOFm-kk?4zbbo!w!*gCd+xEI>UfkOD%3GdQ-#n|nc_Pm|tG;>S z&pfNXd9m&1-B0tZ`sUS^lp@B?3H^;YFWzkX>qDMZBi}GM6!?ZgAsiOqumFbzI4r1;Fhl{}^nl>pWZM!v2qG^+8+9aAbDNXZVt!a~J+9W(r zqG^-#;z_aXXFOw?)L3TpjA;^On?%_rQMO5xZ4zahWX3c}ub)KUCegP^^ldWc8PlZL zHd@~%#jtJ9Z6}#2Op06Eo^edl_b1W1NwjVft(&CpPoj8}DBdKBH;Lj+O7Z*#&zL4* zeiF_nVS7?M>&@uiB)T_=?oFb5ljz2-`*2F2Z&Z zwu`V`gzX}17h$^y+eO$e!gdk1i?CgU?ILU!VY>+1Mc6LFb`iFVuw8`hB5W67y9nDw z*e=3$5w?r4U4-o-Y!_j>2-`*2F2Z&Zwu`V`gzX}17h$^y+eO$e!gdk1i?CgU?ILU! zVY>+1Mc6LFb`iFVuw8`hB5W67y9nD;(uc)hO8OvFzczYD*>v!aS{HgrzUUH`%9}6A zBeKQYIiW|xm&Bg!SFyd4{E{Lr<4?hV0+;*@`-om*AJI$fBYH_}>uqA&_*p+Gw*BPa zV5h-mum$wK+?Nz78Hd4_dEWoQ^pav5qt_W;QamG63}bv7Smq}cu{h;-z;`HRhPuyC z_ZjLwL)~8{{bkZ$CjDj7XNfasi7;o0FlUJ{XHm#mBFtH0%UPnwS)#;Q;=@@Y!&zd& zS>nK1qP|(;y;+oP7EPOt6~y*ztO$B^m?esvC4QSFa+@V)n?=WFiPmO`(`JdvW{JvP z!Gq^1^LfgAo-&`O%;zcddCGjAGM}f+=PC1f%6y(OpQp^{Df4;Ce4a9&r_ARm^LfgA zo-&_Djn7l&^OX5KWj;@t&r{~}l=(bmK2Mp?Q|4D;{#BTNmAUq-8i^KzS2YqDuZxXW zRdU-mz<)L3qgV0KtIPpk)hOfiQ=r$4U)4C`l(XOj=#}ADRa&Qeb@x?`9k$oNUx2?f zG8=l8+0d&RDV$OY{kF7qYIe2Fq&qRf{l^CgXOe#T|KM42y9=1Y|M5@o)m5p6NJ zLchL3zrI4hzCypgLchL3zrI4hzM?jx=hbG6?$=k;T8!@3SLoMQ=+{^1*H`G*SLoMQ z=+{^1*H`G*SJbZbTeT~r`}GyIE2I1M75eoR>7n23etm_0eT9B~g?@d7etm_0eMOq4 zC+XK$=+{@IY3G8gj38GTL9VJ^^TAcs$mm(mRdoI;I)7DVbBgDWSM@gIJA~Kp={08Bq={0?UzNvi;E@}u z>5%Ljr2nha^#(n!Hy96!jT}^`H}KRAc}j1Sr;Mlh?Fi_ectc)u`dPnU zJQ%IgH{jt09=stooNgt#q4gQ#3UBa#h2M}Ljlc9W`0)mQydgj8&GMu1w}lJTbb*>K zP}2o!xj!fpr#Adbb*>KP}2o!x>l3)FOhnsQ5K zz%7}c#wZBPCZ>pxYt@bzRW!$G3aG$2o-yCn!%Wl%kZc>Yz^s<|(g?>dZ zyGhA!(#vjA@|*OsoAk1q^s<}uvYV9oCS|@!FS|)EyGbv*MfqKGYPw8Km#OJ8HC?8r%hYt4nl4k*Woo)iO_!{)$4j>D$Bv91cVTZ5JCu{kh-p$_4@1A($HUDN?Jq;Z8!V< zvb)(dA-2>X*+h0Gwk#{|w|#xL5J$2}f@~``L~-m&!^BPkC?UZy(DF+)f)rV{Q&@v6 z%OlTdZtm>!y!q#Oo!6N=_uTuO=RD_g&OP^@B7J3%zOqPPS){Kl(pMJgD~t4%Mf%F3 z?onsZJsRCd6uHNu?#^kirz+A{7U?UC^p!>3m-6W=i}aO6`pP1GsaEsSc&IiC7z3wcrI4bmH0efnNvbhC7z3w(ta*h;<;EU?K!TJuGU9-WlkyW zXB;Il?|+>m?Ugwt)q-=pGN&X>8oe^7gfdHMugoc_c8q>5R!VziPDxtzkzSco;<;EU z?U~pT&&5h9O#C~0oQ z|Mi;!CAB7_Bd!w9#Y*xG)i}?^N<0@UF>75?i}R5S9O;!gC1$WoYJE<7X1FA`@%4LU zPDyTK^vawP&&5hS7c1dBC7h?kvyzh9tj@r*l9F1k(~js$I8uq{CMC5*-51ZrO3a6s z)Vh77SLT$|#+~*vl#*KO?sS2u5Uxn=s?GJS5DKDSJtTc*!l=I)lcuVucJwX82!jHj3RUdnRneJXJ|^&#+P zaI0#EJ+g%#A^khxNBQ;t20sS=5&0h{eLLwtCjBR159k^GWxf=;oZ3ZtH|V#Ims5K{ zk4%?S{|J5#{5<$5xE~w_{j7PJFNH3r4v{_#9s$Qd&kwVIx6n_%*uPu&WztWBe(J~m z-9kTEVE=BRXT{mSTj-~s%c;|#=Wmx&FMuA8ET^V8@+HzQllGTFms78hew8D?N%{Gk?fGZ+1Q&XR1ABrC-E*-gxX|lo*b`jnCoIb;Yi~LAZ=lEQ%PB|f%lZ;^v!`b(k9d?|D}{hv7VN61H4X>>(PS*E2d^QF*beVIi6;!B~+ zd`pKN&y{nh|I3#`m-$lYa>ic@UDg+|bj^GzbUE{G(*9EDGG7W^&fG*!D>?5a?JtEc z^QF+`OgriKlkYEuF7u_(WqlFL=?{|MMfyXe{iV?5%*~{40XKjf!A;<1a0^JA;#)xM z!><4SE_d;J{QCQ(|A6!#lBRuSXkQuHSBCbLp?&eC(B;f0II@R-eUkJYr2mxkr$~RA z^q-ObbJBl7`d1wOKjeG{{BPi0pr67o^QBPj`JVctwDx=ly;iwGTvWkHw7bM$iBtBRIAza?Qxl*) zCr;%-drqA4bIcgeiSe8`WzUK6oH%9AiSe8`WzUII_MA9n&x!GzIAza?Q}&!VWzUII z_M8~ciBtBRIAza?`8sio=fwIhpY!cGacUa0=fo*LbC28kLY7|)6EoEXoE@thdXiSe8`W6z24oEXoEGxnS~W6y~*_M8~ciSe8`W6y~* z_M8~ciSe8m&xtekoH%38i8J<`7|)3__MA9l&xtekoLFDsGum@veTC0Ro5FMA%ty(w z=foL%PMopl#2I@|%ooYx4DAcgiSe8m&x!Gz7|)6EoS3f@#~FK0oU!M`e6K9d*mL5H zJtxlCbK;CWC+6$KF<&Q+^%Xwn*mGiih0kcuiS-pe<2}MR@timDoHykpR5w1SuW4Tc{Zxp}vSNd=F_wn@YbAlzS_!SW&pO zIxPH8;77pU0p-ui*H?&z9|Ql0{Ew5qo%A1*{u9dWA^mCorLPd{U-}BMa2Ker5G$>( z5DWDcV&Ptn{73L};OD_d!TsPc_(jSZ1vPh}{~iYQR-n>j;8UR9;8TvC;|TQ?V&Rv; zr@?;$HM^yJJ>?N;B(+9?&374^@sXZYfXjv3bAmCW3O)5GzMtAr`)$w7x>D^an_HlKvp+F47+&-A(#t(zk#c zz>VN0a5K0CMLx) zot_}A5sK2!lYYTzt!2_NnnQE?@0HF_Vulhkl$c4o#Ee#v8C_yVYr~8#F++(NO3YAV zh7vQBn9)4vbdaIMjOI3#ro;>-W+-t5C9a^v6_mJw5?4^-3QAl-i7O~^1tqSa#1)jd zf)ZCy;tEP!L5V9UaRnu=pu`oFSR+5bFR1Yzf5P7cH-ei|Yn8KA_f;c5-!1$I_&eZ7 zRgX3Jc@2JEqZrc1*w1SeLpp6guTczXw4c`~hICmEgS$Y@NGoRm)Qq&!k5ld!Im0NW z9|8}9=DbEOZF~yUcRZ9n27U?rGWaz3PoUn1(lL{u-oIA*E8ugWUAji`q0uf~gG<-Q zrF}h9l=2ekmq}~pS^2M!{w8O54g40UIcNR)FW~n;J*`mAG_@x+G%TW+8Ug;Mlqgq z?6fuh-n;M?j@;l{&==^9+6P&P66CaEULNbx(Lh>zTq^zN;GN)q2mh8M@0ZSN^aVU) zKRNnJq0%{W^wzM_yTCo5`|+CeK92nVIMOY#CjAfK{{kNa4{;58(xhMY?wgQWPP?zH z(fqdasSC|-JN>U51M`~S_VGUle*ylIvNV&g{AC!3!NjQkP(09s)Tjs1G3r5dRq8u* z9{P@&;4aeJ_;ow@VD++o-9f%1mYTq^N{wd1jeiH808y!)SvX(Mzl8dVk?=>p7eAp8 z+RbYGoI>axyhd~8KHj}{O<RlV5d&3$%M=-7-=dGlF z9n?E|%D<6(?MAKiJAJ3>4V``$Y3)X>^t(xGH)^F@z?;ZvCH-E~ZKU5vx}EgEM-3Gl zyIebJh@*yzjh(imh8l6Z6gz6D5x3Ef8fwICw4;VNYN!#nk30t2QA5SOMmuV#5x3E8 zEyPhn#l243QA3Tmjds)!M-6e*5JwGh)DTAvQ+Cu)aj(m@qlP$YsIj)sU`Gu#zBalQ zhd64e_||DVYKWtTif^5EyABoK8ttf|M$<++YN!#k(T*D8s3DFT;;12x8sexSjv8vD ztn;Mps3DFT;;12x8sexSjvC^qA&wg2s3DFT;;12x8sey-b{0}C;HV*v8sexSjvC^q zA&wg2s3DFTrtPSqzA|dGqlWsX=(Ny|8sey-zay%&9W_kbQ9~RxOxsaIeMi)2M-9_< z)G%#F4RO>kZAT5$cGNI!M-Bb#UT8-Ranuk;4RO>EM-6e*5JwI5#L!3DQ9~RxOxsaI zJrj3XcGM6@4K=H(R-kz-A&wg2s3DFT;;12x8sexSjv5Ab)G)B4hJhV5#8Jb*jvC^q zA&wg2sG*)MIvp@?l<%cB<=&xI za{@l*AHmOoTFIcCN5TEzFgU^)4uA*2FMyA8o>w{M40smQ>H?kTb?~R)dGLZ!<6@&$ zU<%iOYeDx5wTkME@ALW7nj05>0Ms)$r9GEYoAz8vt#(7uU8G${wcblY=oyvT^k-Cq zwfg3;QQxQ+ZsXVO{MtwQZ@}H0=OD*C&aX#Edyb-3t8t9_4w6u7EregIeoAO(uGPrG zzs_==U)|R-=@?9mK?-!=TC35tjt~B`OVrvGryuayf_~CFIVK10B4+>`1c$(V;8B;Z zQH;;!e=>Uje_*G44TXwU)zY zTL2fqH~E#j(>pIZ#;Y%cj=F2T21DrCj9QJPbUhkLIei=WyWsDGe+YgI{5bf>;3q)O zKh$b|&-iH&_A;=S`7h=$^Z$bX75wku{{a6IyqD{_58Mv^y{;!B_K1i*B4Uq-*drqL zh=@HRVvmT}BO>;Qh&>`=kBHbqBXgZIVl)>Kdql(@5wS-^>=6-rM8qBuu}4Jg5fOVt z#2yi`M?~xq5qm_$9ucueMC=g}dql(@5wS-^>=9|s&DY@ABO>;Qh&>`=kBHbKBKC-g zJtAU{h}a_{_K1i*B4Uq-*drqLh=@HRVvmT}BO>;Qh&>`=kBHbKBKC-gJtAU{h}a_{ z_K1i*B4Uq-*drqLh=@HRVvmT}BO>;Qh&>`=kBHbKBKC-gJtAU{h}a_{_K1i*B4Uq- z*drqLh=@HRVvmT}BO>;Qh&>`=kBHbKBKC-gJtATc?WJR#5PL+#9ucueMC=g}dql(@ z5wS-^>=6-rM8qBuu}4Jg5fOVt#2yi`M?~xq5qm_$9ucueMC=g}dql(@5wS-^>=6-r zM8qBuu}4Jg5fOVt#2yi`M?~xq5qm_$9ucueMC=g}dql(@5wS-^>=6-rM8qBuu}4Jg z5fOVt#2yi`M?~xq5qm_$9ucueMC=g}dql(@5wS-^>=6-rM8qBuu}4Jg5fOVt#2yi` zM?~xq5qm_$9ucueMC=g}dql(@5wS-^>=6-rM8qBuu}4Jg5fOVt#2yi`M?~xq5qm_$ z9ucueMC=g}dql(@5wS-^>=6-rM8qBuu}4Jg5fOVt#2yi`M?~xq5qm_$9ucueMC=g} zdql(@5wS-^>=6-rM8qBuu}4Jg5fOVt#2yi`M?~xq5qm_$9ucueMC=g}dql(@5wS-^ z>=6-rM8qBuu}4Jg5fOVt#2yi`M?~xq5qm_$9ucueMC=g}dql(@5wS;>*dt5qktO!X z5_@EcJ+j0eSz?bYu}7BJBTMX&CHBbbN$7Bp)ss-8V~?z!gc==tWK)hkvMI+N*_30C zY|61mHs#nOtET`y#<53MGyg`%9$8|KtY+_>cI=T&xsT2gdt`|{vcw+Qv}2E~W)!s} z1+hn#*dt5qktO!XrX71^i9NE!9$8|KEU`zH*dt5qktO!X5_@EcJ+j0e*|cMiY}&C$ zHtpCWn|ADx)x4$4b?lMV?4{F=J+j0eSz?bYu}7BJBTMX&CHBY?dt}qUx-Z8bS?%;> zbnl!c_Q-0d2B+P7W{Ewr#2#5QWqgWQjepfn$$s;MgM@ zIQGZ}jy zM>gZwBb#yTkv$ZCe)=-4BhaqN*L_Q(=@WHpEH9LFA6Vvj7bM>gZwBb#yTkv z$YvaSWHXLEvKhx7*^Fb4tY(t6(~0yjE!?ItT9Y&&^gbHF$5YxhK&br!f{zD&e)Mt8 z=T8NKe_9XR~Y@Yt_QE^!7F;?1G*}Fpa&o5;VD~BTC19suT{;$#7KMW2}0jX;F-oA zp0D-re5yzK)S0DEqn}3gNS{VOhw9-8RFCxOw4XZlNS{VOY3h+ajaFR`s_Q{@J*e)J zemf)hq<9vpbfexk5AKk<#)W>abcfV6E%bTrP*h{oDjlJABvQvu&J z1~)rD_%Qfs@Xw5y&-&NQ-;w?Y;hie+Gr~`RF7ZxEyfftz?@YPGJ5w(4PL*hE1zqBu zTH9!JiFc|*qyXEtjgS!>QO$+rE z3!zpF3Xg%~;BoL-ew`rgXD)ZApC|ny_%-k)j(G*tias6l1MsSmTDY59xI5V9;}xMf z|9*SQd3izhc-&GKXU>&FxgUZobL7~>|2(>a$_;zw`RGK}% zgx2$4DjuE|{s6pcgcEk}QhGZ%-!bZJ#v6tAs2<0Kkx})f9MzQ3PcZLM|7(1SoF9XB ziF;Jz%2$mW9{_iXy?fN38jo^}Yxy3r>SO$r^B!^QU-bnfq3ib^^^(RHIfk;tq>q2o zsQzwP_!e-TkK`HUy}IVz!M(a>q2CD-dS2q*^iOo=d;KntP;co99VguDx6Fcjb@&D8kUOfBeHg?s7K@1-CAtlyssKC9@+Xf=LTaglM> zsHn!+5AFg7z(H^b+y_1jo&>)NejR)nd}KC1}CxBxDKiBY2r<0{a7#AkJ##v6p& zR3rBZ-LGwviiU+pK+hv>=F`NX2R6Lig9( z0{3y-f)Q{G^lF@Kip`wwcx)R=+eSRLjd*OEl;&g1+cqi9X)~}*ZP{t_uubup(_Uk< zO$s!cjcxv(wr~!7lYFzWEt3K3T%zCj6TXGCIoYOmsxzR~?J%<)X0~grIvs4+DAhOv zTDRNL?RJe=o$n_U+tKZIjb5Ge3(y+g4oll%X}dNqg3N+wa4w!lJTwNc=l|&#;VgnFYNWgUN5@pMOVFy z5qi;8FS_bQSG}x!=tWn(=&BdSdSR>=UG>VZhJ#*o)r+or(N!eW}IRIVJ%$5>ar z=&Bc8^`fg@bk&QldeK!cy6Qz&z38eJUG<`?UUb!qu6of`FS_bQSH1E&mt|e`qN`r{ z-hE12SH0+}m$uf6u6of`AI$W@Odq=HLsxz1st-TxLsxz1st;ZDp{qW0)rYS7@Wwt^ z>Vu^|bk&Eh`p{J$y6Qt$edwwWUG<@>KFxJZ2YvWwAG+#8SAFQJ4_)=)rG4nC4_)<% zw_*Luy6Qt$eYj{Jy6Qt$eVYC7nXRin&3G8Ct3Gtqhpzh2RUf+QLsxz1st;ZDp{qW0 z)rX_@p{u_V!@etOUQi74)uS}q6oOD#r62=@~q+^_#m z2lwm0)4>D!?|s60qhg*Z;W4?^1Dd&V+R?=W^wAH{M?avMDE&*N=y;W4+~(uysUJ{u zq2m=@_?UC#&wxKM%8iZge;-hUpd;ziA5d)Iw0rgkrI5=)$G{KLOFk%7IQx=|OGYWd=xF)D;0Yh2+H`snbPxET>drY|1-}lu*LzU4=6v^h52}uw)_YjO7)*@x zcMsCvJ*YZzj^4u(t{3*he?R>9tGz3S=&@g|-sz`w=6<5bezEHGanR9YzZiCoqsM-t z$9{j6OX;tHjvo8{RW6~U$9~m<(a~c+b=^;0_Y*z#6Fv45J@(5nbRIO&j|Tb!_sji( zqsM-Eh0*ofk2d}I*iZD>FNNp}2qqr!`1BL8BAv;jW4iw^@C3gqjSyHIz=(6yToMfj|ai4IU^aS`7 ze%1So%J&M}o#}6q*4JE>cFWo+4LI!{c_+@f6Sv%{yLOKI-<|%NtI)mhPR$|vY*+c0 zzUCTuUrSwylw)*{yi-w`j**IVJyMa*uL#XKJNR`MY4^)JHRI%b_s%;t@8q<-bZ0O` zdLQVXdZ)kUD%96pg;x7c+;yjBqMUZ$y_4Q&C;iS&^*hed*Ib3Kkbaf4=LvU8b-pS` zI6Ikz-YM1jYJURSb$2Qb^qK9wI~5H&ZNJ*7St+OO!#nA-b~69G6Yt&0{PRv6c&D_d zvZOtgr6^JV!iRU_z&oWw|9Yc-eTY{75Uu_p9P%L?@*y1ZA=>6cw9SX`#)ojlhj6@y z@VXqT$f1fHs>q>=9ID8nik$pmILIlMzAUsVa;PGQDsn1!Tsc-n4prn(MGjTuP(=<^ zq>=oaQ8bq*aka6**LqLlrqxkwXq>=9ID8niX5uQp^6-;$f1fHs>q>=9ID8niX5uQ zp^Ar5#lxuLVN~%js(2VxJd7$HMimdEiic6f!>Hn6RI!UQ?BWc&IKwW^u!}S7;tabu z!!FLSi!pMR5XnW|<_Ryp4p-0<8kG6*%Z4W)#9(uGr z^k{qN(e}`z?V(58LyxwH9&Haj+8%neJ@jaM=+XAjqwP_9QMvSJd+5>j(4+04N83Y> zwuc^V4?Wr*dbBKpgD7MWg$$yQK@>8GLIzRDAPN~oA%iGn5QPk) zkUKpgD7MWg$$yQK@>8GLIzRDAPN~I<{3mGgD7MWg$$yQK@>8GLIzRDAPN~oA%iGn z5QPk)kUEnLnvejg$$vPArvx%LWWSt5DFPWAwwu+2!#xx z5O$gl*lAk0O|5bWg$$vPArvx%LWWSt5DFPWAwwu+2!#xxkRcQ@ghGZ;$Pfw{LLoya zWC(=}p^zaIGK4~gP{EnLnvejg$$vPArvx% zLWWSt5DIyO_V@_x@ew@#5pgmdJc8#xLaTX%R`Up+{|KJ{2%i54p1+S-yM4^s?Mt81 zfA=v{v5)v+AG3D*n6=xdeqX<;$2WS`Zl8L2qi5~*sZTe0)@~pD_&)maee~n|=)w0% zUH)|*^sL=J^~FZdC+uU^ZXdID`=l%9{2F+J@N@nmdhj`a5k2@EzkZHiKTjL^JZ)-#c-S2i}QWC>>4IB37F+4-I;-mkhddiHF;;x41dMEg~P&iAN!f8Y_vez}Ct z;CZwCatWj7iudCZ`*Df=sxO^c^=0&o*<;=VNLX)_KkOFz+8&c9IPH=0V{!whJsN#X z+V-zM0IwRo2aqreZX;(q=%=fX(Yha_{XRx(eN3%YXOsT@-*cefD11!q)acRcW3<7? zXoHV2Yw;Mf7LTb7>c46=I#R9A=^K?EMtj3(Z;x8!)J?a_Jp7U)&&k~HNF2;pN$npC55!Hxuto9LHVg#2M@i)+v$7{St)(?0v;Gm> zbwpz;pTQnGqOq0JcG?k*t(>;sj%aM2Vv;BNTqcf-Vtuvv$VkCH;^jEpBuY)h~ zUytQSpYks| z&q(m^AoZwkn)wXwQ${q_^O@bVjA*RqwELG4jrE*fBAvJteZfrs(ihB(HO{BKjHuQ7 zSN9qtYWq(6S@{S(&Imouh}^(Ac7qXp!OUlH4>h8(q4U?78I2H~emiKdIG}bnCG`B~ z0lAsccv;)$)(e8SHG5Z1OQ^%+`H)g@R{Ht{39M9DpU_5?+k@x|| z;0G9YA7GSyfbsPKaqitp|xE4$1?SmisAR?q_rldypRXAU*6s^{~!A z#*rS=9i)dns25DWUJ$yV#El zeb?+|FZ`dW-xfY74`*L{q1!wA+6&#r+1Fm^nCfwOV0U|^-4Y*%jmOnHIPIR=JKY;! zcDeM|kE`7|?OywFG2ma_I@tAI=oaB!@0HITvD3ZM*6`!RAx}t|mxCvyN#hLoI_Mer zC!|c{FO2d%;|@??GFN&JsPDxo{deFA@Si}>!#_cf_Jpp@>7RmEK+gs|AvGF3zxsqU zY0QF-37>%fC!|d0|GMx=V&Ere@U+Z62aF4^f+ksLexM?IEuA5Vd)T+B{5M9HtfyQwxU~j~r$Uco-)+ z4F882(;bHS!!Ums<`2XCVVFM*^M~R5Fq|J|9CsMUILv77u&#ePI4sVGg?_4jn9^rX<^Zyk5KSh7~6nDX%^2+}P zzuI-5;>y`6Ug<03_<6)r@c$H7&W`W_d%+96mf$J)KMMax;r}T7ABF#;@PCwRJ_`Rw z;r}T7ABF#;@P8EkkHY^^_&*B&N8$e{{2%4YkHY^^_&*B&N8$e{{2%2mj>7*@_&*B& zN8$e{cX1T{kHY^^_&*B&N8$e{{2xRA$I$;V_&)~!$GDec=>Hh}A4C7g;Qtu>AA|p6 z=>Hh}AA|p6@XucJ0lUl#&Hpj<&;IgCJI*-<|Hsh(G5BYf`QRA(KZgE~!T&M%{}R2x zmzZbx5_j|^?&!;m^}ftl@5_wfzRU>DJG>7E-r;>(=<(FkjHlS=U1^V}o@PAd-QIUA z?eUa%dpCZ?|Du-J?Okcd4^K0m@}BQbJ7)Ht?>@7~Q|$RJ^myv&w8vB4^WEt2l=po1 zkseQZ&v&E8Q{MC4X^*G8=eu(}o?@SOp~q9~^Dgvw%KN+Vyu-WB#(2s*ygTjjly`VHdOYPF z-hHIUQ{LO%X^*G8x4Vz=c*=Xb`&W;rytlitpB#^;*w0<)@f7>H3q77)2%6qu`Umj1fhr5t^WIV<0?aJ|Zirw3V9#64*yU^n)c5fGY zJmtOGRU+dl_G(wU)@Nos<-OWn2*0L!d`9Ce z=lodAJcFY?lfK}zJWBtSM;RaRk&1`!6Z#7_&uE;be<>pMkrO_fVo|5_3xQ+*&;XF>?cbw}#&XphMnvZj}$GOhqxJIC{fCzwAxLGN>d-sc4KhbMHu`c?O9w4a>NojUE&)(PFI(T;IK_vo}+ z{R!p|PcVOYg89P}x_AA`e8>sf?+NkX9ItvhAs#LVCy7r^(sP}p=Q>Gza*{eaiC3S* zflm^XoFpbWNlbE*nB*i*dy<&sBr(ZJYUCs}auUZoiPxQ^MotoeoFoD{Nd$6|Iyy=0 zagx~MBz|%dKRHS4F(H50tr;t;YeN2@G*>>M9(h=4ufUm5U+nY*Xq`-OM-$9#PUyb$ zU-iO1=3AiWkSF9Y{;y{>C+LMI)C>EV?}1*CJ0bt^kv}9o4QhV}<#^_KLcOrj>sTge zxf7~!m!!p?=xvOQ8GZ3H8g)(f$s?pL3qeYN1RYMc3(^FHaMZ)**RWEG$FV2 zk$vR+HTbvSgP?oo33;iHbjzKf+JffVC!#M3WIN|*rgpTMY)Ki$Ne<6*2qoH5W4+NFbg`Nr!cB<_1*s0FF}u3C)DrwNY8~%sP}Q&Gd~mRgPitU z=!6`=*Y7u>CgcD{_vRDc-$59FH9itIm{5z;f7O2(?Z6Z2#f+;t($9A$)SDaE_`bZq zgU~Ze6YAr9q#b@jJ)P5DRW+ghZg((AZ$3$HK1pvrNpC($Z$3$HK1pvrNpC)>mU20m zq&J_WH=m?8pQJaRq&J@=s+^=ZpQJaRq&J_WH=m?8pQJaRq&J_WH=m?8pQJaRq&J_W zH=m?8pQJaRq&J_WH=m?8pQJaRq&J_WH=m?8pQJa><3)K~D31%}85iUk5#$*W+ zf1b!cPvoB`^3N0b=T#%SgFJqcSB>a+;`}^*k|)m36X)lN^Yg^{dE)#$aeiKLzOIB` zCa-$*89a}gS8Y0N_sFYGowj@ARkKdpJ@WKEdDXIW9OvhW^Yg^{dE)#$v3;J{K2L0) zC#uiOF?_tE`aF)2mri^hJ4Rk=aoV%8dAWhnF??P=;Pk7YBlbKId!C3rPsE-lV$ZAX z`$&)4@agx$L;yRFc9#&kkH{0x=ZWX@^r3mF z*T>rv^3t%=_Jq8Y>~!LP5y|I?GtEURI zsRC`PK$|MirV6yF0&S{5n<~(z3bd&LZK^<ofi_j3O%-TU1=>`BHuW5B z>N(ofbF``FXj9M8rkEeh{i{cprx>Z7qE1i2|0$S11?Q(=`xH!`g2_|xc1lslba0wj;xtjjX`+bJ zL=mTTN0;@hX9iBI-3f^kP7@)Vmj0dN@&0LP-stiEX{prc@&0M))97*5XJj9=pjS*yQTtPx zo%R{b=al9doHnadnon@r+)goWonqWN#kh4!GYtOK+)inftuzcwX{_zEXPKrLaZjOy zmvryL!ArV#A$RwZ#$VG)`@UY%C|jue(yzKNqZRuSSN>AqapFrF1sJW^mvlYGWiU3X z^l_obo-a}2%VKppc$v9^mzgVgS!_7R?`OR%9)!Ab<6DH^pw_-Yt$l-9`v$f43g>x+ z^Sr`&Ug12iaGqB<&nukg70&Z2=XsU$yvliA1Sx;XK3SR)W)ZSGdyKDqgqy) z)_sPj3})@|Ga`hAwy)Vhs+%J!OCx6ya;nsjKi7rllHy~dTlrk3uU zE1;k9yr!0J^p(G+mTt^~e#-NjTK9BtmezNc)^}Dd_cOs+YW6I(aF*70R?3`GzOVnR zl&Lgr?JRBWtj67!mE#t7R(jAe!9(QaNIy*a5%3uQwcgH3!#$9}Mv)ubx-1saEoW+gL!oykG=2_S{OG`Yi>#XWa=VaFFtZL2a z^}=s)U*DpXZ*l%_afWa4-*4k)-^R_pO^tt>8vhP@{tkNn4to9$dj2lQf0yIG%kkgk z`0sK2_c;E09REFz{~^c!kmG;I@jvAFX^x-fczttJoJ@24IpyCMoKwC~ZaFOUe8M@^ znseNC&Z*X%;~9W+xXL;1@f@ylPG{4RI-BtxAFsO8k*d3KVGewh{1I>r^gQi3{O6on zy8r9G@|n!o!Eb-o~7*>u(K+{6M ze>$6finM#KS&fE_$3efXGn=*>%&IP?gzkT5S!X+o|IeyMe9SALM`yEX_q?-2lCwmT zvqX}!8dK=M#FMkEw4bHFn5BoBrH7hjE$(daq|cz*F?xo4mOg8iK5I7c>Zw`Pi+_EQ zw0n)&;0*X}&||<^dW~5{^8VF6Kdb27=oP%PthAqHrTr``?PpnOKg&w{S=E=0VU_PJ zt9)nis9D@;R#CTq^%!$j^<{iJIUaAGr*_U$JLj4EJuk&7Uy*~+bGGNDUZ*`*e_m09 zka|2%eVu1c^1PJke9zUN4;&SomkynF%yVAaGkTuzy!7VuCDJ9*%U}#T+Bwf${ds2R z&P#R9@m&3RDeZDFheGC1$Q%lpLm_i0WDbSQX}mlg%%PAu6f&2#LgrA&91593A#*5X z4u#C2kU11G$5>+yh0LLlITSL7LgrA&91593A#*5X4u#C2kU11GheGC1$Q%lpLm_i0 zWDbSQp^!NgGDlo7heGBw`qN!7qM1V>b0}mEh0LLlITSL7LgrA&91593A#*5X4u#C2 zkU11GheGC1$Q%lpLm_i0WDbSQF?zayLN1_?3n=6Q3b}wnE})PLDC7bPxqw10ppXkF zykP9f}0t&f+LN1_?3n=6Q3b}wnE)W%8AS%8uVi`2+PJoX}S;6>uVi+Jos z-1Q=H;6>uVOT>YfhyyPX2VP3Qu5(`EUM>*_ULp>>L>zdDIPem2;3eX~OB&_rc;diI z#DSNH121tGm$?2*f#bkS#6Op~@=L^lmxu!|X~gGW9S2_G$}bTIULp>>q*0#oi38uD zg}y-xeS=o>2Ce1|TE`o-jyGrpZ_o+Zs#|P%| zfqCv|o;#Yy2j=mCd3<0VMa^@k^W5n?J}{3D%;N*|_`p02%)`JuJ}{3D%%iS(bTy9; z%;N*|_`p26n#Tv`@qu}KU>+Zs#|P%|fq8sj9v_&;2j)@TJU%dw56r{-Jj~DI1M~R6 zJU%dw56t5OSE!LI)W{Wl;0iu)1s}MA4_v_quHXY#@PRAT-4*KY3O;ZJAGm@KT)_vf z-~(6ifh+jH6@1_dK5zvexPlK{!3VD316S~YEBL?_eBcT`a0MT@f)6a9kOdU7fI=2f z$N~ykKp_h#WC4XNppXR=vVcMsP{;xbSwJBRC}aVJETE7D6taLq7Es6n3RyrQ3n*j( zg)E?u1r)M?LKaZS0t#6`AqyyE0fj7}kOdU7fI=2f$N~ykKp_h#WC4XNppXR=vVcMs zP{;xbSwJBRC}aVJETE7D6taLq7Es6n3RyrQ3n*j(g)E?u1r)M?LKaZS0t&f`Law5a zt0?3u3b~3xuA-2uDC8;%xr#!rqL8a7Vm8k*-H7(vgaIo#WZU>%lJ4o-@3z=-2t4IlQhI z*lEX&*A)pn?Ju8PCx*PPXJIbO-^01C*x31=UA(Rc*=f%)UKiU&&(&O4Y;5$J&+Cei zo%Wi~>r$P#lIna_j+U=Wb-qro54kSY89f_$T~V~p>^aHnilv=)M0#BjwbPDEudBX< zim3H3qSNb&tDW{-<#lOKWl4J~OVPFdMbvtosP(#Z=wENtuO(W2iB?}y+nf$csu!b6 zEYUVgw9S(EbdKj~OFFahMqwFMlu<<)Rg_Uh8C8@~MOpqZ9F#Rqxh%9Q%BZ4@D#|K% zTsb~-8C8@~MHy9;QAHV5lu<>Q@8OhDMHy9;QAHV5lu<<)Rg_Uh8C8@~MHy9;QAHV5 zlu<>Q5kwhPlu<<)Rg_Uh8C8@~MHy9;QAHV5lu<<)Rg_Uh8C8@~MHy9;QAHV5lu<<) zRg_Uh8C8@~MHy9;QAHV5lu<<)Rg_Uh8C8@~MHy9;QAHV5lu<<)Rg_Uh8C8@~MHy9; zQAHV5lu<<)Rg_W1GOAcc70ak%8C5K!ie*%>j4GB<#WJc`MitAbqJkU-qly?+#Hb=h6)~!a zQHA$?-W^m~)#=@zm1YK`iZ-ffqlz}FXrs!^MpfFF){%Z=y()!_3(v|=s;ug)>Pmbb zuj;JQlUCFJ!tq|!SxtLYUN!AG^Qx}aM|xFfHSHC8RVm8<@~Y0N)`1x9##QyjF2$=l zt5TYCJVRJbd&N#wsxx|3XO&f*RrS$6(yKbFX|L+6rr+Rruj;I(y{fY+mHIqh=~tCX zo%X8Es@OAnRcBQzLyTV4S=IUwr@gAP%Bs#Pt2(Q!>hw<8`WJexO3ykQt2(R9_EcHb zS!Gpc6@^z-BR;;5v;8&bRh?Bm_c!+YYNdRi=ONM$gPtj>suehYfV5Y2R+%-bsuegr zM7~#bR@D}aUe#F*ysERRH6%u_>Z}s6RC)iR8aQ&OvZ}MH7)JN2^(4-56j2Sls#Ewd)2lhst2(Q+@v2&)?u%8ORp#8PYUw`Gt2(P{?@l{5sH(N@&Uo+j zVWFNG2^CRfQfg~cLe1n0e?a~2J<0EyaPU{^F;f>14aCaH*F2mhr{N`6CV@DDms*VfwB@Ln8{1T3nqjjE2YZZY| zz9f_{2^HlE^(76VR;CHHR#2#@PpGI*_|F_KcT!p_KZRQPDb&hOp)@Ac%1@!z5DNd5 ze`)2X(t7hts5ifaT0JO~BMG(sQz%CgYW=5h4%GTjrM3Q3C@&J~%`f54`LEW0Dy=t$ zgnIK!_)F4SRjBkLX}$TSbdj{){8CzPeq}P$W`^3#P@5Tfk^V((W>lLxn^&(1?{>Lf zy(Zjd4pqxOvX30S`K7ep{1WQTFQHsWs5ifaavq`H{1VD}gnIK!s1>0?z4;}S^9bcR zLcRGV)QV7{zN8`4n_oh``6YaUW4;LL%`fE~0re#frS;~Q@XO?Aji}OEBPx{t2=(Td zQ2ry-n_oh$Di_Lag!+<(P;MiX+X%I4RH#vaP@@2$Mgc;N0)%oKA=;4J_-tAUEYzD{ zLiAv_Q5p@%ZOofikP7wYmr!qh3FS7ze+Q{YuWD0{X5fW-^Ghh75o*LF)JjpI-ux2E zXM}Q&>ss3bnf_VZ9MQS>YH@Y5U0v$9O`G2Zb6B3N;cGYVC*6ezHP(GiE`J z`;@kOtZ?Ke)c8)g2h^BOX{`wnYSbpwcui>cSm6jtsBxB1;~k;KR+$x!k%Ssa3GE&$ z91#h%_Csj*Scyxl^g0Bk?FK7xgO&KeO2rS((W-3W1*d5XE4|iE=?CRPD^dGObiNXW zuSDA`QT0kxy;41+|7#ttM1d>S>pA@bsI_)VYpt?SZ*mF0LB7`7Dg7#Gjk1-tDpsP0 zl_+7QYG3)(=1Pt6^(%F^QhmX6#`{)Z7TViuR2N2jdyVeMXos&+jR+Lii6oo20aTCWQGA=0lhdVLpWU5Y9t54?TmV<2A+? za!y^p(=SWUp<@Z*_sP-NS!uH!!gdJTp=XMelNi;qjH^JmrjR=d;Xm|KuuLud*TR1- z{MW+2cf<6r=D!yHYvI2Z{%hgC7XEADzZU*$;lCFCYvI2Z{%hgC7XEADzZU*$;lCFC zYvI2Z{=F0BbjEv78r`4P!v8AGWesOmX)a5snZt3R_H-6LB^|C(?`gE7uF?$QeL{T! zM))H5HSi^l|7V?fmD-Mfb?>%{x?80dq#VtC>HM1eGHxU1uY8Q^)W2%gqEM?Ag^z>w z{8gGE)Rm|mIbSPqgjz!-%!36`yG1LfQOS_f_(0r)R*QfbNA?;nk}&f9SOP&{dj0G`O$)S;O=G*gFW>d;IbnyFK}))_RbJTA0m>bT!J?zE0Ot>aGXxW_u~u@24D z1=dU*nyEuGb!esz&D6m|9h#|wjXE?_2PbuCrcN`=Dm}1f>R_o3&D6nF9h#|wu{tzU z2XA#~rVjS%&`cd1)}fg?G*hSk-RHDs>fp8x&D5cpIy6&2!T)ObUk(4O;czt^u0}JfVRAK0u7=6gXl6Bhu7=OmaJ3qiR>RL~ z*jNn@t6^X@_r99DUd{ck=Dt>=nbl}!HJVw?9j)eGR&y7tb^ZGO9hzCqHNS=4_AOrZ zmw5|!_ZIH!*K{wJGry*L5$Xz!T49x`=N{|1$9gnYkH+fJSUno6M`QJ9tR9Wkqp^B4 zR*%N&;in#c>S3lHX6j+49!~1vq#ljcqp^B4R*%N&(O5kitB1FGG*%CL^=Paf4(ria zJsPV=WA(6FkH+fZwjPbu!*D$stB2=$G*%DW^=Paf&g;=wJsPV=WA$jPp1P<BjjiFD8@T2MuDJotG@zLVG}C})8qiDwnrT2Y4QQqT%`~8y2JW|k`)%M( z8@SU3?zDk>Y~UUn&`blGX+Sd#Xr=+pG@zLVcxXT~4Y1LGW*Xq60nId^nFch|080&M zrU9-R&`bl2HK3UWcxym24Y1dMW*XqI0nId^nFch|fMy!twgJsFpqU0V(|~3gV7LLz zG{AEMnrVRT1~k)vW*X2;1Da_-GY#;+7XH`5|5`X)3x{jb%vzXS3zKVMaxI$CKJD^~ zweYzXuGYfRTKHKD8*AZVEex#X-q&*1Yq{UG+}Bz(vlh*)MKf!;qqW@2TJB;knpulx z)^g1^Xhbufxj`cup%ijicwD{A4N{2F(c=xC9Tj>Eb%SbL$EcQ#Iq-3gnE>@pf%5fE zfzUGyH>i$`=g4t1euHYnc+vS{+ZYPpD)x*Xzr0oKT^9Ptw~9BT)--0`Dz5aaxH3LL z&S~&9@Df-8wO&!jXuV?Qtzy7f3pyHkD|NR{C64PGA08*JQ+v^S8fq^_k6hNl!#eTc z9P_Y_n0%euh;x2Sj>kvqbX7WouFANLoCm<2U=B1(>(mPLU)8VE6Qn&RTBlZE)OvWK zd0Qv_`^XnaQ@WJzeDk?ZYBy>ns?g)jbz;?MR@X_-LbzQAx9d>vI&`~Eiq)A_`_q~A zD0V%HU5{edquBK*c0Gz+k7C!O*!3uOJ&IkAV%MYC^(b~did~Ol*Q40=D0V%HU5{ed zquBK*c0Gz+k7C!O*!3uOJ&IkAV%MYC^(b~dihUc`^ES@>HqQJu&iOX}`*!--x6{wQ zo!0tx>iS0A>E+Cgx>KR9-{^k!9m>B?s2ND%P2%JosrP}}X;kSCk-iz!PNT}vPNTw& z;3my!yu&+<3jY!O9Qb)qE9#ZM9~=g?E3tAswtYv+_4tm|S@7H7>)=np^PtuBj;eee&#kAWWt{}}uP_(||j!B2y~I?ug6f95_=^Y%*ry-Il}{J#_a-wFTkg#SkP zZ-oCw_-};&M(^~RX@vhq@ARs)`EP{(M)+?`ng2%kZ-oEGl=*M;POn1q-w6MW-sx3o z^WO;njqu+H|BWg0-*@V=~emWzY+c$z0<4G=D!jC z8`I{$F>U@E;lC078{xkZ{u|-H5&j$DzY+c$Gv>e1JG~0ce`Ch{H)hO#W5)b9X3T%1 zcX}0?|Hh2@Z_JqgM)+^^POnOv|98RvyWsy_@c%COZ-W0O_-}&$CiriH|0eivg8wG? zZ-W0O_-}&$CiriH|0eivg8wG?Z-W0O_-}&$CiriH|0eivg8wG?Z-W0O_-}&$CiriH z|0eivg8wG?Z-W0O_-}&$CiriH|0eivg8wG?Z-W0O_-}&$CiriH|0eivg8wG?Z-W0O z_-}&$CiriH|0eivg8wG?Z-W0O_-}&$Cis6h{J$Ii-wprohW}>xZ-)P7_-}^)X83Q0 z|7Q4ahW}>xZ-)P7_-}^)X83Q0|7Q4ahW}>xZ-)P7_-}^)X83Q0|7Q4ahW}>xZ-)P7 z_-}^)X83Q0|7Q4ahW}>xZ-)P7_-}^)X83Q0|7Q4ahW}>xZ-)P7_-}^)X83Q0|7Q4a zhW}>xZ-)P7_-}^)X83Q0|7Q4ahW}>xZ-)P7_-}^)_rU*q;Qu}F{~q{nf&UixZ-M_7 z_-}##7Wi+0{}%Xff&UixZ-M_7_-}##7Wi+0{}%Xff&UixZ-M_7_-}##7Wi+0{}%Xf zf&UixZ-M_7_-}##7Wi+0{}%Xff&UixZ-M_7_-}##7Wi+0{}%Xff&UixZ-M_7_-}## z7Wi+0{}%Xff&UixZ-M_7_-}##7Wi+0{}%Xff&UixZ-M_7_`eDMZ-W1u;QuE0Z-xI> z_-}>(R`_p)|5o^Kh5uIgZ-xI>_-}>(R`_p)|5o^Kh5uIgZ-xI>_-}>(R`_p)|5o^K zh5uIgZ-xI>_-}>(R`_p)|5o^Kh5uIgZ-xI>_-}>(R`_p)|5o^Kh5uIgZ-xI>_-}>( zR`_p)|5o^Kh5uIgZ-xI>_-}>(R`_p)|5o^Kh5uIgZ-xI>_-}>(R``D}{J$6e-wXfm zh5t7AZ-f6f_-}*%Hu!IY|2FtBP|4#Vtg#S+X?}YzO`0s@OPWbPH|4#Vtg#S+X?}YzO z`0s@OPWbPH|4#Vtg#S+X?}YzO`0s@OPWbPH|4#Vtg#S+X?}YzO`0s@OPWbPH|4#Vt zg#S+X?}YzO`0s@OPWbPH|4#Vtg#S+X?}YzO`0s@OPWbPH|4#Vtg#S+X?}YzO`0s@O zPWbPH|4#Vtg#S+X{~-K-5dJ?1{~v_^F8J?)|1S9Ng8we~?}Gm>`0s-MF8J?)|1S9N zg8we~?}Gm>`0s-MF8J?)|1S9Ng8we~?}Gm>`0s-MF8J?)|1S9Ng8we~?}Gm>`0s-M zF8J?)|1S9Ng8we~?}Gm>`0s-MF8J?)|1S9Ng8we~?}Gm>`0s-MF8J?)|1S9Ng8we~ z?}Gm>`0s-MF8J?)|1S9Ng8vV}|A*lJL-7A0`0s}QZuswp|8Ds2hW~E(?}q>TE&O^*$|LJr zQg?tJU*D4Y6!>Y)7u}NbT-+_`-vBo`Cw(ip8LW`+`L|mrY)<(+ONLd>xYa?ZCq^ymUwUM$mQr1Sw+DKU&DQhETZKSM?l=WMbwTZGeQPw8P z+C*8KC~FgCZKAAAl(mVnHc{3l%GyL(n<#4&Wo@FYO_a5XvVNPgZl$bSDeG3sx|OnS zrL0>i>sHFTm9lQ7tXnDTR?51SvTmiUTPf>S%DR=ZZl$dMKv|n9YcpkSrmW4BwVARu zQ`Tn6+DuuSDQh!jZKkZvl(m_%HdEGS%Gyj>nTU9|DdBHQ!?(%DjK4*` z6@FXlw?WUD-mq4!|x=p^M^UIfvxA++Ol995~zx98r z`||L%inIGWGuQH-1e}G0Bq)I_B(Zbl-4GV9i5Eq26eYnp#8{wO1({}C%sZuy)~#Oy&_9`rL1}bQja$v^?ao|Urd2L0CpPefv_`R zXTcr}I~O(|c0Q~Jwg@(+@+ZAgmcDP0>=2c_0nuqdbQ%zy21KU;(P=<*8W5cZM5h7K zX+U%u5S<1@rvcGvKy(@qod!gw0nuqhbQ%$zMntC((P>0<8WEjFM5mFSH6MsZM5obE z(P>0<8WEjFLq(_2P|;~LRCF5YS)jQ0@gh22M8}Khco7{hqT@w$yoin$(eWZWUPQ->=y(ww zFQVf`bi9a;7t!$|I$lJ_i|BX}9WSEeMRdG~ju+AKB063~$BXEA5gjk0<3)75h>jQ0 z@gh22M8}Kh_`sVFy!pVJ54`!nn-9GCz?%=e`M{eGy!pVJ54`!nn-9GCz?%=e`M{eG zy!pVJ54`!nn-9GCz?%=e`M{eGy!pVJ54`!nn-9GCz?%=e`M{eGy!pVJ54`!nn-9GC zz?%=e`M{eGy!pVJ54`!nn-9GCz?%=e`M{eGy!pVJ54<&lw`TCx4Bnc-TQhiT25-&a ztr@&EgSTez)(qa7!CNzUYX)!4;H??FHG{Wi@YW38n!#H$cxwi4&ETyWyfuTjX7JVw z-kQN%Gk9wTZ_VJX8N4-vw`TCx4Bnc-TQhiT25-&atr@&EgSTez)(qa7!CNzUYX)!4 z;H??FHG{Wi@YW38n!%eNy!pYKAH4a&n;*RS!J8kv`N5kXy!pYKAH4a&n;*RS!J8kv z`N5kXy!pYKAH4a&n;*RS!J8kv`N5kXy!pYKAH4a&n;*RS!J8kv`N5kXy!pYKAH4a& zn;*RS!J8kv`N5kXy!pYKAH4a&n;*RS!J8kv`N5kXy!pYKAH4a&TL8QTz*_*k1;ASX zyam8p0K5gjTL8QTz*_*k1;ASXyam8p0K5gjTL8QTz*_*k1;ASXyam8p0K5gjTL8QT zz*_*k1;ASXyam8p0K5gjTL8QTz*_*k1;ASXyam8p0K5gjTL8QTz*_*k1;ASXyam8p z0K5gjTL8QTz*_*k1;E=%quy95RvIf{k21Q+Z-G4;wiWh%W!VgM4x0sAhCScHey1!i zR{MDg>?+tcWyOFxD$azzooovbTY%VND8v>ZwipVr#ZZVXhC*xsVha#km_lq}3bBPL z#1{MI+67sv`IHaU zd}UXvJyi3RJpgtZ?18W|U}wP|3_BM#A9g;h2eyc8H!;&qb_J}eZ{1*~8_aZrnQk!C zP0Y|yVn$h2-@3s}H<;-rW@ryFqwFf!Hf6y~H!-99?PPm_*bBs7#G)67y+G^*VlNPT zf!GVgULf`Yu@{KFKnBlvvx7e+Qp13fORD-ee#s9x(b%Q1(f`&VXuLuZ|tN!dtk4FrO&0(o*Q6qgS{R0 z4%lD9-U)j*tXdf!Gt`>5n4wmn#SFEIK1K?l?&vo-=OOs&^CK~Os;d2u!dL5>V#ed} z)#|30@g#h;#wljdFOQH_D{W$i`qWs=pwFn1rO&96Ri7G*8T1)dvh;~&vh+IH2iX|Qv#Cm(h`tOvFTwgh$o@;My#NZ4w{6+?Yv zsBf4fjWN_W)}V4GMWu5{QI%bx@*!PS{!ywt{1}xFZ-?KZj*{NeQ888RA=OpB8~!x- z)8QWoe+KMK?3o3BHvEI(&w)P|{yg~k@C)G2hi}36z%PVf1iu)5DQr3HA+QTzkA$s) z#l2&uHzpdeN3A!Di6;1J)l*C?hOgE>#W4396KHps0gef@JIn*e#B!XeRzt|aJWJ8N=Xps#qvY|z`p|r?0RNb%*rA4-( zw8(}Q*@oi8Hk20GhT_CFlor{B(jpsLWYheEx=Lx04K1?i`L2AWMK(R(l~r0~;|+oh zEwZ6SHnhlw7TM4u8(L&Ti)=$_k!>g~vY|z`p|r?`7TJc|aeI&5f>jrSckw8(}Q+0Y^zT4Y0uY-o`UEwZ6SHnhlw7TJc|aeRcvUH4K1>vMK-j^h8Ed)&tgN1Y^Jox zh8EdOX^{;rvYFB%n<*`_nbIPgDJ`;@(juEFEwX9eiAqBAPRc4RvZ?<@yg`d>Xps#q zvY|ybw8(}Q+0Y^zT4Y0uY-o`UEwZ6SHdpP4R+6ebp+&SV628(Rn?^utztSR`#zD$g zT4W2QMK+Cwl&`eNrZJK7l@{4FGE%S`~v?u{B zNz8b*|A)g^qDw}*Yf*XQT4MC}fpj1Of z8IAIWNUvJS*5S;Bu!~?DV3&~E50PFeyA*r;@Rz|4z+VnT)sq~;JDnlC(;31$oguu_ z86q81WuxD*CA%5+WLWx^A=0GBoqr|D zzYF#%*xj&K!(Ib>EzaBndmZfcus6Wc_X|-z>T}{lq+`nd6828myJ3HYySoRLe!GFr zxexY!l=eZK^BZ721pi_9^u0rL=A-b{C~t_=OzlylydhFE<*QNN5UH8+)hKU>)J*x$ z!afK40_;n$^!rZ-~@P`4e!}L|D~_86q`P_8?WS*i6{D zIGPVTAJzj~1X}{D)`Sd^zEKS!eN*;G*lM7lev-aXErq@fk-jPP24JbR97F6oW$8O= z=vq#{f=bqeRinZosNWE&AKfphA6-l8N4Y`$hDiO?o(^@C)Q@~pKRQb4r+hd3Y4E4R zKM?*5*qPWf3;t~Q2g9EOe=hua@blppz@HD_g71M}2)_t^G5k{a<*fa=GxWV8VMg^sg&x}mka(r%>MwRx3F~O+QzG;jyR%t)Y$T3!H z-(}<)Yqd{fPvd0mXBcCR7qy>lOg7%revVPVT-whizgYXDj5(~sps%_zGpSs0c82zu zu`l~x``pOjW3(@f0=}R2O=B{z(|(${@;}r5C}Wwqq$b=GPJ}mvy4+pCM9|$C8(1F?_w****SZTWkCjixGta#+ z7VC+G+|{x8Kr9|igk#YH-#{qp_6MV~Di-PT6nLydJ(d3IL)C7zH(%{eo#R$p%R_NV zSGv{7|KhZ;bO+suc(5zfAB?Yd$GVfq!DyGeKe*oA5pu^vJz<#$#i_{QsJk;1PXsCL z8;pl#SGZG^O%_zj&QP=~6dzgQ-b7;Hkooi1u3cLY)Q3CiehNBc{qz6bvBdg;P*+HX zd!khSg5E@bq$y0fOTr%nMxr<5t{ezatl)qZt#%6J#jZTGVKjr(tmVqksSCra1qTe_{{gOfZwBF&9f`87z}!v22#Z za@i<0nvG%muzgt`8_UMA@oWOyk4~MAjJCaqhDpt*ESS_n#3)v!8 z&l*@GYhqrunEBWe*36bNKU>BEY&l!OR z7G`~HHH)x*7G*Iuz-$(0k|o$6Tf^3}b!a0dvE$hZ>_m1F+sHPt&Fo}$3fscA zvQyb<>~yw`ox#pzKVw5|J3EV=&CX%xvK{O^_H%YVyMSHDE@Bt6OW39CGPaXl&aPlr zvR&*dwwqneu3^`*J?uJmJ-dP3$Zldcvs>6N*sbg~c00R+(eGHZyV%|ASL_~kFT0Q3 z&wkAwU=K3-MM?HBdxSm89%GNQC)kthx9lnQG<$~qjy=nM&z@t?vlrNl>?QUx`vZH0 z(XWEB*Vyaq4fZD6%l^dPVsEo|*q_<@0zxFW~dJ#XY=` z7x7|V!b^D>FXt8f5Pm3Mzz^ex^CS3?ypmV(YF@)@c^zNK7x8-Dz#DlJ_wvQu$CvPC zzLfj^u5Akl^!+Uv{_wm&{!uxrY$M^uZ zd7Mk0;DdY(U(46=^?UBA z5Ap5%EPggWho8%L@bmc3`T6_;ej&ezU(7Gzm-5T_PJTJRf?vsZ@vHc5el@>_U(5IK z>-hEj27V*IiQmj`;lJRw^4sV)DL{fq+c6+ia*Vt;lJb0^5664`1AY){v!SA-plk$bg$5_x&4v9#$V@e z&~KjYrQgDOi@#034)kaKF8>SvAO0SHpMSvr%0J|P;~(*l`6v8S{u%$Ae?i}F{uTe4 zf5X4!f9K!v@9FzU4Z-LuCk1``UYc;xH>PEXOp!(3f0ZNXdyeSafX0Y@#J(a=jHPeF z7_YvWK}-~r#QtJ3eRh5-eSX_5ritm|Kyi?mA!dqMVzxL~%n@_NJdrO7#C%~1k0=yH zqF9uOQc)(#MTIy-94Z!w!^Gj@2yvvS6jh>H)QDP9Cl-oDqFyx6s>UYa6^n&WED_CO zsql+sA|RHF6}0l>C|Z$mv}hHpM4LE9w9^~?4$&#PM2Oy&_t3lSu;>%3MMU(AD7|AD zpqa_IkRl-l#Tv0ztP|_S263!7P8=^z5GRV0#7416Y!)YrQ^XdrRh%kL6Q_%9;tX-7 z_!;$|w~MpH+2R~=uGk^Y6F(Q{iwnes;v#XexI|nkE)zS&<>Cr)rPw8|61&CK;u>+S z*dwkJ*NYp(jp8P8v$#e4Lfk5D6Ss>y#4p92;x2Kw_?5Uv+$-)A_lsYP2gHNoH{v1j zuy{l~DjpM$izmdB;O{}Jzr_r(X|ui``TH}R49SbQQr6`zUE#TVjB@s;>md?UUU ze;410@5Mh%!(=8mg=v~;rprt>Gt5jg%gi=&%v^JnIocd!?qlw2=9y#7aprh)g1MhL z(VS%NZ%#I+m{ZLIOt(4BoNgXy9%RliXPUFj+2+CK9CNNY&&)Rq%=xBeddxzz$SgKX z%u=(=EH^96L(D_X1?FMq;pP$Mk!Gb?WmcOtX02IgE;JXJ^=5@q`Ux7lO%nqjlgTx~|oelu#u z%mLFjBQ5mX)guv~2pL|7m6sQb$7AQ#2W(R*=^*)#|VhdaaZ&cXgH z3?w8CM?z^m@!*=!f72hxRJn%~qUZ?5v#0B??hoY2qY;`C~*`~`7hFBS0VH$zSu*^)27_(#Xu5RL0(VW{e z7>-0j{V_0*6^ZqPJA)CbP3eQtuw_-&WDSqvGGl9~TBv(>b%iJfR3#|rl+U2drm)IE zL_D60@Fus?f}Mkj5bqyU^(RQ24fKw3YKFQCH8@P~40TZ%g4t9(l2_$W5&MaaLAt}x zs8kspmgqdH264JLo!s7Fq}zeiJ7rF?UMR9$m57t866MIQbmG_@39WNgg6Yi4BtvPH zapIF#)@D@eBDrdvi))>WYlkn+tW92(RgZI2b<3*9dCDDKKYXs*&aF?LueL;OqSv(; z@GhSN;d3B-!M2BBZ=@pWWCFWTIvcomj;|m1H+eQ29npfj>5sTWxcU@ zG^-~R@26(n5s@wxiZvlu(784^e65RS4X6TU29sH&1wl(Nl+l@_g`%%64mlTxhA+;f zP&(Dk6?V=EJLl;3qj=8@C(jWfq9N+g5OYqCIj6^lvvkFr^2Cx?xw^t@!d)R(%pqaW zxp2_AaB%p-%)!(Z>v52Dhe*g=pWK~Z*&pnT$D-*$Cv{a)i&LB+Nw19cQ1x1!9&}Py zH8OE^IzZLKK-rzczFFNBOPHNxT-BXH%G}lIBsEUbmE4NQf(cg_!3PuRwYnTMm!it! zs&&c{LXuTWnFWdZXd)|=a?@*d=|Z}6wNAz%B-smxOO)L+?7J2^Irktj7pk)MkjYsH z<#teVdPZzyFB-l&yLZ?(7m>!8y-L685g%2pT{J;ORVTaNxev7~J?!{d^?-EFf}36M zl-xPX@kiCCZcy#cpe-f)VOM>F+UDWD?1teoWcLmGIgKLahhz-|bC%32*oM><$ zCKK@(JtakLv`2)ZJ?TDO1!B4i_?$q+kmUM$2ctc~_+Wn|IGD(djojkCS{@6zmO3S& z2Meif&e9R!Iq?x2uBA>%;!fgsu98Ty{lj!-(<4tk?^Juu@atxuL6dP%YM0-+Tq4O? zHUc0gF=E5D%sDTC#9XGTOoEIn;I#QcBzhVLMI?Fj#<5&rsNKl7-hEVx=6RyH8XYDrbetPLsG)#BXQ1|(_J zQ|Xbe?nsPEnT4l_b1jq;ZhEEj3`q}a(R3sn$FdzIgP-Fc!CwwNY^g(~8~<=w(;RSz zt~Ah;nJSv8m~uHJq=Dd^kvyd(V$qn)P2McFvMM73y+OE{L3;L6-y|H&sU47Ex-sm| zs7*M>bL&ZruuC<_93S=0NU^XZCotlIEMI@9$2oDIFkSKkyfomMRiQ*MZDEk^5S@*p zisE#QX|~WIdPoN8xkX-v0#$fvjlqF|AT{Ftj;qTd5_j7C--FqQ>5gCM%-Bj7097V-50#E zgU<2frP!H<>&*^2J*`LGWLj4!k_e{jyr@S^x2O)%taKu1s?5?>MKf06tk(VQni&jzbxgIr@V@!S8Aoa z6jo^x%TrvEJnBj1;z{M=N##tFSnkOJOR%!qU{fRL+H|oC{Mq7o~D8 zO66RX%DE`TMNtZ)D1}j!!YE2%6s0hVQW(W4jN%kVaSEe2g;AWs80Muog;AWsC{AG% zr!Y!Wr7BHbQJT7WZ>dsmfAiDNB{5ELE1WRL*6ooXb)RuaQwB{4i!62oI9F+5iCK0HW> zVRSZXc*>w7C_}l<5$aaQ={+2c%$&&wb&+$3^1*efL+UD5SFnf1Dw$3~r?@(3Vk4Bu z2t^`cQZ|`QLrCh)52{HDml}a4LM|Hc#-d#q&|=0yVPNQpEr4X|L3BqXqno-)YVII2 znjCYc(XMExbF<|Y#U7f#kV=_r2jem9E%g-YCPbdDQl*}vlETc?i_kPY_A=G9L_bYY zbY;>A0&^O@IT#f?zRXtB9@@{r%t!J74U!Y#V5BSD-JMp0=fyxg)-~9f$drTh3{fRc z!-zYb-o2`!dPX?fO(XfldU6tKTo%cuhe$lO4pSu=>S?a#OfpqJ8eWc`J;6qLB({ON zpCR?IsjIR)IxWoYq?gOYbtgI($$og>7<4>FbV{;E`1_3TL=(JR)WjZa_X@yQJ zby}s;y4t!rq;+-GI;~Nu<*5U%Rak}nR#6S`DFr^I!12@;)vEI;MLwQdr@WNnd{14m zlV4$75!H1W4#w7n@!+Re;0`D)PV=c@Yg!C806VBGN>b$HXcaj*Qd(s8#$u~g$T~ui z*jk)btj{X89K7NZr~Jhwdb?C_mpb=RTZ(l#;?@)l^VZF<5y|?Dve*I@vAg`mBz2q_*ELeO5;~) z{3?xKrSWxpEUwb{RT{slE*rd7TdE7{a9pj+P_4^Qt;dXtwHm)xb5N@}sMYwj8oyTK*J=)GHGZweuhsaq8oyTK*J}J) zjbE$rYc;;s&*D0bU#IcwG=81NuhaN-8oy5C*J=DZjbEqn>omTj*H&?z#;?=(j-Fd3 zS`SOKYL+<94chPEmsk#diRIvzSPp)P<=~fC4t|N{;Fnkqeu?GamsrmImuS5$u^jvo z%ens&kHde7$GQI!k8}Se9^iXwopwqoj#G-`lqQd(e6)@7QHt_Witd9tmMU!nI^j@YNm;j~pc zN0*~o^H8nJ;j~jvtxm4OQMjn-WB9&oEB-|4;Zic-B_MQk;8skCO z$6%k1#5yC!^RTbP)X_I#{{s7ws$|Aju-_}oOsT?|1-mcoBq=Qqn+`h%wvcQgI|TMf z*gCRBtO<50?8=17tqrytHVS^!dS|r)d)TJKA89kNM_F3JMO^(fO~%TJn6hdmpo-mp znhwW#IOb{}LoSZxw6@%ZJV&Nk#Qs!cCar2LH4dj0VZ1^AnX#AtbK@=gFN}BSze!sKRF~!% zKQo4m?Z#QO2K@u$L*pak6XP>lRoFx8121P+&o?wn|8y zLv@YnI(g1HKVC<4G93|gP9B{zj?QGX-e?m=SG6?q>3T+G!qs%nSUP7s)%N|U_D-Uj zJ(-R$LOufsbOoJ3SI~9(3iAHl6{8GOtzu$sHjS>}>>xIS0!V8tRlch2QYqBx{jr2J z-Iz_^Tp?&3sgJ(LLZwagNhogA(|22N+E+}rNukpb^-p&&jJ}J$xg08H&E?RoJsf;sor{8L}=8f1h z`HHD0O*R(bzmJw6ODwMr(URa0RVw;#O&gJ!Irf0?@^dbI_{m!~KD_9U@6G%8=-nUP zR z5BNP3tZ^>d$jTc<3)92&CL=n}T_5c%@XWOiRtH4h^yC5evT%RM?N88Z9eU&A_J`tY zXsNn%S65n7C*)dXR;h>jx$0lbgj{;OlzNH_i%Kd=Dq5`8{}8m;Ds({S{%@eFq_m1Z z-@UNV+IZQ>n`CK**m$O4Z9I){+-N*>`zK4s-E-=e_JhYa96i7Btkql3`m|)(%98h< zEp6-YE^RKhA3U~u%4v_iHs_(ftS`#`aDL*fFV4R4=G)ht_wlt2owW-KR%f5RxN+_o zAFgcJ_I&!=ljeQ3Y0t_(JXQ5+{;vmLKl8dre>Ua9NK?j+sjt8Kx1PQ62kRfaw0*(e zKixO}%FcD+vB%z!&jnSYD>pu5ZG6Bgc4bg~NJ~p+%$#k_v<^ycTWrgI`ojRRPB~CO zlb2z7(-KvmK(KO%ktunM{lnyzVHK&Z1I&5W9BcN@nL7{KGF@NT8ISzny7>ty^E-nD zwBH)9E}EgT$g#4Lpd!N>rS^|j`%S@JzqY2T?R`wD6T9-PeLSOyR#XAkGJmCqKJf9w zsw6fsW-NKQ@v(zWdgJZfgC2Z+(k++s%Xe?e&)Ga~V_DXwQS)wYnGn4F<+Sflef8tB z&boE^q$78~fA)Rl6*mu-CJs5@_jcLc7o7IQj;bj)-}UIuGgrL%%?n*-Rmo!ZY|#}H z9`o**_2?&iw>0r`@8)%n{N4ZN`)|6ozP9VUOWShJ|I=0X-M{IS-?Z<2=5c=8*k_hK zI{wO&TEAX@_^SBvr%t$ZUiB4E_@6%hurKBua;NWH6Ve!#zchwhuQbeuqA^OYLt#9G|6L-9E z=F+G%~ov|C7bR4iB@c4(?_zRn(HPu+ORgUEUs$QwNLzF*KeP4-;{Oy zY1eNZ{OGpDAHVUy==*zu_g>jG`ITRN{Y24qCtIhjJmHL2SHD(z>FE2P{b1cEYj>Xz zTX6q5H|5^l`&s1NC+=OEf8CZ!ZFyz;``lOE%HPi$KH)~NOm zj+}hLUAeCx@#t-DY`yoG4Sk*halyvCYZkhn_Q>27`A@AYF50p01^eFhdhh%_e}3!1 z)6bamn{Cs!cHg^s<%-zg{R{TY+`8(CG2<3ocJh169>|J5^!>vPuicft&(EhH_v+!Z zo}IexgUdXRfBfg^6JLGk)`isW>}SK-vQAyhMWO|&K?>$k|uAqk<1 zR-W(4FDV)se|jbf(&>iPU%$8V!J5gQ)7D=w_q_WzUC&;e-1OAVr>~5@k#X>qZI3;1 zPTsrb(%io-oHgGlzxnOQ&sluo^V2)VeR)LLG~a;dq>s0iZ@u*|fBCub{WF2{79aHc zYiBLqaN{q7m7mUe`rXI>(DvG|=ALr+?U&sChrKKQao=qZpYZuJIhTI)^Y7q+&|xwdg#OYRFFUw^f|`Dfcs`-&DXk8|CffAX{)Z$EqSlBREeKmFcUKKVt-p;L!` zllkr6^9ow-Kkc}~4xKUei%(Y`d+}%N_D8brJn8BCW+j3>v%G!pe6TUNa{ZNWP8hTA zxLG&v^%kEvccHuHuGhN{>OTD`-`xj1T>jXy?R(>2Oza-)yQ{wUnez3yd#r0-o!7qT z(wFv(W!G+gsr)RfBJVtL$ZS3muD+l=SWxaZU8aR=YSR{hcpM*mwfcz+$*QOyZwvJ?_BfO z_H}K?wr~D!MfR%7+|Fg~FIG?co74O^u~&(ym+%<)aZ?^pP0VeEtsX1n%5LAXh;8|* zmZeV+)^clh^6Adm_{sk=ew_o-nv*({TT>_f>vJjAKkO$^BkxaM%W}-1boW2Fsoof3} z1aY78!A{f4T+%@YSwI12N;Do9#54z*+&2j>* z;~#VJ<$wBSFV!(sH>{dQIIq8a=oPA^if{Y#zaCU`(o*Nt`)Hk`pkoeYJ@s5YwS2LEqGHO z4R+HcSC0}ujHeE_7O3Odc_sK@bui+tuW=`}GT-f0E6QZ7JK^?|SxX;%a4!!=!t~K= z>dCp+6ngeUFW$@^J9?SQn?5G(eB4?lk;T72{7{oSkM&nzrCy{YKB zHuvRCFU{Fn{?hqZ9r@A3`t0db{k{jQcR#W1+U0+XE^=LyHm+i7=b;DfyZx^7pLrsq zjrD-aT?4zohfT8&7)Xp_^X*_RGire%i|~?b`Wj<|kKta_rxp8hqf( z(2}m{m)v{&JvZFh_}i7WqrA@^)#Od8-DXm|6KS|h4J;4ioF5EL(oeE#)S&~+!z_AS z?JV0_vZW|F?vb5EG&E63Yo;XmmJ32QKU zISuZVH2-IVyCafUS^S^gQ7|0*p)CI3jzV$k0L9CJCe@CU{<+lbsp2~3({`C6~PZ;&|gBQHmdGANJpYu*%ykqa@ zzh6-P;WdY49CP==jhl`+y0QMVDeiAZpOg8!DHE61Ot|9IPrp6$k{iFwEqQ%G&h<6t zw%5+N==+OeO^4o6+%qs{%RgEwT3g_&Qt#<4+5R-ob8~0kv~=&88&==Gw&vcP8$Me# zW8Pa&oo*f8C@xaJ~YXU;emPg9m4)GGg9NbW9Wjlv)$t^SMsxo9XnijmuC};(5_w;`kw!j zX|sPaSvMjotEhXCoMfaJWT!UL8HFHqB+WCL9%;0q&noehme7mhmY;;+<6W1Xvv+&; zbFWk$8+r1Yzn=BR_D|b?8iMU-&$ig-~PgLo9~hsb$e~`m#lfz@-dG+^uU`Z{@Pub{=hqF NJ^r4-t1mN*{|BJyceVfk diff --git a/selfdrive/assets/fonts/opensans_regular.ttf b/selfdrive/assets/fonts/opensans_regular.ttf deleted file mode 100644 index 2e31d02424ed50b9e05c19b5d82500699a6edbb0..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 217276 zcmbTf2|!d;8#jK=y?0h-UqJ+B7zac|gaHvZMg(MWK}2Ir5qGrQx75sqaKQyv+|A6$ z$ZRw(*M{&Pm)Wi`}_P_AQO+pNZaDUmTSu-5^zTtZaY2AqXyT?u$ zH}RnnM~sA6x)Gu{G;YN7Da1-#=r0`i4dd>gGj>MjEk%U1xlU;Ep~^8MMsvqTO+o)? zPdZiNg7$6Ibezw?d7H|KGamRZz1!!6aCly~^}aFFCY2_t9wM}KAE8G&-9LHMhy=^O zejy}k7seYral`{tWW6{wp5Kh;9g{{(9FxB?`zOMyza~U3pE7y+46fHt_Y>Z5m5{i^ zDbvPG>GfP4<{$Ypo>377I~wuXJ+rU39j@>82T>_;fsoVbDJxk0LE_sV+}zsqfoivM zBu-U?V^{Hm=aj3O_TtjMn_I7OKvTTeIXT(Q$(z>-9_iSxm`eQYy6}P2-p`)l zbMX9mtn&hi!M!~K=s})I>_Q6qP!f(mK}vWf;8;noq0VRP55XSCCr}t{=Ap!}Hdy~W z%q?BMmyG5sx6UhSU+8ZQ=dxJQowfs)}vhHLmgEu`-+_>I{ zCnOus7t6boB9sm&tpIzE1a}7eyNbNAS!B47@W5~pEWkrI2^S5`&FonA21yR#f#ITM z!Mv*3Im1QEBH`jP`n&=7F}VLtk$+CgC0qax3>TpS9DE8~Jc;^Ql&iuiGW8Z77%o~C zMrZ7t;i6>$E*P#EPT0EH`2SU7?QDDogTJjAjRNOv{j8SY!{*80^na-tJu{m6#~QTG z)&rU+s4ZMW^H*5s8o;`pwDtxPjrwf~2Xc}gto`8UQb7Y61&`qVT0DE2(W>A^0lxrd zj|FRAunt_W!u@0t#o3!186Mf#ch|D%gxW2VB$Ck)<2&Kk=J)0Eo8RX*H-9Z( z)cm!q8t16FBhBASyarh(B%rK^Y+y8lxiLA%#%4H`@OJ_7D=6n6)AHFpNj5^>3Cl?# zlXGl+@{xcmWSqR5Oq6GnVm#lCT^BAxCY>ci7)~L}_6irl2e>AaW8D!%E$ksv*?s{BH3Ccz64yDZjhdx zO?0d;`AOimo)pR>$Qf1yJR{p3fL92PAy`RrjKKsGmx%zl<;YCnRTS`)A2>9~E(Ooo+OOkU zP^a+6@f?#kM*&Od0~v>VpOfv17~)qX;h9>JAWy)x;~3{>k}0pp@l?P?Y;0Vg zF6ozmF1pJ2Tz-%k6n3;l8)*)V=GnLz;6pqU;)lCyi9T3cLP}uONQEzKZlps=gjAs8 zSlS)lM>+*$2EEHo|1+*2$!pzYLwD7U%HsWFlZS5+z3- zNwx|{NtS#wSp^)E9n?PTXP_5cW z<|{E4#+Wb5Cesxnbop%57aA8!LH8U}JHE&BF07-97=)`NL3SN$ zO@>}t6j-xzIo5U+=S&{PU@bu%4S8sg_>9Ruw!TpPJM6!~Bwqdz_!E36TTU9Vj_r*9 zp*LB5TG)^N4w3G%JmLw}Og=F=!+0HYVYa1TR*!zyqaP-Nui^Yp%qbH!>x=Po*T5Xv zvmqJ?)gk@Da4X^UBiP4t$XM9fQXLvA1Q($J@cAAx3v|F};8q>dy+K^w!YSkylO0UX zNxJW@IyA?SY>-3VNirvhA3UcNN}!K+61ilveoLyDoQHj0rAS2GmGqNOAjNP>`oU%> zR(t}QKSvD82+({#%nx{w@Ub88NrJosUo!n71OG^}@tS2I; z;XmDHID>AV7p!+M`f6$8+;u+UuJhYAQHa0)M}4c&bGNU~d{lI|fXC=smiNhA%n#B}a=k_6eF0NO4WYT>i|jsFH&6D1!)hBCWD zvemwYF1xF6pnnt@%ClV8<~IVz%}?R@HSi28N1kjP0M$tMNmA##SCqwzGAj-aFH0=kYqO8xX_+RR0A8QgL14em7e zIrke+d7fACdfvq^=WF%wcszJ7OJij*bqGql=@PBgZktF~_mMvB&X* zW1myzG&^lhhcnh0=j`AtkL6cU*oxRO?ze6VVsmp-b2HZCz&Z-a zF7h^cm$s!II+BjYI(E@#u#OvCxU`Pfv5t?i4svT94@>J)ahM%;heKLNsv|SFju}|T zV_3&icdg^z;5v*g)-f9EAXrCZb93`$zHjs8=2y5g&94xGI;r`UW%?mDVR2S-W%H=!kC zu%=2;C0;@KSX6yo_I3E>xnIvGsDbzjfBtoSN`HaeI%T`}Td};bp|0RF%+l%jB zJo~TluxtBs10^bBQw{ta3mx35Pux2Ce>q@rCib&0Q2ou{P>a90b;qSycbxt6NlD-q zzm5FBZzn(UJIGJ`PVx)?2>FfQMGI&lZ3B;`l5VFv=uY|w-No0kU_J`cPxlWWbd;?lTuZWveY?S1bMU)iA2fh7Zq`}gbHr>L+Xzjt14POt2q z-mD(oyLIi7**T+AdP>LS4oU6X#>ctaxMH0#;TEGouhWL9RZ4|iCh#03?Hztvk?ZH( z4rAU3SFUSBeo}i!Zg^!*Qu|z2UWMN=!r@0H#JTcu2bWwU{EiBTKMvK17MCmhUbGy0 zS4(f8rT11#YH)NT-PjN=hyQGj%W;$r8Bm7fRXHx7!~dgn+*djl;-nKTPMl6WAztv2Z3?{C9p=>^~b!cHdx!-}I`G7=~Lg#*e0=MFM5@*wdhC;I$c1-tWd=#F&| zyR$HK=hovDF5tFkU|9{qAqAsdxq$eJ5&nfEL0uCVVq6Bl?$1c4tHxw>WF}*dXzReF z3r3H3_+@c^IeV(*1E5LvNDck~CAvQY)sK-FAkJuVWV+A|>nGQhTM_&>t1=uTIsoYW z!~h|bmifIofS7kgkVtY5bWFw*BPxKf@eHp6%KXW$DSnG9J3vLaz^0WueqfpONZ@L& z-_pyEXngP~e{wFK1?lJ3FiK-nV12m;ls!*8&0ii!b3{JtA!)>ygUfzfFHl)rZcW+f zvHqBf$kE`tv5vAxr{C)XhJCKGF+N6ifKbAh7!E&J7HFlktZ1OCXuyy%VAbi9?ywuI zJHefMS2wP*$UrwBK)=$hbd+(CyblcxxZudcfh)Tk{`wVeC5iz6m##9x&FP^m0(NC}ZNGDia`blcf;kF|=win zZYx2bz1Xz?EW;VmJIY*RTs~K&!|yFFV<2MSk)Rv|h6M8fR*Fi?TAsB47QjTDxGh00 z2uy!o;w>05;QD(@=OI{wX70RQ5W4NCQM!r-)-X)Cf*m5*<1X+MM#A3CMl2hg&luVT z+3PTXr6q>0IpFm&X0Gf4YOHY;jIMDFEbAtQG&`w1L|gU&7hN{s zfR`>CIHc@(nCy;arDX>>%Jr(q_8n-0du7i%2=Pi+Id+v@WKA6Gg!NQ{6Q$HX@_8>I z3#Ge)bU`{Fb(9k6TA&fGQ8MZ%7r17S+8v0K2J*s5A9Yj+-0_Bb5O7TyxVBKb=3_qx z2!p6sE%Pe9DzApqa*+oxYs?H+j={=QQSz*YYH8#FJcT*p@=?0*fXW*gXt5A2yuQGU z2cZfMJ!nYTvl@cOq`w#_oBe=X!YjcU&^Nh`(Tq?Y^i|eW_!zSh8&HFPFjrkYfF@TD zOhm5nt6gKV{b8p1C z2cc49_$JA_Mdi$Q406!uK{5IKpqOZ?hcWw1G~c%<~+rm(;hQ-FJBk776GFd>LAwLnpKVg&4JQ^iHSu= z70pl)s^WY7beZ2hkp1-z7~+>N^OHeC?kzh&>1to~s#PRAs>q)@u*~m>@)h|<Jg zz(%rt)2AmUmQSBCGm-twNSr=HItcxdPQ%Lyd{YatlYZFovXhyzBeJu&)Z$0TCl<06 zHY)c1TK*L+>pJpBLR5aAs5vw|!lpOej`maK-Cvy3dF zdhGtOpP1n905Y32(|PnNH-W3-_H&=`R=y`coS(th0R_JZt%Q4p=Y^ZHJlSKiQ}Q(V zTKOCDn~F$9j$*Xp1!Yg=Lgird>?em_9MXVkX5bjM?vqaI|xD zb@XwRJ0?30IK!Q7ot>Te&NAnC=iFFXtTEOZn-beIwj_2`?2Opz*iEs`F1;(pmF&uL z^>f31Av~JVBO}93E+YD=SsLiQ1AGW#D<}bIxZFa}FJG#B@0qzm*Y3?fb2KOHK zVfX9qcjCIl6~)~fcYoZ2ajW8X#x=wpiF+gNqqy(luE(q5BjVe|ca85Ie@}d6{G9mH zZDZSd+UB$!)OKv!*=?7#UEg+R+h^Lo-uAt=U$p%xfh1@W>u^tpaUJG# zsOhl1!_ys}?{KQahaJA{a6MU>+$uRSxodKt|5m1u4Fi z(J7NtHm96S`6#71H72z*bzbVB)GHpDr=MrIXPoB&PmO20=V{MNo_9T$JwJGUOEaal zN{dZvmzJ8gB5i%zwzQLJr_;`-%hPq~sp(zPr>4(IUzGk``p=!Zbz0MDcc(+0UhDLJ zr>{Hxk)g=AFXP?L^3LNrpUO04_Q|Zzd@u9UF73Odbs65}tuF6%HFO=?b#K=nyScj! z>vpWWq5JUe&v!r5{a@X$c5m#V?Ge*sa*u^Q-s%Fb_`Fu-$LH>aJnfdec ztMeQ34;GjUA`AKyR23X5_^B|haDL&@B4yE-q9==v^>Oz}?^D%hMW6M39`EyXUwPlM zz7>6^^j+BZK;IAhHucl>i|&`)&)cu0-{^ib`z`6Wt)IW&(SD!y`>VgTe^mc2{m1v; z+W%1hUyFwn&n>PQ&}KmU0civ788C0a(gC{$Tqp@ISyFO+;G}`?m$on6Rr-5r)S^jGIh4Rb8 zy~8&R|FR;bqDw`uiar%{E4EZLRJ>4ersA^^{YGpV@#Dy@Be#tdM`ev#IO@aE?MK&+ z{(a2&F<*{dIj-Zl&f~n}c8vS8GP!bG<($eDV&amC`zEcK965Q>{GMPKfpbZ_CU7>CO`1>1Ha7aIA`jd z{d2C)?KpS(+?VEs&FeL9?!50FEPC+d{G|Em^YiB4Gk@Rw#)onqTKdr23#B8uRlNY|Y@YKQ&7hYL-eUWOBaZ$vgc8j_!TCwQUMOPO!E!Hn~F7_O;Sxw&AOVM zH4QaKYF??iQ1f-opDUCrTCHfmqQ{Ej6(d*7Sh0M?jup?WIJx4&if>l@wNkY*a%IxW z?3II8j$Aou<${%KRzAA&z{*!wez5Y}mH$~4wkm2>@~WPz2Ctg1YTl}qt2VFNv&z5f z_^Pw3zF771YHqbOCs|!~TT|H@a)#^>F_pUy=`t<5gR{wkT&00-u>)N)pX|>+k zKDEPYC)F;ft*zZv>#sdo`(Ewk+TUuM*MzOHuW_wOTa&wH@S3q}rmd-8b7^hV+6il4 zS$kt$>biOB&aV4oefavW>vPsut$%v`wGI6?tl#j(hASIY8;u($ZJfLD&pNJ7S2wk8 zQQg|Q-E{}+-l+Sy?)$nMn>3rEHg(vPwW)B^y_?2unzL!qruCb)ZF+js;Y}}YdS}z8 z(5f8EZxPhc<2+Fi>vIAx;{;woNOEejhbDWHJt-Z{PNOpeGK+Vj^D=X1xBAMaIMib36dOSw-NnN~$ zPxGYOtQNT|Hjd_v_nf=*K$k3UW?BwiFSu?TT9%jX?VZJDSk2dS{@@H_yjsF51YS_8 z=bp2vtY362^@}*B6NP5A9iPA@CR8TKjx_zu8CYR`AxB8~6MaR(n%LqUq>O28 z6)Y;FMx!$6bzy?qY_`~LV)h0A1ei(KvGTiN+=b-2T+6f{~*KVNIAjUfi3 zp`S0pYV5D2{f$&>)EZ@WGq0ABWKWjIlnLK<*f1O5KV#$gUno_!? zlqws)p~>0edA>^Aw@56Z`&n5;OBc{XVjor(i2G5+O6HWF3;-TDi8bkC(U6wbS+SMYT(8ZE4-tXK!Z#a4a$#R-7!Y*OZyc zR%?{j8vJXbSR-4%1cU&REOLd_l^z=xpKh~xjB#=4X`M3CJyx4t5f^Wa<`ikDI#G+w zZj{Rf&D+l{n(|(+fuH!!K7QtjMMs}X+qiYd_QD3=!cUq$A2NB=SbB2V0sD6sT`}9; z$@FN?eaou$nvNWj)Hnu}sbw`6d)x&FJ61Dj4m?G~O9^sBqm=z#6{ANkZWy=EX1=hz- zz$+G;C)H?h#mZ$8VPj<=axBG@+9^FP?(XZRtuHJs zEiNuCEu?3*Y*@Wz-j{1YiOXQv}A9?*WX{ec=^h;#?PL5@`iBaNL8^q5KP8j+=fj10^L9--@VL@6ZFUUA1Db5Du4`Z*OfC$J2 z_C$$zoO9v{Eotr5D6mnD?E-yRJbNswg?KR=Oc@?IR%)`l;<%D+>vpeMyJ5wy^;@|V zs-o}gKPjgE{$N+2)r5K#)aaM!^lBa%2zT^K4V=Q&$&{YP#d~ZfPP1*@ zt`!^BuG!7H75^i4*?XLx`T2MH&dF!Q6!bcnTOjD*wdqJlZzQrCsY0t(g{kxgK~1%s zMx#|jekpZ?WWAPpi#8eZ*vj2@nHh33-t5kh@!Z-(y1JEEb$y?Im;YCBX%t__slLmvok%tCiKe9 z?bS06nux*^CfsKdU74Tbu-nb^oGFA#02kcMeb#ibo>7v-h8!7-+`A-+3+;fK1!);_ zB991HS&Mus1+Opi@eu(&lO_>TVg}9?%NY$OPpXMZe~r==A?c?-ul{-M_iKMOUaH$u zzj0&zo;vPx>>br$e{ULnh)xq964!|*#m}+t*A>5R@gimokDNP$S*uAKuL0@0N*bmS zR0;)E$!R#I4;D8;4M{o_BFyPBre(!{Ew(x5K#85A_UkB@cC#K&!^fsUQ&v7(Ts}62nGjQheZvCh3y>M`a`18Bs8;BH8 zf;=iA5;KS=y}WHAiCLi_ye(EMZ=1l|ZFXCc&u&+{-O)upw?b_!@~Lk_nHeIO6=5q5 za0f8Q6p{_o5u8D#c4y}ACO ziiU}$Lw;EN!BwGr<-usB?a;dOmt5_4Ca2H@s;=F%Hzv?4wTCLQnq~oh)qr0VXrdMA;*HVs5f-Jz z&I_$034n!=kktwtTIF(0kq_w5xUa_B7EOxmC3Pwm-v)DPD+nn~AAUH;Gem&HHn536^qTRWuA zSG=B^iXG>t%(W5XXX5MouD$)Wc#{r#^VuiY))y|$8+Wjh(Iar02zbg#jMqSANL7bm zl0zCIZ4EukP0_igG9l8R($D;SM4MVy}I zmaHy5WSBrd(^v+LfKKP~-~9KI^#|+3&;Q*>Q)?dhVfGW7Hr8){W#basW&Y|}kJQdy zD?4*+&;17r2E8!v$R}ry-(1=6@RUbhyjlOil9h8uZ0haZ#*ceo^w5X1yVVRGGn?Ud z0#?UlhMl-cPj76bF;a-`#le0nt*sea-rNx0IEv z=kprtEw!z{q@IEIeE06xRJld`jCMS_XU*e<3-iVw9Lr`dX%1vHF-r==78%4?}hjBs@B(kip&wbU*A3rm+W6~jrouo`12Asb>rNm{K;rLvgA z4E=p!21zl7)Ri>KE%nHJslX7o6{U4H2Ike~dQyl$79;Z-+j*@DWJq#& z@k5Xm``|bg`}CAT6AuG(GGTkmJ!2}FqRi%ZHxB5Wcq_)x zCc3|`jm@Ag@EL-pt;8sjR~oXCpb3~O5;AK;N(#zQ4w2Z>Uv=h>T-Lj4UjMogU0;0X zrT63eJT#`~!CU@orDL?W!C+D@@sTZ^+@2i!CAtpDxi2%Ff>cJQNphpA!x^Wu}2#B<`&!PTX-mX4(Yt-E+wd{*2e(o8C| z90KO>BV!qd3Rtw6-e^u2rlc}PS-hYSkR-ts_`+m59n38vz})f#43^tu#XM-pRp$32 zM~Fh8$nj{!k)|Vu_Ho&@T$VVd!RfLk?4#$!WZCf>Iot$#YViDu>0(!mg7>t96Oi1< z7KImF;Egj2QEGiegib9ebg&1M`fz=Cp-->Z5nV)~PiG?bLLZ*{FOl0qK1r&_>40{G zT_G4Pf(uT2KuyzIQEBXLaAo7OgczI@%Xg^XL~Lz;H-DX@9ce1}y;vtMk{uD3h)>XH8hdjJj83c> z{{6BUcsppuRXxR^a1!3J#~YCvdmT!X^QqL@NCC#`An~(>$)c zX*X9bJF-bksB5~?Vk8ww^|peqKzSwQ)nRuH#7zI73}M6=GA6OQ;0SbjL#TUn-t_&Z zAm(JMq@1SX#|eiB+kd~6{rYp_AL9GeNy9g<6`$wCrc8GnT|q~GP4788xUN)u z1xaKdi|@GTD}lAkVk9Vgyb&r$ait*0h)k_|;gAV(q0lGi)i^5* zAQ90d=0qT-6ap~gEqD?c#(3xvh0)FpZW8zHOsUlARXhQOkk|lmGOfh=;sbU>r*ur(BG;66>fLwLxQ3U-1(9nl4@`w4S9aoj zkotu0rCCGYF__4>Fg1et7(GI8&;o^D_Sd*kb^foJ8IC^3Ut!KeZR3>cI0NE0N9|LPGanynJc$9jL{fJa-(}3!;8i~= zP6Cfq(lK zKCKq9IV&*7hp||SrvlC74O@608Op=I;)H4RV&QMP>>WKc%Zqi#x@0-yhoh z)Qg{U6-~QjN8ULnelfObGFP##ws!48&@A&rI7r|&40_RK81vy~nc$AoMDsQqq_9ok zp;20p5&_ae;)ewb1eYV^^1{i8mpmy+o5GA@4yD~@6FBj^pT)+NL*B1!*w?*w-P_NI z=RbWe{qR#uH+QaHe&uOeee&a8d*a$Jn%-wbNm{|1k3RWk@rFJ##`PI7Af*HW8w#o- z!VthufvAm%ATfmJl?WLLkO>0M6kJQO$RrJmvRR$niUu)7$QM&&F`FcPa|}Eafqsm{ z?KK*xT7htl$*AN7EjkLaOCVwv0-fFc@a8MezbQM?*zbn; z6?HW7`y2C~d+pRw{wU^)9{~~#QH@sKFsS7)_!9z;7m>2qW{4zp06P!x=ArO1GX%|Z zO~34I`uz|s?h@OkOCVy_*zd8eyB|ewu!I$T&|3tHSw*NLTUm8FnJU}})u58d#KU%2 zFk>doBsmL2K>DC}GwVG#h}k1MwO9PannrCM#jo~?^A3I6(H5Cb<%g)bqtl#z zVdNoA12e$b_$SnzgncvR5WOOHJx=eVlMahrxvHl5TqAd^=|!$rQy%MSPzBF)Y!GtHvHvSP++!ViHavtI^CWn+*I*jo10;YGL!1>YL-y zZ$0AJlhLmNv((99cL6Xe1l8pfk!+|H2@65;3EEcNWQ3khix;U=JTAYn>V}i8mIZk} zM?X9nZebbl0@F||~h{tJTXk@(Xfas}GMHKPigS$tzV`RjcogNH% z5kqGjkzHK%A7;Jbo$q+TB|8c69PU+N|4@ndx$x>!a`J7;Gy}RoT?#!oihjOXTqz#p z;`yzOW4Z5}?64*p#Z&y&=6uZDc$j(16i<7A3kfk87EMR;JH=B~gyN05Pk0mFGE))r z5h8@CaYsDvG!HAC~@#xA9r1!3HV@CAp`I+0Y2GYXO!GdbULHl z=x~~>dQ6LIuz3#fs0_S0&&S`M1k*lufJY)aw+nH+z#f6!6CV%wxFlRk(RGH+t*YtY zeDu@LA6}fTRS5M<#hndXwl%EVwsrjzG>+==+kSWdzVyU@uFih`9oP47Tt4^ShrwBz z02?zR!(F{G;c9yr&qM0Aj4iXMvRa+k<7MEI^9cJp z)8e=Vzlq;c*}vZTxk)Q~e(!;&%XVykc!!SbzS4r1e6TA)JBz=3G5+M6g&X3W{5ShH z?|6b?EecM8P9B3j7({n08jYF5{=ba3+SFhLH58;mmgh4o^gQDRDOw)bePGbTl)&i_ zq0BdNrDq^g&75DRuAwn^ir?42_8J{=&&UU3>e~vC4LO zrCw=k*N*G$Yo~9U)!WzBVC&G^XNwHdScq#8y+-IQGc!?gC~sLCj1wdgV-1CF;~A@Z zq`eciS;4|pf&KH46>@v88OxKlqtnxHB&3{a-Tq%MrzB1&9P-M+m&AXG-+lD`!Wr!{ zy}5(#`}p<2xuUUd<@wW-Hor0Tp&^TB{PyR}hlKp`;jXE@AAMQbc~DYfUG0&VcC8z| zu9dksz1xs>uD$mkdew51_=e8E&zE~Y-);J=tAF7eGsF)almj}q5%`ZfjS}M8rn1?? zbt;od$n%*Di2AC4BW$9F)+#A-h9hWDV}O8xrvS&ZFqYNG@0`2%=|}48mFkqkGfto8 zPAz%(_=ioeg1Zw2b?$%fOYb(NGs}242xTnZpXXs4ySzpgU#8Sx)GG3QT24=>+jSQ5X+matr_P--GSGMPTG1l)twB7$z1L7e4ov$(i2c0tQJXfw7O#ua|;L4&~miI;azik^((kNqG*X&Y8iBo(0J1z z9#;$t4IY4L6kuu~onY_l)atM>rCg9H1)~YptHGdD@`^AkuMb!Z$)I?)X$`XhM-o`6 zWD!BZ1-wy0dz4&C_fd4VnAEg_lix3nm0KF$$iNpZ7(VG> zjLj1)6JiQR3Xvemls=``Y@Y zk;>$!CQ#a6nR0CQvFEwdRaFO{Z`#i47d~h@Ddg7`4>>k?^h@tCiV0FH=4&A--f&`J z^*0%%9{W%lcYseCG@uDaVoXL! zh@Y8>7Is>z2(=Az%)lG&5dJN_SnS(y=`4mvZu2-8d!+d5we?>=NHy24P<`Wzdmnr3 z$tNFwte$g=zl#@YDEBnfQKI;cc=Nq~eRkpeCrrxwAtudTX9fZ&2x#k)-u)F(2gDmX18*SQ&Oq10e)Y00>NLGf~gv6s!vf{QXQxYwDNU zmEML)pZ@sEwY_!R)`r!OK5FS-QZZQUE>Ei)QY?Nb{>GFxfBD!M_qT6cdF$+FOdnyU z84|1lR)rzT#I8LRz;)%PfBnv@UWw@2on`-_%r%U_yP*t30)&gs3^V2&}(SGm3TK7dV%O;{|*Ofm67 zxLs{Fn0xzlUV~l%L@9!ZYIXLG;2t)ffFIZju(Ft<&hS`SEY)J;Ozlg;BgeNBU)ixE zuY&dvUn!rdRV>gNX@72IaqhpxMNRWYO<)|o2XX(PBJcnnz`G%0+lnDj&0q4DW zbp3$AC(h&Z9~hbWavVkugO{PEY7MsT@b&^5$`kT`5oLpW>gi-M!$;gDRvf%qtW$=~ zeEXnSflg(WmC_nxy+#E-kwcLKq=IW1 zW)-klHYGNrfIA%YgqdIEqDRH57papvUJ$G3+T-F`@vY-r3TGFG(mhSzH=U!$#T@j{ zf#2om-^!vMSSD|?3kVd!EZ0UVq1CfeZ&?k@;cl@u&`dzlW@K;&f9`KqY6o69C?@2+ zu&hsEM$S_O-2vd*4~KjH;vT%|cz&C)TJ!RDwj%h<{6viS-#&A1pG;4cy?spEwR8w1 zrFY9`<|j6OgBbKV?%Sq=+_0(q;6;lXkD*_d`-QNbggRrg)PVIpmc0R8eyJTEBQ8$50VRzQ#;-OWP2^x7)8 zNq;qB&iR-#%M^+N%~`E7waJ8S_^2qIE<(mf$5`XBA1gf@n6qR=Nj$@*8=uZpF`GTC zYDCf%!P#eU>Wi0;UYNCb?n7r!Or9}mDwh@i5sg17U$K9S_|AxXxm7+yJ-0lCl?)wA z6Q(_YBrD{aam7LcUkWa0<2Ca7@CcKp*vFgn_;^yWPfn5(i6Q*80VZZ_=3^ zhtM084%_2|T8fLKCFu(~jb4*8)t5aoxzoZ_>n1rJ zj&No@ZWdR-cQ1#fBjqw9kr^JD-T?a0NV&`g9$NgQHhj5%gg~c%bR76DRX8d$CN)aetq?slXT_MqSYxW)f4yae&mT& ztAFk!fAbv&HQu0&J@)P4o%WTU3!l7yrYmNJ)HWeUb{bgE_r`^rRa$K;n~@8%nPt&2 zn(&D5em+%11X8>VeSGF{B13}Eoe3v*q$UNZ__k()_-4DHsL~N>KuQ$|nrk@G(0yy| zy!o_V9MZFpkGy&F?CY<8DLY+S-S@$j;wK9}AHA&o)>X;BUtB=D9fWM<$UG_+?7}Ws z*zt%#XX5NGiL1EHEqTY?!w&rRt~K$D5xG< zGj&$gINa=w<7M|fIAzx(Q>X35M~R^E06(_>f^SrMJD7BeurPxLIbAAVW6@a^_HeaM zr_jrh&qd5uy*b9r>CJkxhFawsmKnt4B{Id~{7L!W%vY7fCtFGo+f0r!IN}$U0-{aq z7jeLRI&Z&NLFMABw7dA~9`QBW4TXqf4ssW{j~c}V4GYBIsRk9kMa8v{1}vs*;NX$N z?8C+h68-~Xfz2c!8Za`8)=F-eBq5lLXuK|J8~CZx`J; zA|e{ujV^hQEGyr&Q|lzTQ{{~B?Q>dHhTc9E#78qDyuY353l;!K6&l$ug3|{VTJ9*HY6;bh3@sVA<-AXfZHr+R5Rl8Gdw=nHLXL3wA7T8)L_k`4Wp5to)g&L zC!OF+#mC!ueR52UMWwgPGCCsz$)wlBXgGp*4>^rVV~R|4nLUxnYzb)Kz`F-6NJ+wH zNJKCLONt#xyB1X1L>5fQ#uQw!Z2(-8;7M)6@{y&q5q|#sr3Y zF84QXdXtvF#mXz<-)Ik!nh9%&v7f zTdUQk2pbXzc#hYaVzAWrhrI^&k$C@>8U@)hW|tx(u=HI>NtEDkbR*S8igj|9@S!V* zPu}|Y%nhR}6Q@-#UM?0-IX!a9INn)0V$|5NQZzy|r37^2Kvl!Mo_ITfk1nV{Sz49GWS3`j z))>%QXV#gNX1yuK#6j+xIg{CB{znR92)He?*t!G4LvsFHF1!e#FuQnZs}rw6{10N| zF5F){V(_pD^x&Yr*Y=)Ux`E2-x81z>Kgo@|G0)=L4dhDP zopp`PX(zX;Y0p((iL*E>ZDekC)#iuS`_}KLN4dhvD}zV$>6DWjms&P?@s#3CHIHLV zCzmOW=|c21R*(Ev-W08tw{e?>nJ1dLK4uzbjx=*-v$B;lMyo_rK@vlF0cu!?GBA^t z!W_Jq=KAjpYi@c;j{oT1%`?`|yYTJI+2ckP_sX8qIX7!%`LZ3tx5eY^$-5WUcAl5B zd+mMwbGqjwx`rfmnhi_0<(`WQJ6^&<$mH95F6=cF2t9?1F7G(m@mBl&-pRtRJ^Veb zJx`=zbu1o|10TRf(!H%@YPHfp@FJMff^7k--V&+hSY&|(EhQD!V!tay>jr6~6zUSb z7YvPHJcJGwpL(QzSu6GAZ|cg_>iT**U%c_+`;y!E#L&`R;>&V2`c$z|sDPEOC-K;0 zl);gdh4BU>a&36M44H6&*U18znL*xS%;YjkV$RUX;}j~UeK5U8>Bnb2{fu(f?+y4_(d=VS3A}#(tOMx2#Ss%!6O?T`C8iq>PLIbt`*4Nyl8o&jW0#S`dpl|k$J2NHgGp^z3v@iOB!AQZq0@!IRQ<=w6)u7VlTO2`!516CDR{P z71JND4Qt7hSiQI{&>efBEchly_o5Xu7#}6Gke%w%D@}B38J^I+;BfIC~ zXWpz?7_k@{VsB7GfHT8X*ka@roLVLSJN*D4A(w<^U}s;d_`TxZnKVYcG?SKzPzs@A zP9u)*O^4I+TycEl?L)|iA`r@Xz$>1!b5+1i9PBbe6&{lDfGq9$tWh=xToRBVYWafW})cztA5$kngu-C*uuUN51 zoXwZQV~QeeSx&do678a`^{rhNA)y_K!j4u{6yEN0^!LRXj9~>nqwBT}h*55aqL+K^8|6)BmQ$EK(h45&jP?Xc2J*T14I1A~`e)?h1d~hdb1QOduI(p+3ZO zZKO_a&qN+*Llm@_WRgYLkr08YMZl>ZyLJ7%?crt^u`jQo2ARw%v#88+Bmo(aE}}-J zhe2&nQ+x{FM0K~500JH+z6iqd>tO7&>@enYAheBrbcB$Y!yy&6aVB5XWNH#G`?+KM z>89gcRMTZH=VmEAF-uCT4JJ?0_qfB1isnP2B0m*#jsvI_WG=_y>mkj798L-DNXnMr z{+t96stv(R%JOW{Vivxz%P>Q&|ImUKHQx-hXmw``2GzhQ6NpKIDo35SpxO=Q=3r@@ z_JNs*&)zi?mZyl9=Fv-_#jNHLcg}=S3HRvj7PLtG?XH=yQ6?+cOagsOXja@g6L3*7 zXfYpn)Id_*<4rYMkzT09e@B5pSa<|j0{Of~y&_BTjN+W)q5`@>p%7FmL!nQ_3)VZb zZP_*~xT>W?9z-Zhf&&iWemfnIfGk@Gxb-+>`BD<@ysca5K{|jwc)00}Z}C=B^$Bid zAPtvWUdL?`my3HiZ&PEPs1D#zmZe}+ox&i8^{l^Z)l#0G1eeqRY{?v{1s4&*(A_O& zQFWk206~m`SgzmgKEPdv0xjb1?1Rli8U=T^{%s!&`hj^&ARnLw{eoZeRc91MI+0~OmM<;d@Rqod z8n!m}DPd`k;*G8RGX+R|1ZJd+G6^%CgV@cJ;ErwZpzOT6#VmY@RN~>te`o>h&JVP3 z+}VQRE-=ajd@-Bhj-&Ab+%fKhTQg6Z3HS`sWEQ^IDve{3nt-<;O@uiTZ&}%%i5Bmy z%8f7tY<4ZuG*w_9txBsxyj;rDltM9V3qH8*7O*w&Rv@#sAQ&CO?NrSvyWh&OuRMGFzO3!}9}S$epdz<-k$2ew@oN3QzIf-7@axj)dA*#DcA1{x zJI3sKDtBvq@{ywZ@=E5FW=%-X9Fkr<=;F;j!oh;TNA{3N*(c*()y6h!L5u$iv}hY>0lq{FIon4|AZes48R7M`BW;Ww5x^2UW`>8ybPOZ1Zrvl3;*;`x z5h+4SZ(rv&@kT+=#m3vxl{#gf&!WSIUNFgoMIi899_j3k%`6a%v^yi&*BN&tUfJ2} zq%1eagqJ}A`(21+-F6gNN*0T0BVDHax_ETP>@|<26}~ZY@#6{UPfdFHyQW@B+U4FI zrGqz)5iiakaB9h8&+oslZ0+8i$M*0q&RG%0DHhV?N1s&&lC=`j?-^cJA^!2jed0`4 zJd$d@UofFz({SIDTSqCB6S>s-o!j>^zQ$fF%Zmcs@&Y=WqGs2zqlSDoT+a_+{IG

3*AkxKE3K4^TwH9rq=S2Kt|XybUI!I|lHDFX-Y+C3KWDgWqrjYfT)0 z8Nw!zh5C3BdN#F1i&@Q%KnrcKMf0<0G3a&+=xU@Du|7@BlGZ=zGKY26z6!x1)}(QJ^b;@hfX@_b>u%^0E6!v<6Fb_?a( z+}e_5(cWZ8@BeC z6xG}}yH=bgez(3s-2B9Irx|YjkdHYMw*jJ5PD>DK08FAoaAml~dVzcFlQC|8U&39h zf4V;l{~-Wy8~YFUX_3@F7k|fnX?&@FTJp=^JTKuSF#ZGtsu^tr#7R1Mxso&@O0pM6 zEFa$E4Y#S)2JFL9wx?n?mI7PRW&u@cip;Yb;lQ%a|mFG4cN z)*1hYvF`wks>=R;_m$~=CNt@iNk}7vkc1FI4ZXz>AR?g&2uMdnKtM!9j0i}t0s=yW z7?DM!$+{v~kVQmv712dj(Y0e)7fI&j`Q8AU@80!F&Y6 z`3PofE%^BZIEy@r1$Gm!kSug6_9yA$JPrpUDx0Oa1ZSMZYm|(Mh^O>QKAgWM;iip) zO*shwrv&_%hnuFS_;^ALg`cH{!dQ~vjb%f+R!{oi`j7wk=RAvSK)4g@y>}DBSXjd|b@@<{f0)wEoY&|sY=$Xtf-(UwmxDcKVpRYEXN#LTyTe2ea1+!5c zxg)|>glV;F{b~lc}6a4OFxBZ8o7VTog`@98xVWfppA&bjHqCG5CX)Rof zv{3pvZy`0jD}vfpaVjUY7NBbmkaqApV5Hg=kSIg7&(Z6s3Pe-_DP2C#B{1lDB!K~4 zf=gf#ISw2|TE=$~w+T4NYz!S7CMn$GEiFJ2tkGIX4UhSj7Fa*dgIHwDS_`=t8y^EA zLgM~t49XQeL1WM(-@gn?^}j|@BAnFPNNzleoelF~CAcKeLWI*n(o}}6>B89J!c?8h zCL|_C#du>JIyoaVHYyqzRJ|&q>`uQk#|apJr_<=hp@!c&nMV@GHQYR!4#5F^!YX2P zC`yoYeogOh5>=d5z&(xmQTb7jfB!VP*sK<_SE{yd{lgIBL4B4iI(l?bZE8c5F{p;? z_?*(Yehx|}{T!q2WTWTYG0F4b1KtDU80RTB3+YK+>ujRb3Uei!dKe7n}=KAamu`f zzIZ~%`n^SCmde8O)>zRg?c+O!2aZ(0le#j#ookrT_u zz|R}CKr83xD<}1fw4t`AELg1#_%@0dP7PM*meGstIJb~`hCfHA%+Kc!wE`{o6E2 z_h2aAdjEDD>MC|p?HrD}-i}z-_k&-`mlqyCzVLK81zx`!91i&$Dwy~dw+L}77aNE~ zJWf;LvsAwdPu$PtJT6<~iN`oa05&hA_kotghdEEs+PF;(YHfsh0%-wa9_I;K8@H*? zX>I7kZ6xA}$2nKf+9*|j)7l7gh5EnaiME`!wKht_T7VpGqg?Gu*~uUlv?1u&fC)sG z1!`Beh*NZl_Ns$k1wVidkxqivUw@&j@w`d*2MrE}XDJ*#jasBy96H$;xTQ4|JuUa9 z_SA*41C*)ttrxPzz5G<{f@U@aaqVdW^{y9g!wrG{DaTnH$4^7HM(b+Gni@XK6tyn) zCvG4XhMw4|tyu#fRNGTtGv?5e+7^q1rM%ArcpWk4c)gTnEEds$@SsKRsU`-u zvKuqhx%l;3)eNkK#-GXhid&H+i~75o(u43cR=C!Do4USifvg!{nNOg84|~}`x(0_?g)R9>BP2J z6TGhv-``pbw3gH#_?{>S??#XGxxKi@`AF$?)-~7`t4TR6glJ$DIu-{IHzW%dq^HSt zn^7+#(@|#t4!l7C?ggADaJ_NwBezjCtSuK`^PLE7f`JO)Zj>87u^Uo|GrOtl#3ih* z{k`L)#9+_;b1$kLkS$(chq0t%EM|(Y2%)%%R)a-Az>)!02jqt`l=f4|+ZpML65S|N zmiNXGRR!}B?~)B(+WSJ)w4R5mq){X9SrP0kmiL}9M@ph~#%jP$OgosX?GF>R9c;?0 z`CY}ePhs|4x@j7;Pwbz9d`7JWPMZh@qxA%BcIWpiK1cgH_z(KS?OLVv7d{P|w%gDj zE5Wsd{vxs{T(2_4Kc))~K7%0PNTqbs>!i*?Db?;~iG3&EWC)e4%u9_Bwd*YD?FDDs{X$~%Q?*|1wQ#jXOnSug&3$u_oNIu0rp26l@0qLq_g@p$ zIk0A?Cy7NDFTa1`llMRTaQF7@yRo<6J0YF4K;t`M?~^|);esDa>3sKZCmIxHf6Vzn z#Ht0p1MemA9kf9FWdZS*QMgTz7Rgs4BbNyH|Y<$VLjEY z0_TZPJ;x;AG}|UL=8z=OGTa8w{orGUiH*kmHE$teSHGnNctyX~xL^LCw7~jp%#kd-naHxQvbQuW2-;wv1BvvQ8VmfMO|2D zU>u-jNGG(;F|^KpB+4U$1h3wqz4|b{>cXxLx{aOpR39Gdh!dif4Q{=o~YvHyS-a>R(_SVKg zx~bMesjy6IAz}g3#z4GZYoQdIigOgzw1p2MEtCmc(E{1ov_TN>*DRAuB5jnx{z6Y^ z!=NW_@n5n*!qreKnu^=d3R%XrkqnxkwG#3&Q7f>e0eM3k3%3Hm#7X_bmNriAt$mWe z{tJH{rfq!*r|@>f16V(TdZyWBgwK-?ha`pb09;q}1fjRn6PghbZR1~Kk0`jnr&=2k z3&Sl|Rn`wm6k3SbG_)2-S?)l6Am{AI(A*RGFlg?$Gi6P(>&Ty(Ep*j-iJV0|Ax-5Y z9f2pntsqCC7k7A{v=&Hn;w?ZT?*2zDaE*&vfXpmh(dK$f8zf(9ZIsl1r?nBGw_8TR zN*--QEhIld7QPJ6ES#~$HbfCxbpSK#Spj?t9_xpg7!rDUifcp0IC5Rt-J`~4-O*=s zg}jw5PF<2Xe;$S?oC5#!DQATwp?h(&*u+GO!4+>XiAo?j!DKP@tbmg45FEH^0YKO& zTbLW>;Ff55yc@}hJY${w6F$9`=D`yIJTO4_DDK(u&fEU^&s~Razuy}*zQdR@7OQ@} zUG=z^xyGYtdA|r z8zf8m1BqbVcY$^v{C>xTcn;`n&b9YC=GTrcTg@V)DNE0TAp8W@c+pG4Ao=NlW z8oMCwU`&p!mGLi|a>x75ChhGy{bJYr{H`5}3W}8tOWM|^v(@T!`GeMvjk|YNT^n|w z-Rf4A(Q3K8r2YElj+Q&K)&CTA=ulMHu_L0Wx&0fnH^RoA1K)2i;qKzXY**Jd9a?2Z zMVXs5)3p-XB)Igw`yjHrb5W0cr`Zyf*{i|=#EqmRIBt?0_EflUyrw8w$kF0KLmSA^ zXOU8PI?u^N6+>2`h}e&OsKNjRp)v%C^5C{G8i($W;5ZsbBLWaVvOMgAmXo|pj@tbY z6T^TVF^A?X8TCxB!t!^|oXN$B&ykcigxKrgq`W)w)=B$!NG=f1nf%$zf_ZO4vn@eR(UMVxUC^%$K=VKyR5i9_7|I;T9%AYG{yC zAT{WStK!v0QVL!@h7U6fuvqrPUu#27rcp0A>}L5P8>MT+hVnIV&WH+;LKT%l2tp~y zml^M?@=jeaXULMr5So4cv4=97FL~HkxcJf5ziSbp^$5{@NHRBVF`poa@}u-<4qz|L zGV|Vv4-cEubydqM-}r^PK;M}Uw~y(*?vBg{X&G5I#<)Zo18E&G=*X|fFFcQcpB>!g zEL$8B+^dXPif2>t>}utjHXn<`=VPF19pT_};u~q{`H3RMQ0D7&;^5_5jT3a4eQqB& z$~3|BjC^V7;@q~e#oZo!0(}d+6p^DEn1NLTn-cKcu{aT+{Kj#?yTZ5#%8W2D0diud zV?5cqB|OR&IWaCIrtm0RV-!uINkIIc5ww&II=z4H*l`a`(T;WNF3Q0%b7qZcOngj8 zg#`{SMo4eSt`(4WVML6yNXcIzu9Mr!hYSy%`bVf3nESzz%?rD9I6t`e{oQ+fKhiqY zb)siwLD#9Y<_3)Wy7CDuz|D&7#;E8RC!iN`4_Kmj;P~HpCX~j}_%cUQf@2zUDg@$<<#ud4jtz%#gF!#<}SrGBYcS-4{NAE zl*?gL+(y|GWtAUtH;^MwX^k+&)W~mNHk;-@p89ON(QI7qxLEpal>Aex<2|A}pKcY? z{V(n4C(Wu3eK>S8!QI@4Wx;Iv(ODv%vvei_UY!N}6TuJpC*VKVY^EsrK?);e+ zs7s)=^Y2^Q`5g8Ek@u8`#AS>vs68RZH|}W(Z>0k>HSNh7eg-}1@~IUzyL01KSlB06 z{}r^FwIo$D2rua8cJ*zX0?Uh%$U;F7B$44CVd!EVuu}M&bYP&`;_p9-x zhn84g%%B`cmb?Huvg~U!;#P7Uw~{l=N{}yNaX8wYL9m!nkO*1uBo;wqM;YQWp%TpLv<-q z?+uc?v3BmJP3SqaPv|)hJ#(s2sD6o_GL0AtUI>a2pxhLm8p42W*c&b-6Y&HTOLfp$ zEq7D=Hz}PXw0aZxjPiNAeKDiqc*}x(8;HnY=b~AM996|?(;H;K)L|Nc@r~HgC_X*R zZHP+q3jhX==^!9C5QU@>HA^}hME?8VRliieLYyvUt=udIuLQSjqTazQxRpUiRtEfy ze}uV*Swh3Xs=|(;+<@F319>=0C@aoP_r!`;YgUXcQLjh6ffm^oM{ILP^S%|y&7zz2 ztq`Lf_@bOE9371plI+gq_l9wDUm!nHa0KR2v?j7EQ&9GZQY>*nwaL$SQ`S)Hv@A&z zee=c3H9eoLU9w&c9>}c8KA@^=D(jx@RugmP%G<}<)f64R@XxoRm9vK)yYW<&8hrTb z)km1TbNh{Dbv-VhI`-~+M_#)`vx781h=rJ4d%o7V?v$Uf)(I3NW70d3xx=EOQM3bQ zVgQC>Go6T#@)B4pu>wMrXrha7qkl*VN=YVU0z}3Dfr{i>44?keVPewa>g)sctM;FN zFRnV_;`sxs)Zp{k?B#j?-OWBz11HW%W9zoQ{t|xo@A>b1qOCHF>lg3@KQhXaBx`~@ z+UI;u7*)*GtJj>d!QR*J` zjq_^N{hO9N%1ZxP$3(0rXykuK@P{diNBM_!<{u!_l1-sOXC{mD8#-vK>_JRl$I25( zsuf#@rP`s0ld0tI!&*r1zsYsgobdbH*3aL6M0+3G3ynHrec8+J32I-vC(6~+*nd0` zv5S-4V+OxT*6d+)tvsM=s*E|ytd zKD=$$U++`<+-sT>J7DnO0hkA^)?R4#Zp8SO6lX-kHp3c1a0uU)*O}4$$=**_Bx!@D6akZ zH}wrRSH1E5)E)h+f}d~SHe%=CXP9pBDT~*ZS(O z%WL-3EzM2cux;D!C)O^VPsq?F%)|x{vI{w<4!g`084$xpBeMaV1YR8;QL1qr3@)WL zDkX8emrf$^UUZ`9IaHjbcCNWT(rr*Ov%aoTC$}n4J)>CKy>f@((Qocfd}5I}wf5oz z>c?0$if$c+NO!QS^gHQ@Hqlb?C_FY5JgKU1&&OB_9a#oK>7 zxOUfmX>aLMcRjo*yK`ly7X7>Snm%mikGsE7Z`^qIFHBKqK6IpS!KEFmo+V{b;HL=m zn~M4=S+XO=mtbaYpF@|H?nxC>k;iFA=~~e&rKVbAV-b28>#%~Fo4`i#6dF#;kvj(~ z8-$h*+n8lgq_=UrlY!75FX&%3;hQ>Zqoi4$<4B5L?akM@r(e1VY3OokV zw=*RX*rzyd5Ine9y73vK1*Z^Joj?`Xw8Q`?D&dp>B+%&s2gK_isGmOGenHLp#}-yC zn7;DtiT3xL`6)yFQK?+9=n$ZuuT+hh-6z#Qb=dmdJ14j87~AaftM|Th>e@%RP8$4- z9(es5p`>XLX%?diiUMM9JCnmWB1?vjOCvl#LL-Vqmo&mi1A+e~;!7lywAwznm5E>W z)n$Pbxo|W0DNgq~96Df%LcffS^8zK!?){q=JLyH-ixG&KMj*)F673e=$w)Q_r_IL2 zweno*lVnjRsk7Nywt{VB zkExSuufiFXufC)HUCBh@f-jK+;>S919*nbU7l7il9exp&>o3FA1r)!u!Q8TZQp-06tAz@2`R?)3Vfur@uROC}@U zInKbMBnbT}(O86NZ=&B1x1qK2^o5xg0ylVff2aRp+lB2Y}PTZr^u$p8b^#Kp7JGDpq_(=*;92g~&14{)Bk9 z#gZWq7^gljKfV>j`d$^SS~=1(Q`2C$OA{O^AXLrPs_7QDz>E_YC3!4S4B?MJ=MSGH zI`ee$bzt&=C_Kg?ck-pd2M@fTcV}h!6P0bcZ7t|JbLE?FY=7v|vZ{w>b{CK5Km6&! zXP&PXe>(U?*_e*aTnW>Lc3FQ{ueGfUJH{lxd0_dw>6YS4v$p41RxB=Cb?3|}*l+Hg zhR01uniXalgZ=&mbVWH#2`01N4UAZ`Rq^^n5O+cqjwhiN zI)G#a^vNh-+r>idNl4U5NI1nM>M+Ie2F@O7&JJv16R<`MuKW+5iPchGp{@dFWJbdqgYSC2rNLg~y)QVrL-0!aSJVq5#)%_EGH~ZqSKB3-9RkqiSoQ*fhVG1(Nzb) zJ+dB#P-5WUER@!&W#@9n#HCDc^`XY*9%$xN_+ z9(d){_q7jy`q-*}EJwW(Pyokwri2$P7i_&N6~SXMOqrGOffZFTJc@zIjlsU1dmanaAh?=I?Y8;9eWd$h^u7{5Oa`e27iX@YQm%2>5BobPe$?)G;NRcK~38$hY=6j zpq4$O-7(4uu1|)npkyJsG2bd(xpkpuahlg= z17>WTN3=Tu9p?q?fY)nBjGGH3ja-sli;N4|_L^M5jpEUiaC97KC54-l$k2nDSwIg) zJlgqDZ3>5to3MDfy0}_BARSS=vE}DJIqmUoa6fR*;)iAgLCrp;f=HS8=LfSz%s!N|Hb^Vw6bE0@Lm}z3>-*%nZ`7cyu+QsIw((exT+Nb2- z{BeW&JxZ;h#MUE7yuOpI9fKSCSX*jEwle5Fsp zPQ@Y^3cGg^tLBOAf+b5{Kk~}Q<5~6F zA1i*fcktKRxiKqaJKcSgz0CdPNTqMyUS(4H3~dZ z;zT+sduB%nE&M_TmyF2$a1}C5LvC`>a+c4P0c`@{M!aHGlYy73*VS6}NN@pexWzSd z#iC&8lGDddUgm>ssA#1Pa_IuP0bQ_Z(P?l~g)#w^n01Qcvf6R$y6p~>C*pCug4H4E ztRYKrPSc1wJ|?1dvMV&Af6>BLox4=MV7a=0$o^MVmKL0NG58Dn^}!IyYqTz3BhM-! z_29hD7Ita0?g___#DUgt=tts-ztR(88zB^Rp+$#a24~d8+~R8{9Ta6U;0~m^w5TZ! z@DQpWqPRE;W4N?`2oA4#5>=%727B%O9+NoOnp&D?n3#d|+5+Aa?Hux#DeUO$@~8Xie*NL)=MG#x&#FIqM*(O_dc}UV{NeRa+)twel{I)xw7)e!2XPOK)`r!g z^6G&80`6fm8KtxxCYy!9j%Ly;iYLnCfFT~X@np9}$2kbLnJACnh-51d$A5;#ObZ6u zg9?ga<0K*ASn0c~&ai97mdh4#^)a|HUU0p=l-5vPEc%!ve!=o@el9QmDOmA!Xv7Vk z80;U;x$Xo;=tN~ZFJ=(NRz zT!A6t{}3oJLY4xE+mkPgMZ3jzF9%-{2c8Zd-yMAE4e`48da#3dTKf*##B0Gg`o>85 zg4POPRnMT6iq|SM`%)~r%;wnJXw*=Qjy9#G`TJI+$tG|d)9<)zBfX3Z#*qrm4N#B~ zTN?zlPz;3}b7bd{zXI<3tNN!$UAg=9vsbTtbm839T}!7OoK-%qw(@GdJZjaUXhY1Q z)#tAD-`+BB!-_{AU%B>?$q(iAy|>?OuVLh8af%0G4eju?MB7Bst}_}@#le9v8H*MC z#qQFW zkNimT&ExwhUwb<^9Gq`C>LA%BV?UHCP2_s4ifL0C66|`XZ?)AU4v4a1yx58b56!OPyXmV$`%H zU4w6&UgwfCBqr25h zLwxrrMrRiCiepevP>=wa6ym#rfwMr3@rK0fMyv#JphRn6AR6bb*;#v#81I(gR}s#O z`B!5--U#io*KBYiDISjgC`(CsX{1J znzGP9v!RPbyNxj={oLQms>LDruSUB>_(j6+DHI!~Guplwwo#k{v(0Kn0*wrGx@04| z;uY0HKEx0QZlsiGN0sD&(7NHb6ep@G_NozkSJ&)n=2~*_PpW8#y9zkT zGQ4TB4jAP;1HgzX3J^k2qYY;!EPY@x|M0GYYzwbd6G$1wrv`shd!bzW&0l~D=c@Zp z-HZF4Kl`aB9BmA)I;X}iTmBf_N4#pS&V;d;aB6*sXHJq(70Qm93m&>VV{mwphkzhv zFW9^p^=j!Jq8ppG7e5=353M+thp1ewoYGKK5BJiU>K|wzG^}6$`(pJAZ(f!+RwFO~ zLplHU$E#N?UphZXoKnNt0dvE6TtvZ?%VdLp)a}tDQv!HZxWF-t@S^;V$f%|s-v}V= z1Ss1+B_JPHf2>tws&N6CSxntAmc^#L^tSpFt3G>$MsQJ0V!q0SptX*;X_n%q;kE3e zqhO)(+9f$I-Uk7~=d&ml48h`7Ajm6CD?c}8W-OWG!~z8ukp*<>z4=Lkn;eS*yI8ZU zcg?q#SkW$Zom&0b)3FHGq9C9BF0sK-B1A5*6kt&d7(0p{3rjRA96 zID`BP$|5133Z!nTFXFc95caGyO8z8AJoz~-@Y`Ep5|vOW0YeTK9;C?grYx6l6YfGD z`yg@2!3nJ+kkljuLjR@uEG*L()o0Bp`c%!v`T*?Z2jd!CyW{&Wzy9uDvK0w{2jyzHj*4B&A6QCB$J9GkT1?x7oA~ScCNvKy4jlQ&yKvz=6@oN z32qk`=AYkw`r^&L;u!JdgHNcRfQ$0zO`s6y2>$@1n}eM%haKDp3lR7~tSiZkm32wY zQY>aW%s*z7GJ$OcrP92B)g-ehKa4z5v$442cDM?g75Zd7qBFUZf~Wv?I3>x6I`eqZ z;hOW_7cB83zq)7r>eYHnr_+<)`j>k1>n~N{siPq1Hzg}(B~^*5k&3f6uVdPpcFBQX z-zy)b-u$;(55V6sAFw5CX6Ffo>Tl|IIK5=gFM-vM$Vi+efgrR zAF2uLD%-TUa;tg~ehj~V{sK5EW41gf6-=J)Ho702zPSp4Lx)=fQ&v{N1} zEfGp8k0BCKomQ`t8BCd4$*u6M0s7>MfYe=eRf+4Q<8?jp8Bxeom&g?}{%85DO6esmL3y|$^RezmTiqAnpgJJEEQeGM+sOKS5^ zwP-cT2V_5?9DNu!5+eEaG%fBop(gZKUC!|xUyd1=*J^~@%5QO&OS z=9MK+K6Vn4LJX#qy!I~2O;)3TqIT19u>Dg@^Ia7bb{UE z{pl>wWZ%W+>BKf2x$VlvZC9c3Snw#9m`ymrNK@9MD5+>tOnSj!m-V!XT6$)K^nn!$ zYdrZ*Dd(`7E())zmMS_8KcLDc_6fgzgZ3TuKS@{7zJp|DCP;P^ijrJTyF|_yy`>il z+-Nxje;_kMWDZ$NK)TY^z3P#;QJZJCN%F?ed@My=Bpp|`sv}>u%-69m*bmxVlpIi| z2hmb7l1`_%5Y3=Cyit18Krl;AyUr2CE7~-gPgs7V+Z{0Td~LDB6p#iv2g0oQl|PGR zUR>*Gr(Rp8UMujdJInl8J4VbFFV-HHmbTj*>?^; zNHJM040vcctTU2(QOetF*P-H(wz4@R!aRYv6ODv%X-iXj*bWGXKRn5 zK7os8!QblrqP^~owdPT1C^!S@(O?wewg;>YEi%7yB3=c8wj^;FX&Ta|y+OEQYN4ct~17t$5B7X_5xJ&#^LF_A2ba0gD!aT0ApM-aV(w}S9 ztySs{X%ewI>G%`qiRaiL!$&6!N6W~q850qYlI}9b+hsY*qCgT*ND{CL zab62jL+lnuJj%U*`{}$&V|%(L_ebQmhUhYnK*`w1RBSC!3b+^99bO+qcEynji@Sn! zdUf{=^;71r-(JfSYcCym<=7EvzPk41=f%|DP#RZl#y)nlmcRVQ(mYgz$EUt`{gsbg zQn~Z|n`~iv-G28+m=Q&QqV5l7G>os+0dVtAuvT1OK^+Mbv_=z7ywxDvVJd?ES&Cv> zxfJdWhzy*QK}1`DD)C8G-P|g%XVsI$sp0zWB^|5l1$x_x9<$Mdi*#O{$z)_sqtoM- zPT4$RZVsio4#s zea%|7Rikd*bUq*GD+Wa{GFdiq{Y!)!1_~IQtLQJJeKl|le!jvg1b#|a*%y0ncBx|5 zs#Z$JYL99Y;Y({F5 z*=|6IB?4|}Dq%$IRajRtO9COA>n-FHBgsO{W<{TVaOGn)Rox}ZV#x#BP$j*Hxy8j> zo~+u7!%$Z@VvxF#&HzraG8ZE;aj6Fy3)L-@-4?UiZIFD?mM8&rJTV^FR}6^m2#@7Y zG?s?ZplmPr8OA~m12&jtT{!dpd9|oYPN}M@{RDv-hIwnn#ZPY8vyV6d*msS(@!0Tk ztPSxMlESEhJ9HL1G$kmFdKBctioo7%uAm0{sKalOd zd=ZilD}H48qIK{Xp50ZWbvk^+u-idtMc_IMaJR<_-JuT{jWC0`L})9t4R*8NjBCB2 zz^{OV1R1gMt^mBLvEITh6x>8Xx(a#z(h+6DT@Y;WGqXD^AGZImCWsfAj(t1t-k4Lk zy9{_gCiRM^Xsxf=@nb7$cC=X@o1$KZi|uEX*9Jsfdp^cT8q0vfUsF|ptj})}4>>uKzkHRoUs(Cp zi|pT3>No1I%)`v;#h=*u_?`1M)PR{BW~DE)d%-KYWXX}5j0d)-R9)~_PHAV!;P)25ALI89Z3-}>q1fx`t-<{(IwpT*H?G7YJ0Ccz& z(}AbqVa5L(?k9vf(Fo=)SE6WyKKX!+Rs4p1UN+#@WGo>~_B$ zluzMZI&eW07{(p=|D*gc;(#7x4_tvrrD1XI4cH0XwF9>o<*uB%yV@aU2H!VUKeK$} zeIAHF4rrRqlVVonKfQ0o%P*ojGsX`49M2xpQI0$Q-h~;Uk}U2!s6NOm`4-I7&-e6a zyaQk8t=OP=CR8C7pScZpq)0NNt}Ey<3bEJ7`!;%nxH!ER-VKjUPV@_?^$foO3M2wf z)^2f9j-ej1e3;+-2_xqBCq>aAM1(wV4U#1BWSpub>A)`+&#L{@ajKf};9zhhCv3)O?t@!(ChQ%J_Fs~dJZm^9~zy4_p{iXkr>+-ay}?RFTvaKczP#EBhT zirMW3CyDg@D23SL|MaqP_bnf=cJ2{^lF#`yGHr!RXVp@5lxnJ}VK=L;GtWbtfdSNh zGX}{e!k$z|KDb|F+SnNnxHirXR{1NwQ^dtBoa*33$7!1llLc(&p0F2N%XfyRK(ZKV z3b+^XzJ_B-H@{jb_r#pJBqKAESwUGuvQ(Orb)wyfg14A)!`0u|bjE#NVGCl4n4>PL z68l!EE335oxAwS7ATr!~Z_s@fl3yhS;*rsyCkto@cKY=OIho`aY7sd&<97uo!`6nR z{dPPLhsH`LOj(MSP$@(aNJd3IhAbn*Ev$tL(T>+6@(|tH#K9n!kT%Y~ucFe{C~Vw? zXgscIzPZp1MT)rJA(HX$gEgfg-yG<#Gx^#@V$N@EVKzIUwU83_I5uqoK1swZ^EM)g zc3K;hZ{AKjS&Y!+D0V(4l5fsi;iqq?_Ka{ItnO+QPE+YHWpKOEKM`t zfg)T#S{sWm%%KJ{WQ&S3Agv%1Q$)H8)pX*ksfE}Ml!miQn>OKPJgNVmPwM%TSmn@@ z$en`k4OJWJ)Lf~w{v!I&3-QIUSi@Ki`?yXF)sKRzhOa!@x&r1`;GMW1T%j%ho;YpQh8JCs>~m~!hU6=pCh zdVEqN81(3a4J8E;tl(fU_juvoO8Mq_Wi;6!;1WL7X?KF;n^j=R;ZIA9b-gM`XvdN?d3aw`go zVuqE%fc#$>>0L0Swj>pgL@D~oha3u}!k<{0RMebQ3KS_{N|lzXJ91Cws)tw!ey~x} zm;TzDvd&+f$aboCCWiXng1)1KS;g%v`Y4ACElu$_QDetuHtO7r=@h+;P+)^W1W(cl zMvvL-v>}q#WwcrK_)<{docu!?B3MzQT7`UgjmC&k(qEBpZM0G0@rDPD7XbP=T74?_ z^<1@z4b94;|KksOEsK5W-q=4qGA}mwd=`sPqV@e z&(yXZpuIMLeY5LHdVIq(vIvI(P)GJwfAQt_SJ;{Bmv188p-y~u-!soWyJyd{UwrYy zC+y6(pEUga{Xg+Ht?3e}ifLJk$aU5J77yTz>tHV?Zh`uFqMuhsiY+$Dq69C3K@Y3E zR&kQY3S$|5S0_(wR2vVipvIDz5N<_6M7bdTzLij6B{AWTt0;viK*G#G0kHdG$7Obs zMybvPds>OtQLFQapop@BB1#~8L_%;n#)gP1>*lVMD&Zic&of~vQU^|<&Xh|?D|QMl z(wAIDk6X6;;iN~AsdI=Eh+N3Lk)|mT`KZ+(mXwy=JM6wuHdDXV47mtwcX_Xg^H6hT z^N?{j)pGPQ22u`1Z#jj2#ToFd!8l=dh>Biuxq;fDFRc&^HfKo%iWAsSzsy=vVbUp7 zT@;dqP{dQ2U`Z$IMFS@xE<&Mo!1krGFcf5m1kt0cwfgs}0|z8$aJ|?)c!Dik1YO6p zNY2_A{Awdc0?&)w8}*@5g?oyNtwyIaIWg93j}q;%@kyxNneK>Bh%c?MCRmaJNvIqf zum}8s&Vl{`nKYP$fKTvwN-BK6uOmx?jOZ|$CKDQKh?!ux;d<#&7%BgPzXQL7D$5cI z5~B0P1825(*tB-ugKReymsW@K3bS=@zlndSFej{c#+vwKd0dL^HgP4 z61E_klqza@g#a?3Mimz($Hyn6`5YdUbQfJlpE*I7)gmsrUxmY6S|P=m9X6Z8949F# zL*Kk#MWQYt8nS-{+fgfS_l z$%D-urcGV6ZCj@?pM26o~VI!tjFIjE>e5l zHc;C5+1EkTBe@v-e)X=^9Py!Z$Xl8w%qZ@h;6r{_Eb2w*W1Bf;Q>;&yo?%9GPHBZ9 z8na3$tq>FKiT=c#L@1!qiP4Gf8#mzXZG}} zLI&s5MMcHgiw?ckbwd{hoc~45Ta+z=%evXF;3SaJ0(%)(nou(>Cskv5nrNn6XMypf$y}kNvu;JT8g=l%frG)fst%uccEXUrfU-|N9y1gk zR^leLo1QvyY}@vu$G3j}{Wq8YvUBeXDR=w7|0Xal6*3ciozhm^N%6Rk5Q&`<8*4Wv zcqOmVBB!RM*sU=p#o`t%qDAL-gXvN&Qf(3qSfTt5;;>>E|FkJ6I)Pwlk zmeqzIpQKL%l-B3BJ^6lpb?qArg6BDMtUv==seLtsoXGEp3pB{f| z=i|rJclxT=Cd`+!UL8C|?Y9&xf=6tg!darK41~3CXK}6(5)QLkg?MkW!;zKY74%qt zzdJR?oZ*&Y4DJ|rOokyNvu{O)3n5cX&)vx(hcX=_c#h~lx-^?c($TI25Ng#JPqQ)H zNaNd5DhNc$Z@d&NF*r89Dpnh8o5Z@EYnSb!Z#5ZLV*mcbh7TMp0tr<8bV?l#Pi?#Z zJTCRBJM#3=mv%h;;!E4^ojq&j%zN$$CRJ8qUsADL(M&e7BoS zzlA9hn=$`_=)WiqIb+bxdFk}oLko3=i{dr$?n#q^o5h?(>Ok>A@Pe2V%wfBi1~1Z$ zR|fkl@~shpG#fXaD2%WFL|z8#gbyC**2S@Y3^3YaiIP!h*XqgfclL{Zzcbzd0VyYs zNGWGTQR4yf^bIYKJxw7uH+^T_#j|}KN z=F-}{r-wW@FJ&!Lwmn=TQock%Me5u?P>B8QQK3gZLxFiEp78vrKra@VBO^v z5!3X3n6w0sUdn84PVQAj}foq1&+%ilSo-%z%`Mc^r4s`_p1>#LZwVf2(oZay^oVay^O2N-xCklZXn zMzPzdm}Et^A)1*f2!uxwLC~)zT7YCV*Gq0Iijji=fg>J(myw;XVi#(Ui-C?AYMppN zRl846N^c$*FC(qHP8EN9i)6wxszV8&AI-Cez$p~AgQuP1eUb2Zt7ngKyGXz( }c zmWQYgz4gY=`l=g4(Nc-(kUv376mJ%*N8KI4AewYI#E96`U@+0%OklsH*T*2!xOF~q!5fOTFq_hkz1ho~2 zLd_Ve5QC>v>wl6@=r$qH4w^okE=GxrHB>1YCg&WSCrzwWz`6Mrs|=Pa2-KE@Ic%+xEmPcC0MY!YapSjS2|{X&MQ)h`5yh!9y6qX12n)6kmcluI zV=f6!!nKNYjqUSGiYN+1q|p!(hpF5YKf`cjDA~_EG-7j?4x5K8-n)14i}M~hwq#e` zg055Bdof z<8BN`^y%1t-ts~tx~GNXskF!!)zap0WRX%R{mJXBtj)rrDeJo3Gvu~m*#!@^8MnFH z^dWtQy2P$g%gD!5xf9*)8sX0y>`L;M{x0AmU+?6L}z!L9?6xenp0 zVp)X?a4tFdr@23q#O~J{D+gT2f$fRH-`qZuut{u_(h-FI4J%)$W{d911yh+%tzN`F z2!6GA0Xw;rIhHbi(HBeA>r2&Zh2Y6r_3BHo>mkhqoErp->ea>F&&1hgCvjEFR$5BRzs^@k60&6Qq<6cu^BKfR7Mz6^A&mjQ5Q z6@VoNUxm#iKcpuTz6EiGY+sMoxVL~R z0}%G4)od`>;P`9|3rVx0jc|uTkO^tUk#%SL9^Fd&ASXAb(sTPAa$T)MJ%QFx|N5Lb z3nz?_zy5dqYj?V7uX#w$Q2AQnGXq@tCwk)3Gk~}|y?$}z)5eDYZum#lvuDKT>-U<+ z6b@C(i;ow$@=tcfrx(eWM4;OJ*{31&r4aUEzPK=?8*UjvP67@W_z^;V?M8eH&}P zeY-5|t=jW!_3l0U)WUB+VXyrgJ$X_SST)4s^JmJDvokU@kj}dm1KXS8Bl;CmAq2u4AM@+h_owOEV9!Riit>c)K|>wdz$nU6WH#T=s$NtcZ% z>13}p&7CF1>-Cc2fPCIEM{y)2nKR=u#mvkYQy>MrisyCYj3DJH)P*La)AfY;=|giQ z7yyp{A%#gY9k;6+x)Z{0C>Vf^ePH9d1A87{^HiVP`xb30C?7nue8hnG-aTu&_v=1j zd8zWo>7#!cBPoEB*`^TG-%h?YdigJ1d+KevhfZa;L zOtwP8rCMj8-B@Q5tZa%?N@iX^>#Q?d*-)Z zv-q(+ZwHC8<%7iK2Yr$LmxEa1LZQ9TS?C7T)j^0O znk?KWJb-E=H;OB}6nE?Z=tRhy<)uS<&z^kGsCjoUd9+9O%#74#K)dnz9@V+p$1S{j zRNLsnoXM?Q^iJ_7#Y@goOU&cTOhWUnLkB!M{J!CtU3zvJJ8RaI9vvTEFu333*^|@q zQgfrMLRZ$M)9{W{thss8WXtd=lP6CZF0t$u3Gp$}ZkOFs)V82?Ac=xmNqh?ZYxoWN zGwe6KI5rUQ3DP#Kv^h@a0qhma8d~Oj$7${F@F5Ac6@Fg(8SVj;3yWJyR4UQ{5O?XM zdO@ffM7B84GpA{yYYLRWHw*nvKl4Ms7trhY4jF)(8Y9R@+z<|&62ck-0vXWAK%Xg* zkN^VkDrY&bC~vb?Q-2etzoOVqO%3*8PJo=);77N~N2cOm?W@dD*J}E7@fGHn!<;ww zPRBo;iZ`CBT)42Za^ZuIsWU6_k6o>qdQZz19a~Nvd47J^md%>ywC|gnI+TrU9iJ65 zc)>*ZW!7r?$&=I7cTWBWC*P}6r@pFQpdNJU^yxSEBELpt_M7dePGwc-yDxQ9m%|)$ znLRjxIr^;Lx^?xMC%3G9?X}aRyA8_iikq{0!GH=jCK)o(XIrvT`>Hoh;|+t^8ui{g z?;`2BTs^6;#@#3hglp8YIEI;hsqny~U|Lp-j6{zuInicIOqN94sm-S6q!Uj43f?>?Q1`=AyO z$p_*cW?kQ3CK?;HAI)auS@&dxM2q^?S!UW6S6(HthBWrkkaZ#M!XKtO^((lg_ zv&B@i-lZ#S>#_B!5CSa&y(+R=+FSZtqUMXIrKhEmk&)Z8B7-Rj4HzQ7x9Z`QFz?qW z87z?y8z^C;kjFpKousXg9_%C^ucxOq(~M$*J3lHl4dDuSLzV~2>Zi!doa3-JONwb@ z4-C3<$OyaRD>g^IqMq4tc<(z*XueW?BmT(z5u=$~Ds9kfQnXd^st0^`a;vfY+NqVt@(|HOC84!Dp}FI6}Js<*D52{pV5Bs1LOQPYRYl(987?P zQ(D<8b!~UneS3TGGciZ1q&;xKS}+GvormL&r6Zj#5J*h7nyiVE4!C1(pz|1_%m8ns zAf#q-0&D;du+1(!7IeR)5Xl= zZ&a$EJ)wMXbJm;3KIv}guAcAQb;_&}Q+7=rF>C5{&zIM)Gd%!a>T0ildHAsO_9Lo# z_x`;r7o0dTZ_U2v)E~&Aat5-%4E-!f@2zkZliz+Ts^5Y7BGn8Li=aD8^huT_{sc_u z^h5-wSqQ$*bA35_E9zwoV<^Lbwnqlvm(DfRk`#vtZ_w-N71(^neI7+gU?)!hj8x{)|0B`vIapNAG7KRa5_m93G zc*C=1yLj?oK_~Y)C7&z!DN2BbpJLm~;AL@|u$<1iA^s-=?-k z{y#wnMR{ad?TC#Bb_&)6 zI*0BebdGePkBF6x=pH4?)UZyXJM{+Cl>9mn z!*;UKtQ+g`LSDPL!?uLQ6Gqj}0>qKgHD zdW5mJ*E zG~p{Myrg`Ag%Fk|?qjDC)2^rgMO&a|J@CYCppxu+)qj8eD6G$~8#>)H&3pK0OmGF3 z?`!4{O8e`29yxvT1ftq8BH(-|8|0rrLEVd!S-jP5N79|%gao2Qe-w%sdL@t5kYJBN z7*mYbgFq&30?U7$+yZpT(eUWH<6qeS5FQW25!`uv`<*FZHC$9gW(G<@JykWZ??HRg zffY-mjjdmte)dhI2((97;QL~yx#owq_>TY0R#&rj;O#G85YK|P>jue}f*(V%LB!2X znEmSOgI4*Hx`DqkyY>-!r7lLkRL_9Nt!D#k$tTZ(2KlHuQ@0XQB+j|0C|0Qcg4>MR z2{}0Cq8ye` z0vCmlS28%~>sJ3E<8f2gaHP>$$mRn%62n3531NcvgfsjEj}hhEQ;QMpc7%9mLlrFW z0Ilw}mfs?D`WW^c+AXq{n%cynMkQgR}0)$Z+dodx+$a*6XzRFLBuZZ&cecq{CA#V0P8bYfwH^9$m|{u zZup!r^;-Runn8xLeUs}2{Qmjo2YP0Y=&*Lr`InZBuO9!zOKZ8l0C`hutDtpvNirp)T{ax`HBZi*cr931a(hZA>}heyTf%9y`F$O9GAD%rT|wa z4idc!>F-`3V9G?#AOv5L7MF*K=yVeBmfe)C-Nr5D3yr|!q%x(@Z9FAQPhy^`>(us{G-G2O%(n3 zVjTpkvG05&kFU#Gy6W+H#93*aTNOmNAmSFer?3XP?Pf1*6=o} z5Nvic0;9t@hF}j!K5Y~)5FR3r7zhWxlfRvU-?h;Dy=;iO7kNN0A{`*`%{Nt)Sy;JM z?!8=nO+ANXfD_BF)Sc79IAQq*{RZI8OhTL~Dk8Z(y66Op5)D-(kQ|3h-8fn2@*!_m z^7%Xvvt5k=cp$QA2*r)z2s9$T1&2qX=mspQOGqWJY?`w2Gquhy{w>%Mg~a~5<<(99 zR8OjV4C*dQlTBnZSgZFB_a3`V1LpZb{TBiA+yi9yG9(p zvCIKpqctW5wtYp>Ig+9w<|U_Cv6NOvjBEtc_1cYoz+2-6*6HoKC=Th>G*CWtFvH?C z9Y}sAm1H3jDBlcP2lp#S;+)$+)R5WEk!ow8)*mbL0<$62y^Cy4GU(`^^Wp9qd;oo2^d+$jVr6#gcf z6Q^Oddb5JTIo&2;thg0)9;}udCmNZd0PeOaIu@ggMy7*4HqIbh2sth~%AMov>=d1d z;IkuPRVUiOCTYZUa$pnsqain}BDfGgG;SYmeSJXg$=W9S&F-u9z?g%6%COAZ<*ELH?WC6cF z0Ab0M0Opu1CL~1rC5IuJFD*ade2`5f)X?HaF+g*=QzT%R@^z;CY$?SJoLg3)1Q-BW zhtA$IHgC!Pr77LVRm4@t4!f&MQsuG7a_(9`TOB9895gYYzb{dpy57rnqZI6!>7&wu zUB#Ev@0^ZM^VgnwqK}^auw=7ZM6-aYRG}45f)%T@xH*W)k?fE5C(<IVlN9 z(oUNz5!o6kB0Nq>cFcn>c*8s}nMR^^!$hP%n1`gzLtdutzhioz+$U?6B)2OsF>N;Y z8`w6zvU+iJt3K22Q2!z&1rMPdOz(;64t=Y#i4eET?&uXC{8co?7LQc-v$Bp8`{xzYYf|gEAKUx5zvsj| zqibSDj_n$#JXl%SRvieinh#X?Qp5XY)Ae4pmG*1GT^Ygd;)#qqr(nNcKH4tCp1;DL z71B)UlpxKI&-Cu%cK>^(fHJ3<_QXtc5U0kci(C|%ZsSAqf0^$eY-ZEx>T=cnL#Fp> z#kX{DU(*&-zw*K~Y-vs^ZpbRJ0MK56@UCvx=ax=X?`36!d&UQEh=#b%!~Y*^?*blG zb+rMXea>8xliQrhodn1|gg`Ff67%)YMup0(HBdo3B& zCB3lIEjMOoVqjmxmuRrv=<4q|qK(zAZx|1c6@#-!jx+}chlP9R_U)CLFmC)A8DplN zky=|*B?h0$3hZ}Q^lli|9mn*>Ozqy?7w+8~F%5dVOt75k^TFwluaF)oa1D{0<#MCI z*)`X|cyxTH)naq>1hx%pUkS)LfKJ?(DQ1XZ)QaNevca*R`Ea|u)7}Nl=cT3nB~nuK zW!Zm@nJisykLR18O+A0fl9Bh0ny_{F#TQ@vo88C1c;iXC!SUxb_nCQo2&dcaWyT73qc&1o)zFw(HXxzG z=gUhllH&#i8p34>qec%OG(>a5oR%`A=a9-F=++^FO0Y&PgbgjZI#3;ev*E((>cSEu zZ_uEDF!v1dI%IOhXN59R1(-#h44Y|DZzx^yd!K05m>(nYwpFa4D4 z7=MC6`CCb0tgqo>9XEmc%MBZ`Se8mpI~}cmSKT+Ota47@tJfX*b~ClY+mwZu)KaKfg;gZodD{#qa?zX8n}9Ykod`&a$!Vrrh9eOj%%_IVkt0OK|mn z)PXy97DE@l`)Q^tXFpi(^Q4Pgi{d~h}k)fhqz8PjWvBQGFeu{cJh#W+TkZXq- zLsJ3Vv-dk*zDsoX^QXs#X+Qt-|0K1QC;j(}k4~l4f~$3wYzMoy&e0RPjOmgUXz`LNK1^BJ7+Ny+S)3C%Av6GjX; z@PG{i8h6x&@jvSxGi0Fh;E;?AY%F=9+;p;F{86RYaa*>V?H9*y-MV>8l72_Z16>Um z_M7eFcfYXbIb+JNez{|($h7EtqiGY(Yw&q8QZp@W%v7BF#FeDT>3+;+33})(2&vae zC^LLqX%=;TT-R7@?|!xY>s_j8bYb4eZFQ68P3?W=KzDG?lPBS!tZnjZ>u~Vxm5}bvxuG&D=!~wHb2&EsnN1TbPcu9p8M#> zvr^+So6aj9b@rsbJ-U}vhH}5d67635+gVp(o!I~CWi{rCxJlF7K7_Qfg|hP2ua%Xz zah2;BR^D<`DB`o!dB;^x%lgX5JG1aJdB<^{+Fzv7PK)0LTcp?-D_~hENrVgB{EE^n z+)u3RSBzLN#W~$`bB(+#_`auD!o6eEuqJGYPQ>9+4041U(W9M3vXeorIJ#Ixyav!^ z#Nk-bJqb=T-^bGUIat~HU?@hMJn`Z2Kb&~~_kZ}SlUO#JLIyL`m6H;x+< z96IC5!g>hqR(n1LcQ)MAFTj5x6g2H^WvbGCdr14uhiCUWsjoVj_tX|^b>f_m)QaT-dsp?C3IbO*=nl6uSG+E3#qtfnWxzDQ^EqJjmQwjM zt_k?;BldUQ7GIMFtJo2k4t;6YEX{z0uJ6hG1J7A!44BvRxdR8D>p5>B{*4}Z+g{XX z{`@j^lNx}QukLf{rG4y0_PgKOhs*kvOfFMZ-+rqqOQ%dOwU0_G7oEDpb=b8FyZ-=n>|hqQ9Jlwt>lUn(P(5) zOG;swgnwcA)@5X7_{B#9zk4uS`HG!4;0)mKM{mS846Ln>Klu4aZ^aF&9oP_m;FGoq z%hx7``_IX`;TpRwslK{@IC1TAz4%M}!{Pyb%Lf*zlFz?Xc|`+zm)Dlq?|=OG+dX?1 zjOqFIuhn^jdgtZ!=?N<@VlpZT6>1eYR=o$nqKCJ0E&m zzxJ<7dKUGZK5&@#wWUSnMK#sF+&S}#`V@V)XXxPC(W+7P6;o4r&tEjrIJM56*{fgQ za&@1&QZ=iqntsu<9O2XDb@AloU4h$gNm>I=hS&5fsvR&WGgJ8olqD8< zhYU^bTiW-GsXcLd_e#Opl@r^qdICA&-#-BTe&$pi+a$R-n?AxDx=OM2vXXhOJvopsokJ&(PwlC<{ zuc}gQRhNsH#cZGuvyu|W2s#GbB}P#675?#bcW*~uLDCwEid1s9oJ7ADd)Mj7Ju?i; z-?@tlbNnfmd|IokJ9?#)d9-U^VB!3ewo=zqO+5n7R`slUHqc{&+F9C4yJ=}zTw>v# z)9j}1?a@ZI6`yNw6a(t~M+(nUH~yFb6bQ5QdvQuIBOU2PU zF<6`8{Ki>!bozuAkUIiFu{vSUYW%Q^!7OHs{ueylm`a~t+nQ!SY2W{AHTw5|Z5{Q9 zyV`!y{=)u){Z3~473%j2Uba6{lXp-0MI&l~@17wMB(gL_wMjv&g7^%>z{PaB!=Zl!Nt`i zGd?jv9CRK6BS?QhoiIvMi-T_dKhtn~i}8P5e`@Jd_Qyk2{vrFrVJiQ(SM65$!|jjX zP(6mIT6^y>HMC{X4mGRg${nhHnEhhQq85A0jzy@)LD%iZPWLX<1G_Dn$Mku8u)AVs zM2^JBjag?G3&rwdCG<}39o&jmYdpRCRhRW1pkDHnS627!Gr;vt-$0;$|FVjHRn-H< zlK-9SbK^btG31Yv&|XAVfG3(nCp_sJ0Z|H^uN4R>&2c)nd85W-Y%C%(UhO_2h zv3zd%?4`F(^0{Z$h33!dY0UNH)i3p#Y0!16UM3GMu>MS3l z^fXy7VWp%#95!$|sBH1q?%e}NjLXUP`O^mU8qL1UAR;~ z9A!oK?gtvi^cs-n_hsjd8v(>oQ2*qBmd!^HD~%F1XFN_hvRSK+!xA! zo~-QhpRTGd|9SdfzmdOIBj0`a>3^T^@~-P}pFU-kFJE}hfBzwgsTa?lt}^i6 z7aSs4>c-{-6#q;G4H0)}ys(kVy4`?9J&327cuU@J1rw~1Md$ao>Jn1V=y`sPUoT7^ z_4<$#D^FgOJoJS#PpmXr^kL5r8}ay(wm<9lK8$~tTTLT|EgNUdwMwUD4C{GaNul$i z>u&ks``6hS%t>-|a#pRr(ka=)=S^wb;F~%a|JFay*F8OQ-vw=7>LXqbj|}Xsk#7?G z732Eu3|M&!ume(=WF~rXL?RXO=F+nA;1{l_FwO6AQAbv~YlUS4~^c zp6wTRhLKj#8~*7BM%e;vr;B65X!WsQf?I-}s;|bG@O1dt%AL#ajcb4OkornajC-eD zF=v)3C&ov&&%Nc=gh^Zn>y!nrrm!>$lIIH0?YbBL_2KeJ%d;Wsh%sLz%M| znJ(40u*VmN(;l(?NXRnI^l~c_t|+2iFW2g*f_5xbQC;>u&J^JsB0RM?n~~5IsB0Eh zZfaGN?ba9dF>o67cYFROHT;BHwtN3ESKFRF8)YBz?cd8jq{_bjT9Fm;*fI|Lr4mC1 zI{_{&EzOsh30DJ&$=EM-VXw?cPLYFYh!y05CmcA%fzMOuF!K55e(8_b(AkT0jz+_( z++{OzvMRNYtA-DceRRUk7f(jmjJ*DSch8mWpKrQ%d#h{9%72~w$k~h(X_j3m^dbW8 zXrmj-eAolRtqM3T&hVtCrX`r&dt{{M`VwI?1g z!Z@>cd2vB@UJ63;z_pqy4Xf%DA6%;CXgEd_RcEjfBrA&_R9eQ}4f%9JbyYh7`=BVZ z9R@xc)O4b)&>y|z@o-{d%bM)ChKDcv!(X3XG;7tU%XVzkH?>xlEuFja!i{NXHr-iZ z*L!LLGTfU2*M~s2%o{)=irb%-YsB zwlCJ#Zq(%#JN!Ku;+u)(!JB0QTmWF+C#SgM&G=DMb<^}FCc?RGB7AE9ukv_lK2lu1 zF%)5-rr9kmTej%GFrKw{tgv&`=PT4_(!%|==6Vk;%+V05Djrusvy+p(I0~8D-GbS~ z%1wasivf#BKCvBaaZh`jiIW)nurdEodhXp-%Kn#FG{qN^X?%}fVIAYL(~^@@QgnZ| zt9xz+Jdz=pkI#qMikOD!8k}O{HBM27#5*G5L{?qVdn-Ja)1|t)KJxYpuUNMF#wVT} zF{VY|WG6P&DWCFwW}D#+gAW}0@GZ;6&epB=(}}R;AD88%)K14Y=R5RZx-gx`vJ8Jx zVj{dPXe!-{PB4mgBb}Zc9|u?U$^KLewM<9cHQnz| zFtpT^WD6%j<;+DqJwA%j5UVz^8_GYY)$s@Q>*88?!Asj_bagH~+Ho#yPve)PZ~IYQ z{@-=zgsCXX6b4*J%2dDL`vr1C1y?A`v3D3{+64M0nXA*NUCnX19NN54QU5 z+TXs55exKJZ*0fC@%D24-S*X#$T+lXslwc?5UCqtSg*YEXxkGnx=W`68AJVlN|%OR9m0La2hW5M)n!LR@8^UWG`P zt5SA$qz<@Fpm3f1(BhVs#j8~EQ+8PWX8HJ~%ds8(88gM1VB^wsL^+}dLUX+W-;fPGcZ(1=_Ju9PMpv;uvgw}|NA|yo7}D^p18}Nr@zM@dG&_&mt5FNg6~AsCkNUDPe7P) zF2wrD^!q$kX11qWP8#CUWu|+xwQTW-27Rs)%BF^!Ot7Ljryn}ZZP5)jbW|682MQ;& z@J@A0+q_-E?-=;>1be9kui3-Z@z?C-%eQZKPusI+Mf(?L2eZcXQ>*R1?KkVLx%O<= zd#I-mdo8QbZ%H`Ul7sIF{K|O{r2?OrI9>B5_zkSCaY788CHyY?1GI&}wv=h&l(dHP zA(+JfSD6@+{4(6bcrW4t+uUw%gEIOTJstka56Uz#o<(`W3Q$py;qZncVTB~z(gHJR z@rKWG!Wy`ff1DYdFe9RcME@712j23=p)K5N>A7uNYn$ELYUoZhla8oc(pvG{hn*ml z-q=tMzY_4GYr5mSUUxD|mza+!u)ARYP5e@)q$H=C_-2{uah+Jg@lzTTPp2mMAV}f( z9~CzsT~%*v*%)(H?daoj?ghn5KfppapJP3^Az!?W!}&Sx6(W!>+-zZ6oyr8PT1K4V zY>z~=@2=lWQidFlkpD{u;Hy!OgIhry z;eylp6eaFtqwUAh^>q4Vj*L8nE$X4QOXHoUi(cVWLK?2S?FTyCbg#o+sMBm2eJ!p# zTHT$e3*GoosLZ4!KfJB==;_0zm@n7F8AyzY$AeP^9)!grQ&Q_h%OUk0YYypeC!!FG zj;S>ft%iFCh%MAUyw&9!z8oPc&VpuOZ(er83U&1#zv#UJ-fF~2V*B}t_73}X`!&0z zO7xn4D7Z*+WX1ICz+mM{T`hk)q{Z8phqGv_|sQfIGqGgN5B^vX%o?CMj08Bj5K`o3R3`O;%^ z&Y3aioQbm+=`By%2PgN)xF>s75f(O+)e?16;qAHYTd*vA)10Gnw|)!n!~eGJ$KTlh z*gCs;7`AL>5AHSBQCMP4SXR((+=eaj^r`7nnN?Jh>Kza)i^HC=QC60c!C(iz1YA}^ zXb*{l;MiyXk9Nym8_z=E&Knvp(SDtC%}z7LlHgoY;;{;+kMysH4<0^o&FHae_8r%q zw`{{FSAX~E+2e}`oVoe-*6qdpJvZ;T>(2WwnNc%rXjQ5D$BYO1_t`SBZE&7D4yA zS#&R)IdOEaRn)zF_9}^Fg}vxNLyji_x>tOHf@2Gbc$naiFMv9v&X_8nU2e{iTRL`~ zd7025GxecePA+#M8{xZQuQ3pI93|isXr~gKys>BH7(XIQa;KD- zY(cU*mjP#l#zpoP&?Qd%u4_9g`lqxS|KL6r&VguQwo1cFR!5mhT3G{53M4A{B20;c zuR(DGtf#|IC}KtMs~A;o%T_9XwBZEzo);~wzBSS1c04&cQr19q3lQtQ)Nwy zcv~Lbm#VwG2os2vxjV&+C*H+t2BF3 zNAo8s|4MsTOtWEVdWyQh&7To>iBqc~9DPj{3f;eYxJI?`eMySKr5>^io6$2x6R5 zG{ibK)DBrVB>@XT;0o|tYHxD>umIHf9I2%L+G?zmvwonj-)GgM=@ zz3MrYukxNjWW@3fEhBLG@4&Nqm7Xac-`c;lXNWd0(F~;hm_ME!Y=1*T0SvN9=mVT` z_G0alj4)ww@DCGbVB-J>iz3l29SJ{8&SMK0e3)?o7YGf-Zryfrmp$24X&39?L_)4{ zY9ZVu=au_z_!dU98W67qrv~Cs5+b)lKjHCvETQxS-B|-V;ZZt@j!m$LUJ%tuSiG?m zp?OBOY;I{=V!vQaK$--X_@o(n3a-&4Vw=qmdn_(N zW+WM>E!af-JAX4`E4Ckt0QbNHU1GpFgMWG;IMib^#(yuyKSS!F(&IhJkpAR!xcoP; z!G=li%}7ax5A5Xh#HeQ0wI0qCj74>D)G}um%8EpG0NHen?EnQ$1fV0nLo3)vqTglU zzCnpwPe@OX%Sf^;pD#m4P15j@1((KU#39lnHUTYvGSqX3qO-Shnm0n44LB%yk@)49 zu-q?3#0jVZ*aYm~x@Obz8y?)bbH~c%x~3LNY`n!+sp)oWQdmEXm{wDUSX|?6M!n>Q zOQzIIWq5D^)558Hcwf!HNFm5J>@5gNY`9#2#Q02j-6l^(t|^PObdnQv73*cCWp=I- zcGK|H>yO@geeuH8EiKnxwK!udLLt}-_IN;EC$gqG(J;>L_T8UbH!vQCtbQfpBz)mC zWa1>bACl|Gp?oY^bU(aL`u(zUK?F?jrHG8PJt&34W-pf&A`xt1Gqei#w<_%wMhm=T z&xTfLY1^m2@Ob+ky=uu-1%YvYz-Vvl2anqT7k`s314ld-T*NKTG}YZM6x!Sny8 zm6vbvlp{zIg8=mlB^#TLPuYwm?zwv|fAD#A%S%;bY(x^VlSd5NahE+C`UWD#c?Ltz z%EN9BPBy{YRFP%H^(glFvU+H)US(DfFO;exMAy`F5_8gU9VImpht(51hmRA7bfoN9 z|Fid{2Wqe}f$PuJLB?jYoXF5}UqiGm0~bRJ;M3SwQlE2s+QI^NcQqboDaur@lkX=h z_kS)taLeTQjDWv{l^kH8hdzx6ENT-pQP zvd3Me7ux^&uZlk@x>Pl8fuC?q!`in*ZYP;>nCM06>D@8g-KD)U;9?nPR1>|4@OEp# zB#eD*n2IqkxFi(jrMu9sErY~!)4LQ$OQUU*zV@d(ejM30u@C3hlo(_FX@BLh|DAnH z+FY1qzJL1g-`f*CJAZZI{WGWBxAlg*lJ)v^X{tw?>%@paW!;>@10UJ{`Q+k#d-HnV zS(0yjx_!%i56K9Dvt@(|u%HBtz2CuG7a1@|)_6m$4NWFyF(d{M5KT z_Lr7%&UhtuSJPD0RagG_s10)48$3@$h72Qyb*zk7KJ@-64V4_Ry!;Z3Sw0300dw;U z;H8rTR~#8QxpLqPTudkHJaAoG>Wm(oasQ9eV=Fm+`nxY2{qf`$IR-{ zC#lw9i{`WiC)5gfDU4VmgU)iuF{20k2vexfSce-r`r1S7tGlT);YSK~=%#B%UVZm7 zuiJmom-TGl4kD8fx|4MK83ZEPXKzpIjx}e}-@j-lquHh_AB@JDigi8H^qJV%MNN~j zzm=Th%0-kg92mzA4uX`VNQ{A>tZ9DKVCu&WIa$AT@&n{mleTYHpFWMt5L(;3H&)+x zZpEde*4+Kf^G(yC3VyG9>>e)rGy7kUw_P8;J-g)i>qie~fpInH2e+dqGohFDG{lpg zg5e}9I|J$vgw4WI^K_-KYY$@X6g&Hx`Ck3>D8RBE`y-KnotU&g2nQ_v<-;sk4_zs( zQ+>ouTq=}9+*|aGf}z~4Nf;(0swezpeNY|t5f};));^T&)fW57+!=RY70S)XUAVSD zU%6h^CB|<1ZhO{?<_eEGuKq2x5cxtBVp#7b8aehqQW1>MuRo=nW11A~_RNBd;c)#I0~QR^axt&R4}_KwsZ8>`fR^g`z< zi_Um!ke`{5pLAF(N+l8pT!*H@!7FMaK{#RoQxX}9qsxAb=ufyt&{>tES`gil>8KD) z75dTZ&zV1a`Bm+kaRX)6j>EPY+EBmmuzJo3vV+KMxMOI4%D!3UK8C*Ou=Yj7=Kq_u z4_h15Qli4cDM)MI?%QA8^1tnUZa=kYSR2LO2Un3Me9D?pd*A;u^mTMbw0tEBd}L={ zj5oCMQB=gv$FL(#G%Xsuuq3BWO)WB0qyy@-kq&#O24;>b)e1_rQJ|vHjlnpa(jA36 zO~-VW2^~>lyTn!AwykqyWd?nJ`3KRJMW>e7XcnSH%v+?Nl?|=Uf88JEAAyGZy)43rJ z`!;S0Od6_(TbzDG^-F=1E3pfwIEG=K&@44oEHvG2Se`99)PhogQoVE-vX)$x7QYUwoqVGc{Q^8WY*v%Y(60n1?p^pK|xX&_mHkDyM7^-b#MAZ{&9y zrFs@IZsHF9H`WI5e<1bj6{)9>^;C(`dOF?>q@JUldM2`-InGxcUR-c{dJ42VKX!2- z!I{avjEwkrJsBZ}Qm`4Gf-S{FY%3+Edax|>bk@4N+F|(#7k{|U*E`SZpRa31z#q)V zy6)~zKUwtl4e%x~-)^xFw(oRRTK0eUzWrZc+nP7r{l{%7$+H*Q_uAX+h5BDc;_ztl z$wrm*AN#vD(V}NVi}t`GDV{#CZq1I*f=M5d;&Z#3P?t??|4EQWPlkqYgfK33Xqz1s zq|_)e2TRDa{!Vl@aTPis6$ZzAcwGJdU+|&X{)e~zsekMKP0P%O&Yik#)9Ou$?R#%= zO}F2{E&uQA{VMU}i{E%AzwC})1#LMGZN6{2*wWa4UW~K;v5Wx5`Hsjqcf`zL3uK)2 zPhmew7Jm7oVzlmF==s$Mkcu^YGf#B8-z^m%9O_P8H2v+ z&wQ|#EVViH&qzLlV)-zlE%U*?vef2ICzpXvE|{s3OAuU=tu-_hYN_dn$7f`xX2iL> zT{GP?@y6TI-)ejn^=OOT9nFDb#vCxN&qv0rI5uWZ9y0dKLz`RgjG06mMNAvy z0gt-`c-&iif1vAMvP0q+;r&9Q)qH8YVnOsL`d*sSr2;b-{_}{To zkJGXWJXwNgsl=Qq4Z%mE<6?;BA+VjkT^4EZmAnF1?&wFhigPV5#*K{J-KfzYA_Ils8^H^g;`Y_amAq zR_L*9?hZ`|b`mk7(ww*77~Fmd42n3K6xo#Emm4RvM*c9@NQ_jNF~qJ)-R8%0eN6v_ zod(mOYvj7NcSYTYY{^co$riurv{>b^#V(^mVj=hLrEKx%kzT>Ol%_tho~yL4ls1E1 z@5SG|#g}I9n0A0*^mFTE>|kQy(?nGe?n#1pQwwTr5Rt%w!hF9L&KBcEeK^` ziXC58XS#;{Fn%LU7yise{MW_IKXY7koeFUG?5Ix30fF!b(BL z9UO%*LS3L0E#~*C5Pn07dKg*Q<}XB8%R<8_D)!`@F*OUfCw&ssEKkcDGc{d|QUS-j z&qJ-9wr8Pl$^s2XFJX9K1to?ty@SbqWvM4sDvJwW1N!TYpL_``V8QLJf1I_n_3-Yi z?yp{0cGo*EV{mWrA9?He2l|4OPk*&+9yVsO9(}WETC4uz%^U4+7cY=HgC#v{aCW8u zXV}kbDC?7&n3vbRTZ!TEl%yJ!{d#CgzHSIm32m%5j{8Ax@fBjW`8sZ?MLN}w(e1FM zMICV=oJ~iS=`k#NVXYcluITl&3~7OU_i&^*!)0G}$&S~bTe+n?ZtQPYzV*eQ4$r-R zFwQWvT-N^EZNIp4oBheni?6>C*H)f;{nfJkx@WPp#NWd#g7>qc9(l=Go|4l16daYt>L16>;&O6eN6PWV!6*`U zy8ZTtEh!FgvjQe)x%1K4J%H0FI2C}JtU z=!+LDbH^{n0AN54>{a70n1Z|hMFnem72SISoC2g>J@=@L0=@-DFbaj(&*+uitw&*g zUS3AGLYL1|RNT#t{Z4q^bmJ&L%YM5IAvE;zF^#YMa^2I} zaoNAQ)3&3#-xFYY^1=SvL+b4HXZOg>$w}|wH!I=J1bU7fSlO67A7F%g0T;Zq|r~z~HKe zJ_E-D^}o$uv|!z0!N-)$M*3~y>ynvv>HgzAzQS!vKHK#GWYJE37c5};4$O}HAhj2g6D|DK0VYkB>J zy|1^I!jycxRjrQp(+h7N+^4Ez=05ZoJc{vzQWj1(_jc>4W|G2$Ou`mNb~lB!W=iBR zR|32j8(Art={~r}5^9cGci>m<2Sz`9R2(x`*PiSjv3E^qnJZoR;+{k8k711iuQCVQ z>({Q1PV#;G7e!CFi4MLA^Ewyf*)t<9N7qww<8XFL1DQfyO5}3g<;Jljcci}}!iRr# zI*USY!I68LywX(2l{+q$89vG%AmX>$Wv|e` znGC-ikE`3&d7rCEPga%QSyF)`?4RO)d(|f{U zjaMK3wcV-@9@hR1oSOP@F}i%hsxcqDefYzz_eExc>sv^h*tNU6F|0{&6X8mSzd)bz z#o?43_)o#ip`f%xH~*=*bm};XD&x%4PP4)13fq;7FaKi4(dYIZlJh)m7p+|e>)2tt z?8QTG?lrbb>1F7VHJFEK;^SZUd2vJ1=SS(vpNidgoQFwGNrL$+DbgK00MKbmS$c!~ z(5YOkqm7kz%Vk#`YkBU)7x&vcj46mFy&rSVrH06yJNSw|cpb`~kFuvgW=iDDU3y-k zR#fQDu?n?31et@P#H&at-Hq;9@I!N`4v($C`2l+^SGCkkL>a)}( ztEL~RPn@i$**C`3v37N=*w{N>Uo4-iUAIT_85UcyaZKp775QkTI>!Vn__10!``U1p zyy!`e64%Y>Yrct5!uomaJJRFEAZ8iu@wn7j&6c^oinK7ZbC08^UW(OhnQK#|W{#U| zv7+D~x35z^*SNm?Kl8c9b@xx?GbL7^<*|G^eBU@d<%!j2xoc}ApI}E%u|6?7wDEJ- zr;++}*ae+@qLyec-ig+yz9S!*1>Q59`e>!9QR|D-3SOt@MRq&v+A=TPpF6d}ENg_T zWqA+%F7L(c+xzhzZUEsuSf1fge2xot3-sV3d#lUOlasJF^Z9N*cP!O1uN+JDY?oM$ zU?=l&faI5uK)*-kl~}4}=HWL|X3yv-J9$(_^H5EvK6CPLrd2c#_lZaz9@X>~b13SR zgKNH5W+rQaS@#nAQ&-N$x5$9hV>)LP>w$M3MLlFD$~A`-6PMit6u_ z&k`4`8K>og7P)FUGoAV@MMMV2>eID8-8nOz`Yd&A`>}kC?>IA^e6Duwj^xu}gJS=3 zW;*#?9m}US)-H}})Soiv+w(FOn3+2Alkty@mW*@MYck(N>ttsBoinp0+T%QV;FWR5 z$paZxV?T51824p({zr~Gwmd5BCIyC_rl*<00Y_lI~s4!@A+ zGx>Zur2TnVF=-2x=WbXcBeDrEVR#PvCuI};kLQk6Q|d_DsXp7i-f3-athE@+nXIE& zPDM74vyOWAXdRtAL?W1nvDm$wBVgz~VhkiBa3v*zxj?dBLoOm&j)-^IaXa!^@+0}2 z&)Ueh!^vmKPvt|&a_Y0xz3fNpGn10#^10f*G?LGNF7290$#U|!+T~d3 z484QNI3|=VEczEaS8_sJ z1n29am&bB~rkpJ~>E}rf+Euu<1Q~Wdu+F%5$zhnbhIP>ke=3Jz{O;&6KEbFX2S|?2 zI&?@*N!J{}YOF&i$#FJqVzmIPIeDN4Tb){TZHKU$(+<`2FSf%m{!0$_R*5*^{qN6z93i;cj@^cV}}B<9(5SH{z0` zCsjtYmGFG;s^$E^FF8L%3&R^RTRXk=bF|KPMoatJ$s@)n^q$Yr!Yr22!Y2ngltjn- z^c;q1)0`Y)aWGELVc0XwA@==na*)wt9ng;RoE-8xwZpwp+M!DwWVGIM+TpmPL!UZ% z$Y?PS{C>rcwS%L@cHk?;TJ(su1EYnw1x^m^eXtjDM(<1X0H%5xBi}&PSP-SmEZ{VZF z&miSG-uuAd^!i7KXZLxX|3*1&3lYWOQO^q8X^^NhaKnUK%Gj@jd!uyIdJ&;e z0A9ivOOcTh;WoRle-QpGGBV-yqdFb`X&;@j;DXD~pV5Co&0|CFnsCN|ofDUw=Q=+2 z>`eRE zjPoy_dvT=P_OH)fGHGYcSl96(7oImVlLhabu^|1@^CPWY=J^h-l?cLFK3oOOfhjp7 zIXT}jJ$}<~X7`Ae9_ZX^-U}Af1j_7axrD9g62~FXwGVcz@Jujk2iKNYbjuFz?c5b= z*_`fYt%}bpDbDsx@StWFp-2AY_2Fz=F)RUys}~=io?e>Mqo7B&6%T7gftHx46&UF+ zW+Tku8|7a9Pc=AX6JYuN$pZ=yKnKRVS{sf^-exJ>B6zaXAB#Z z)2nylw1f+0bnZt_{~pCXsseKt!tYR3)kTZ!?H&Dz`eJQlzvg)f5}T$KHKcf9sqiCk zM}yZguT72T}M@#E&soE&#?!Up%Z z7hRZs`8jY)f&)7W{Xo zH$X=6yIl*nVCeSWy#juKT!^bfcJEE^_2z z&gFJXtd2^nvWF@t57_1G){vmNao7#_T9a^$N&=ubR<){rnKkex!)PVWse%u0UbbcS z1w#UP1B$D^p0j4j^=HrVU266NU256(m1?233AeluztqGgW1?gh$xZgiaBR`?MUE%n zw!p&A28PS(XKb=RwA-@QrOr~Fa#{cXHJ9}`a^d7sEZ>nD5Z5qRR3P!EmIz041(fMp zgnTo>ooV84)uUx)$ES~-8ed|hjGt;CCU?YS7unInNQhTSXO{^M)?f#6qQH1ung99V z_`m=Ahu{CV-F5G+w`|$6{+3O8C2WbWtNyUirKtY)LHqA-eevfv-}vfF>6^Z&LeMn> zHxNrO{0f(*v;;&Tf&+h##8hULvom)&xCXZz)2A1s{kTHfZBCwc=*I>Tm0Y z^;>YcDny=TSg##Ji?X#o4OwzgJ`?BryXE-Iu~U5|S@7yKZmMJ*Gy2g^ikuNy6k&pR z2{XEL053$D`NpxfCUyIL3;W!>c*^GK(_Z|?zCT>I$NsIZKfhX4F1~2uke|(|A9LA` z9UB)tbM2q7g{)x7*x<@>U4cDZSl|$FTub%B&q+o>lBZXhD-+v2V{!4-EH3Ubc4~2n zX^ov~7RUNHVirBk0w+#wWETU+Yj{>#e2$#%*jqL`jIZyz?Xgz-1N&cByma=t$IesB z>>0QH;*r2XHRQ zIsZdZMF3kThO03^@B1eekBRo5>qfqH;bVL4wKKL(4(i9+pDxB3kI!HG)V9yu+PAvp zJ{9O5)OX%vpOGoE2i?XC91Fd?u0{xEXA2)ULq*Bs8wxoCSaq)5J|LmCQltO8h(HJ4?SlqUBW zKh=br7;*bGc4}IQ?j1iBw^^g}RAlIfG3{}QLk>XsV*yBU88^ePqIPzf!X>Wa_KU6< zK4JDZ|4K*5dQ0D;_7Rn#6F%aYD9ex_-jl>V66P;MLl+hKfG@`c?EU zDd}Zuxt80?(0WyP`qz|K6&Zai`<7J}7WT?D({OXYS6OyiS{cmraJuI^guvxc5=5}@ zzpjo>oQLx5ite;YlS&ybmi{Uot2O3dhB68>WxpsjRkj6#g@!(Q!!@^$nY;MT%mK|y z&boEp^63S$CWgoQ%gjoii`XzqHq^{9gGz`UX)uDm}Y;aex&_~UfEu$wy$kJivIB9Mk;O+LqCR#dvNd7YB06>o`^NM z!#xtuf95>bWG$_03-Nvs`zeXoRR@EZ>D`Rpy?gX1N;k^;M%b$fq z`dL0dcB1{AH&$?mQ}!aGJ3!7PgcjwH8w~eunT1gX&#VqQn`qH3;uZgZ~r{{;j)CRRbT!09~;KLebucGEq?ky`6q9D^wyE%mlR#_OE~j2Rh+77 z`NhfYUwt)lOYe$@e}PuB6|%-NU=@}%J-87oa>oD_{kvEnBY$snPOHXN?EJl0eE4@S zE`v-)?;wYmz3H?P^w47dy^<>%um>zYY7xG6hGsp5OTXCak!vaF7bp`VKKpU<>H9Gv zv2MJ1tE^a!jYxU5VfHo78ps`8E&c`r6YliJRi}D)U1^|e&)1w6iU$t z$|&YZ0<9+Vv! z{?4oQ)$2r(Pkn|GyL(Kn6wh0w2NAvLi&J-L-X|2a&cXd9_sD4I9{H`)=l@r4{QvTs z)62aFb#=*_S?VDxV&itFm2uJD*$rFcidgSp6>cm?FX3fPdn%x*Gd$O7TJnG*NKMhH zg}@+m4!2fI3=zXvQMk3?ryd24Jhd7)ia44$=G0z1nLs>?*u>`(nV!USGt-laQ;65G ztX0J8iK~e>5Z4gzXSv&$!-Fh+JMkf63-Oo49mI$EW-IX#;!fhPh`WeS5}zVIP25e~ zLwtsHdzSbd@p5f2lO5RVeyB_1OlC%#8KLHv+q zeN6n6_&M==LFFOF5tE21@+)N#Q;F%sO#U^S*qxY9ERxYwCB$+*=}W96RuQX-{fPtk z=0F(*6(SCk_9{w(8Y!(-lmSHzy!wFYKNJ5- z{F-I`gKvJ%9%v)lf;z&X0)Hm&=u_k!eX7(!KTm$E&*byDOkd8wE+WF(iodSl^VP&P z#I?j*h))nHrTUvpALeh56aOG>(cfeGeWp(^{Q=V-@%>Mj{*3qypZtUPt)LMv?;9r5 z2}~z4P5CkWe3HQ@-H18FTt4qk>>({RdNQ5IbUxDsOcyd;Of2D(Ql@(`UB+~8rpuY` z!*pM!E10fix*yY3Ob3{*X1a#y0j$+PVu%BJdCj;6uUG-k<|8ncNP5$6&wCC($x7pX875*HEILt0ESs!2vQ$*86#jB3I*nFf@3 zWRg)$GODS`Y%+0+VJ}b^)zpMhO-*WUYQm_dCiOQpVN_ESMm05IR8td1HF2U;P#D$J zgi%dR7}eB-QB6%4)zpMhO-&fpMC4aNVN_ESMm05IR8td1H8o*WQ)?v(qnes9s;LR1 znwrR}smWY3HDOd!6Gk;PVN?_LW)l|Z$rV>Uql`yKQgi%c;jA|-jR8t9~no1beRKlpH5=J$Z zFsiA9QB5U`YARt=Q*o5ZsHPG|H5JE#jA|-jR8z6%$*89KGoJ{fno1beRKlpH5=J$Z zFsiA9QB5+cNk%ovs3sZJB%_*SR8yZT`RKx^rY?+X>cXfd8P(KcXg|E{tmG!lwM<`@eSge#1Duc5kDb*Ca98$KBAwPMl6!rsuE&v$zSy$RuKCU z1H>Alj8uw}kxEf)mm0-kS+QRg1rk^1` z%O}q>x0g;$N6x~}De8Ux^<(DawCj7O+laQHt`X%6m7i#U@jjw_@qOx9;wwa9LZ1@G^XU)E6ZE{KpJe(erk`W_c}b(ycn7VPw0uo0 z&P|JR)6!&aTAIvF3pH5?l(}hfZd#n17U!nLxoK%KH!V%(rlrZ;v^1HUmL_x4(qwL0 zn#@g0leuYWGB+(v=BA~|+_W^Ao0cYX)6!&aTAIvFOOv^2X)-r0P3EShi40quo46Xq zw9HLQ$=tNiW2i0Xrln+VTAZ7flDTOqnVXi9xoIhxo0gKfX>o2^oSPQsrln+VTAZ8M z3t^rzH!US|(^4`wEhTf)QZhF!C3DkKGB+(HbJJ2XH!US|)51u}6PcTq5_z^bH!aRh zOUc}{Fn02$%uP$l+_aQPuf@4(=`uGh&P|JR)8gE;beWqL=cc90+_ZF=o0cwf)6!*b zTDr_lOP9H6=`uGhNC@h~xoPP#H!WS}rUhw{=Q1}fUFN36xoPP#H!WS}rlrf=v~-!9 zmd>_tZd$s`O-q-#Y3VXIEnViO#kpzeGB+(<=BA~~+_ZGIj&sxE+_X41EzV7gbJOD7 zv^X~{L*}Ms$lSCHnVXg&bJH?pZd!)SP0NtEX&Ev%Ekov}WysvL44IpjA#>B>+_X41 zEzV8Lkhy6YGB+(l=B8!H+_Vgto0cJS(=udkT9_#dVM})tO=1b&EW)f2gar~P(p7}H zBPesH2(#uPo=Xf+BAv zl(!PFv7|-bO2Ec~B5x&>w-U-*3FWPX@>Zfm-b%p6f+A5kWhO{zDWSBKVE)Pzk(Lt7 zUqO+U63kygk(Lt7UqO+U63kyg$)}W3QA(*O#X4P{h*XqPDoQC8rJ6`ZDZWr&0cE^O zvC5VwA{C{Sic+kyB`s1>N~tKNRFqOGO0l+;=OPuQl!{VHMJc7Clu}VjsVJpXlq!}& zsVK$TP<|y+QHt3lC{j@hJ_k}NN+}hkl!{Vaq@t8kQA(*O#cD#Hh*Xqf9U&-EQHr&L zph!h2)(e6n6{T1s2#Qpcg0)ZzrJ@wGNzx(}y`X_FgC;KePZ@eoQ2eWvu@B4GKV|Hn zGWJgy`=^ZkQ^x)&W6zYaXUfTfTFI7HvZa-fZFw#%R0#=}bch(nm{zhM zD%lT}?1xJBLnZs6lKoK0eyD`@B{^&+-bdU*yr22Ve6M6LRkD{V*-Mq|rAqcvC3~ro zy;R9ws$?%!vX?5^OO==@$Okh;u(#w7?MtwN*pC<>)({8q&4E$}%qBr$j7rQJ!8W2T zh*^Wb;v0k>!#7A!*q{=+5c21URB}WrIU=Yn71;|bTvQvQU6d*eV$W8&W zQ-E_eKz0g{odRU10NE)(b_$T40%WHEXLNuwI=~qn;EWD%Mh7^f1Dw$T&gcMVbbvED zz!@Fjj1F){2gptVvQvQU6d*fQYbo}>u^(>{i=d}fvzMybKh@|Td9sQqnr$`uM^NWk<;_vV(Zn&t2^g24CToNs ztnu=WtQ3N<#!Fh(3qe@pr9_d0pe9;J5O)9tMfV75(~0M>ZeptsVx$DGCyK2;h>;Q$ zTYZq693&?P$;m--a*&)HBqs;S$wAoj<^2a)|Lw$wh%Lll5_b?~y%vN$U+@v)PU5eK zyNI%O3&Nf+_%v}haSu_}p+VU51)n3zYA&d~z}AUXKM1S7^yDi{zsmGJre9-Pz7av# z_T^1ki3DNcm$c}ILD=~vEm~p_)_zGJAs!{l{#_8(enGL~24U?NJV6w#G6nf|pnRi)Dl8JB1`!*GvPTfa z9szn4djx{=bqivrK%R?LHmFYWNxPt~%dd2U=pu?{6{Kbrgryy2VLsxwu(TsLegT89 zx66~6@>k4Lq+y-LUol%HoyW9Tr-QIg%X6_#2QhO6OZY^r(?O#b(`8KeW?HP%L8A}T zVx11cIxRU=GTo2qDy9QWi*-5(>$JQxfa!t65HU<_APyxCC(0@^XmGaj3m$}}TJn)K zLeOYrT2=}{e$9ghXEDF&L4&iHU-lsE*zzk`I|O0PmNe(GF^y@?Wn((ivYH6OzAf*F z77>J%ThdM+&SFo_CSF9GOB7pZ5LRx%1^ks*wg-Z{jsY!V5p;ur;B!Ivhyh+tTur=z zxQ6&L@fG4eK`=8A+>6{W;(}A;3C2{gCo!K`NGv9n5^>WT@01g9KNsmrVimC(Sc`gY z0$N02*IKaaqrejWRkXEQu&bcxX0_neW5AI_k=t5rG!eH9k%pfV;90~bKA*_+B&M60 zo=lWh)S^$MtX0J8iK~e>5Z4gb^36Mm8;Bc;cMR4llUv*F5;6!v60q-IR$qU_Yj|9iO&+BBR)@jnRVXFcf}ijCh>*9`OY61ODnm;zz`fiJuTZC4NTyoG9zi zT5zUd95IQQOcWWe1!u}%MUrcw)k`{+=`^O(na*T7n<$c53(gc2*{cOl3X1I2f+qzj zd*De)50jn&A4>j|EAXK_r(A&#k%s(3N+JJ(KjV`r@+&YNeg(#pcg|yarlc`D@K-P% z{)#yw={%Ap-?FkQ*CSdVL=&&WGs zSE+?oBk3BZWi3;S{Ww8cqt#+RPOyPEl*qPYwIVei!zW{z9>?@}rW=_)lWEQ`FrMVY z`31(4H0Ku>PtxoqFrK8R@>in0)M9lbrHJ-Yi#3jVUG~mBSiKHkv&4t%8uc=jB-dkJpzS2LS&B+ zv@&@vtqVableDxh1g%U^*ds*t2$4NPVAMzPMA#z)y-QHoBLuxm-W2u-LGKb2_6R}m z5)}3bLGKb2_6R}m5)}3b;T(mautx~zCw-g2p8%>=A;-B`E9>g2p8%>=A;-B`E9> zg2p8%>=DAb3qfIz5ZNO{_6R9qj}Yttg2EmlvPX#Q5h8np$Q~gj>=A;-CGQA(gp{yH zNC|s{$Q~iGM~LhZB720$9wD+vi0ly}dxXdyA+kq^>=7b+gvcHtvPX#Q5h8np@C`-Z zl08CXj}X}-1bqpmlRZLYj}X}-MD_?_je}o7UqYRsFG*V1BLsa(o(Ow{$Q~iAdL%9E z5h8np$Q~iAfaJNbM+o0yNeg>~$Q~iGM~LhZB720OFUenpJwjxU5ZNO{_6T7&U!Dtl zgvcHtvPTH|lC(nDBLsa((!w4gSU)5!>=7b+gvcHtvPX#Q5h8np$Q~iGM~LhZg1#g< z2z!Lc9wD+vi0l!9z9i3uJwjxUkRj|5GK4)sI29l$>=DAL06}4oIbO>_qaCk~>yA3EIO@38sH26dj;n?`t{3XKQmCVa z3UOtn6iB0B8d12Yj+%2Ftwwd!IqRrx*3oKIM?JF+J%%@_Th>vltfM|zhn|t=qC?hE zdkljcSL0-utXsq6#xS^1($eZMTODSr!)$dJ+_(wPM-t^EKp5O8C|`syxN$E~&X0w` zjq+U1kA=aFl9uyhVQ}N4Ksi4a)}$t3Fr<{Yig-OyPS=FNkb-i?Cd}Rrv$wg z%-#;Ox5Mo1Fc?zGdXTuC_zE2A2Gu?;jzD!pzUCDGmrmL8i zGYMgErj$~{^Z?>OVu%=wKFgR0k7%M#k&Xn|crW=_)lj*aFoOfh^u)%pp z9teXoZ>Zv)@Q)j5B zwouQne?7nZ_59-3^IKofuX#Pc}a27P%3$ z$c>;yZUlHw-W2=Q2o)rT7!ZtXqG;jrH^LmqgncBmOdJ@?<;LIOCQbBN7J@5T1n}nS^8*}KANSUfzp@Z zMw%&z(ghQMV_EuGmOhrh8p~fbQkQPj!PaQeSPPzS>BAwUPR2 zBlXor>Z^^^R~xCXHd0@0q`ulneYKI=W+N(}+2X-%`VA zq;At_u+^BA@?2IxjnrNmskbyzV`-$W(nu|30{e3U`*Q;Oa{~MGEIvPr&(GrXv-rG; z&v73LquIpKZ{p}TarB!w`b`}DCXRj+N56@q-^9^x;^;SV^qV;PP0YW^$)BS?k)=#z zDHB=BM3yp!W7MTQlXYnex_5 zd26P;HB;W2DR0e`w`R&)Gv%$B^4821P&3y)&0O^~Qv#bQfz6b_W=dc)C9s(i*h~rh ze@J@&@Vc(M%=hfGxeOOdMu>8QIK2-uke=+e#&rt_H@!Tb2Qj460==bGLZh^ab9;T8 z&bS#l4P%Be{9i3`li2 zI@)KS`@Wz4^FH5aX`j8;dcSME>$}!oTC0^7*h&j*r3JRq0$Z8av@)Y8n8((+qr`46LS52J4nqi+wZMsG`flveRkT7^zgR}An`#jZxL3VxKje^gO{ zQefbtiVcpZ9^qGy@T*7o)g%1s5q|Xuzj}mUJ;JXZ;a6?6w>H{a8||%)mexi~Yon#L z(Tdt=MQyaAHd;{|t*DJw)J7|6qZPH$irQ#JZM32`+Dsd5rj0h!Mw@A)&9u>G+GsOv zw3#;AOdD;cjW*Lp+i0V0w9z)&Xd7*`hc>+5hVR<&T^qh@!*^}?t_|O{;k!0`*M{%f z@Le0eYr}VK_^u7#wc)!qeAkBW+VI_@uEmH z)edP(d#Xd)V)PuOLs5j$`_np7@5Xj(>_~ZkT1U$J(>hY#pVpD`{tJ@)LHyjo?5u;?S%)GGJx@H`5jYa= zP^4k>_r4B&%`|#{T1Vhr(;fPnX|!r}=&PmEy+5rZ@cy)pbjp8~`sr6vKcgeA4x+ve z;=K+cy$;1HPIrvgp;*P(3Ob_eAeQSOit8YL>mYLL2%qx%!*q;b0<7^!gD7)cfxZgJa@u#Cp>q; zb0<7^!gD7)cfxZgJa@u#Cp>q;b0?8=Cp>q;b0<7^!gD7)cfxaLXr4RaxeK1V;JFK) zyWqJCp1a_=3!b~+xeK1V;JFK)yWqJCp1a_=3!b~+xeK1V;JFK)yWqJCp1a_=3!b~+ zxeK1V;JFK)yWqJCp1a_=3!b~+xeK1V;JFK)yWqJCp1a_=3!b~+xeK1V;JFK)yWqJC zp1a_=3!b~+xeK1V;JFK)yWqJCp1a_=3!b~+xeK1V;JFK)yWm;>Yp7PC|Mmc_8{P2S z4bR>1+zrqACdo6_jc$0>oJ{`ehUad0?uO@Xc@4kr;XWAdgWEp1?SsQUIP8PNJ~-@y z!#+6dgTp@9>w~>M*z1G6KG^Gny*}9MgS|f3>w~>M*z1G6KKSXQ?tRp~kGl6!_de?0 zN8S6VdmnZ0qwamwy^p&0QTIOT{zdBeXW+BopM%e(96vvoa%}dTR(;om-i`d6+S0o4 z0r0(~dwt-!)USgbq;!H^U^mzU_JTQ{oX0MLC8OGg-mkV{Z1yv18%FYC$JcZ0_AV&jE?r7BZhn~?JtSXX_e3T^PqPlKc_W4<6FV|!MB0$0DlR5 zC-^S#m%*p}ezh6n)1Y@F_rqI1y!FFdKfLwBTR*(@r_5Wwdg8j!y!C69+bQO)pPh33 z?3C-*Dz{V2TfcgupEPg%?3C+gr(8e0^}|~~y!FFdKfLwBTR*(@!&|@BPW1+M%Jsur zKfLv;uj&2p)(>y}@YWA+{qWWgZ~g3)>xZ{~c9&rZ31cFOhZ+mKVt zTfh36a)Gygc8-%w(cpHSbL3kU4w?TLtgttL>8-%w(cpHSbL3kU4w?TLtgttL>8-%w( zcpHSbL3kU4w?TLtgttL>8-%w(cpHSbL3kU4w?TLtgttL>8-%w(cpHSbL3kU4w?TLt zgttL>8-%w(cpHSbL3kU2w;^~Ng0~@f8-lkXcpHMZA$S{tw;^~Ng0~@f8-lkXcpHMZ zA$S{tw;^~Ng0~@f8-lkXcpHMZA$S{tw;^~Ng0~@f8-lkXcpHMZA$S{tw;^~Ng0~@f z8-lkXcpHMZA$S{tw;^~Ng0~@f8-lkXcpHMZA$S{tw;^~Ng0~@f8-}-GcpHYdVR##c zw_$i2hPPpO8-}-GcpHYdVR##cw_$i2hPPpO8-}-GcpHYdVR##cw_$i2hPPpO8-}-G zcpHYdVR##cw_$i2hPPpO8-}-GcpHYdVR##cw_$i2hPPpO8-}-GcpHYdVR##cw_$i2 zhPPpO8-}-GcpHYdVR+O3<7y<*f9Zi9Pqo`lx~JVh(!&vW8-X`{OCiPM!U(*Lz}pDC zjlkOoyp6!y2)vEJ+X%dkz}pDCjlkOoyp6!y2)vEJ+X%dkz}pDCjlkOoyp6!y2)vEJ z+X%dkz}pDCjlkOoyp6!y2)vEJ+X%dkz}pDCjlkOoyp6!y2)vEJ+X%dkz}pDCy&&G! zQZI-%<9*`f1#x2R1iQd)um|h~=fNUaGOBh$m0#~s`HkLz^McB6{CUtjzFtuIjc*0- z2j2$11N2U?7gTn zYeLF-h;kmHoQEjqAbEKHk;tX|%{s>(i5z<*aw+eT$Z0*<>E0ue)2gy$Z<+i;? zBBwQT+ukFQ)0(-_dn9sNGdFsVL{4kwM(>fxrMyQX#~z6sv$LGOxj5zT!0&)JLGO{s zae7ZK@E(aAdn9s!_ekWJ$K?X=k;pNd%LU#ekz-Dm3%o}n$ILDlc#lLb@E(a=;5`z# zzwaxzKwga_UpIy+fxh2A5PW2T%7y+4!-_O!{Hcr%0b7eTr|>Q+%7A;@k8T-=?SdHa*3+ z=_$TVPw{Pfif_|Xe4C!)+w>IQrl)xS)DPd!x9Owga+F+-lFLzYIZ7@^$>k`y93_{d z*OZF2~5_7`YrHmt*8|j9iY9%Q12} zMlQ$5k)uoFtc%aydmVr^w|Lxtt=GQ{-}rTuzb8 zDRMbQE~m)l6uF!tms8|&id;^S%PDd>MJ}h6%bHHN`f;QFYWxY|8FD{E?q|sT47r~n z_cP>vhTPAP`x$aSL+)qD{S3LEA@?)neumu7koy^OpW{pM9AAp(6lEPx%_+(FQxFMcuu3(@zgoWc8;>0qip9W+d0a1j-O_RiStB>^O_s_8GnbG*WA$P?@;qZar3M>&$H${&zkc*YtHkmInT4^Jg-@ypZE9c zd7`6v;-YyXqIn{md19M+qMCVDp67{J=80A2iBjf?Pv$k3RCzR)H2VAXeBkfb^O{Q< zA9OC7GdkVhuje&q6l%_>zluHmO6(aOQOq+U&odU!GYZc${?0T0&NK4PGv>}S+Rii1 z&NIT!Gq%n%s?LZ0emx)h`}Mr$j7ERI*6ElUO>}0P5#OE1cSZOw!haF|i|}8B|04Vs z;lBv~Mffkme-ZwR@Lz=gBK#NOzX<(U+FT#Hj{)_Nm zg#RM^7vaAM|3&yO!haF|i|}8B|04Vs;lBv~Mffkme-ZwR@Lz=gBK#NOzX<(U+FT#Hj{)_PcE%^Ty{C^AnzXks#_%FeK3I0p)UxNP<{FmUr z1pg)YFTsBa{!8#*g8vfym*Bqy|0Vb@!G8(VYLjOW%w+^XBj@r@L7h>GJKZdvkaeQ_$#(GD8oh> zHp;M3hK(|8lwqR`8)ev7q;`wcZjst8QoBWJw@B?4sof&ATcmc2)NYa5EmFHhYPU%3 z7OCALwOgcii_~tB+AUJMMQXQ5?G~xsBDGtjc8k<*k=iX%yG3fZNbMG>-6FMHq;`wc zZjst8QoBWJw?yrhsNE8^TcUPL)NYB|Em6BAYPUq~mZ;qlwOgWgOVnXXrgqEJZkgIGQ@dqqw@mGpsogTQTc&o))NYyDEmON?YPU@7mZ{we5yA=) z!ir{dYpIo#*M3)0Ui)2Za78L-+iSlon&mmg-vn2*s$=xG)D^Aj82wFfg|*)m zt(Mp>f+eH$O7E9m8T~DFMS5iPB(swCx6~EQ6OI0sx}tfa@fSgVOI->5O>jl?eWSk#u4s;L^taR%&FhW+Cb%LU z)BB}kMt@6PVeR)dqO8}5vR>0|9bZnprub@H`0ud)z5ZL^wbTc|-vvJiKF(inWB~> zSj88sTCG}3t>TMSe6flzR`JCuzF5T~>xWKM}i;OH6 z8Cfn8U0)=+zDRU^k?8s&(e*{5>x)F!7m2Pf5?x;;y1qzseUa$;A|upAMyQKK*Z-5e zbh^A+g3dVxz0$HqUTfsFMqX>=wMJfR?UTfsFMqX>=wMJfRE|J$I^14J`m&of9d0ir}OXPKlye^T~CGxsNUYE)13VB^2uPfwr zg}kni*A?=*LS9$M>k4^YA+Iasb%ngHkk=LRxsCoreub}D`RK0?#S5Wl|s$N0WE2w$}Rj;7x6;!=~ zs#j3;3aVZ~)hnoa1y!%0>J?PIf~r?g^$Mz9LDeg$dIeSA(i;9+YAfZr&sOSvp#Oto ziyh!w>;T_l2ly5{z_-`|zQqpkEp~u!u>*XI9pGE+0N-K<_!c|Bx7Y!`#SZW-c7SiO z1AL1e;9Kkf-(m;&7CXSV*a5!94)Cqi6-si=82Ag?R^TsaTft9*{=bzic7SiO1AL1e z;9Kkf-wGe_Uqk=T-4;8*x7Y!`rPWlY`2SY6*a5y3{w_AP4nKnJ|6AE&2l!U#|F_)= z{eSvf>;T_l2Y40Us_<5Yw<$v%bf19ep@4&ZF_TDW7&D3zX5I2@3!f8+w{9_`rS7DZkv9$&8d3ZoT|62GmZVW zG0>;#ZPP2a>6P2`%58e(HobD2Ub#)L+@@D<(<`^>mD}{nZF=RlMn;uKBct){em|$` zZ3jECeX8EJ&NMdqKLocmdiqJ9s<*At)9Bu}tx?h#gNae2r2Z-`5?9h9qgNibIaO~P z1=vObwo!m>6kr<#*hT@iQGjg}U>gP4Mgg`_fNd0DJKXD1ajM>S`2S-6f8dkge+2h~ zPq{oARgF)BUsic)__T&kYxuN=Piy$JhEHqww1!V>__T&kYxuN=Piy$JhEHqww1!V> z__T&kYxuN=Piy$JhEHpXTh6N_UMZ^K(;7al;nNyEt>M!eKCR)?8a}Pz(;7al;nNyE zt>M!eKCR)?8a}NB_Gt~D*6?W!pVshc4WHKVX$_y&@M%qvkIIHmYxuN=Piy$JhEHqw zw1!V>__T&kYxuN=Piy$JhEHqww1!V>__T&kYxuN=Piy$Jrc;zvW}TvJv`=fHeOgnb zB;N384WHH&DXpb++nL&19iP_mX&s-|@u}_zgw_e==KCR=^ zIzFxA(>gw_e==KCR=^IzFxA(>gw_e==KCR=^IzFxA(>gw_e==KCR=^IzFxA(>gw_e==KCR=^IzFxA(>gw_e==KCR=^IzFxA z(>gw_e==KCR=^IzFxA(>gw_e==KCR=^IzFxA(>gw_e?W zeX5Je^#6uJ{nwIEGZEo0fSQTO)=WgGnTSv`5us)xLd`^knu!Si-nM5VLjC`pE@M?Y z5lYX6(mYKjo5%2}x za0ry1D_wdnRNoh>?+f(}U8t|;LVY(E>N~hlrvwP~?OS-$=yoF185F`s@Xes~Tq)GW z?L_ttPZ1@5TAzlG{mPNJ`M3{=)SMt z+NYuWzR*4m-S>s|X^2lld>Z1@5TAzlG{mPNJ`M3{h)+X&8sgIspN8)HLFm3Ov`<5P z8sgK?eP1c|X^2lld>Z1@5TAzlG{mPNJ`M3{h)+X&8sgIspN9A}#HS%X4e@E{z8{46 zG<4sWZJ&nj`$GFPbl(@+ry)KK@o9)pLwp*#@9VGjX^2lld>Z1@5TAzlG{mPNKK(KI zbY0ghY91Q=m`ZEZ*XrP&l)gy`^-W4>mhO>f&kMDxBh*TZP^&sZt?CH1sw32@j!>&Q z!Y)v&Ib|%!SPH>M`5`}yPz?<&x)swyx#Oda(0p1$mtpVN|;H?4P8sMz~-Wt3D zqvy?AgI8dL=B)wV8sM$LD=>j?8`1mWtpVN|;H?4P8sM$LD=>P-yfwgE1H3iBTZ7uI z)6H80yfwgE1H3iBTLZi`z*_^nHNaZ~yfwgEgI8dJ26$_Lw+47?@CuC5&07P!HNaZ~ zy!jrJ^FbrLHNsmXyfwmGBfK@jTO+(R!doM}HNsmXyfwmGBfK@jTO+(R!doM}HNsmX zyfwmGBfK@jTO+(R!doM}HNsmXyfwmGBfK@jTO+(R!doM}HNsmXyfwmGBfK@jTO+(R z!doM}HNsmXyfwmGBfK@jTO+(R!doM}HNsmXyfwnxo4pbe+{*}lFC+N9J~2QkzXf{4 zx!3bh;rr#^dp#Q!egymr@N3{WH~~(AhruJ@*TE_9D0mFagVW$i@D%tB@HBV^JP&>g zTmb(H{A=(P@Kx|N@NdA2;2L-d)ZAa?*Bn-OgBtxU_#N=O#^7K3ufb1&KMnp22s1u0 zK!1f3B9?oJSnl$$V=0Z?lWvbB3n_!}VQ3Ez+X+o0AQ^jCZo;v>(Um16C>H+%%tnuF|*gD!0o-fzPD zO?bZv?>D9F{U*HMg!h~9eiPnr@>+!cYVSAsya=Ja-{kWmg!X=u&x;V+`%PZ25Ze1q zUat_^`%PZ25Ze1qUat_^`%PZ25Ze1qJ}*LO?>G6p2%){-&457W>&457W>FK7CZ87(G==tlQ)uruX?LH|-f!}G5kh;v3GX-I{U*HMg!h~9ev?;D z^o+gVg!h}gaw6N_Z}Q5C(B5yt`%QSi3GX-I{U*HM6x#buc)!UjCqV}9XYhUo?`QCS z2JdI^eg^Mn@O}pGXYhUo?`QCS2JdI^eg^Mn@O}pGXYhUo?`QCS2JdI^eg^Mn@O}pG zXYhUo?`QCS2JdI^eg^Mn@O}pGXYhUo?`QCS2JdI^eg^Mn@O}pGXYhUo?`QCS2JdI^ zeg^Mn@O}pGXYhUo?`QCS2JdI^eg^Mn@O}pGXYhUo?`QCS2JdI^eg^Mn@O}pGXYhUo z?`QCS2JdI^eg^Mn@O}pGXYhUo?`QCS2JdI^eg^Mn@O}pGXYhUo?`QCS2JhdeaZ~?C zozfZXLhaKQYL|{sds>8Ux7>3iv^w3FvO3+D(i!YRopCMvEuMT3)EU=G(W%Ztoxv{r z5UA6eWq%l3r#H)P#nu_@vbC>LX#Kn|WsSPeEAT?M)%&yp@3QF(cA?H-7j}W&U=P>} z_VIi_H~!T3v~v&a01jB?6P$RyHIDa3v~v&a0)yM>I`AM^)EVrubq2doXRr$kpw3{Ituxq#bCg79u*=pN?7|}Ux3EjtI)h#5 zWuDX-?6McJ{~CJA?y8SJv} zI`ho1{T4p#ycCb=x9aJ78*{Py z)Zd-*g#W5IO}6^J{;Furw$5M|>I`_VNvF4P(9LY=`b)EVr; z-vs}I>n;s($_KD@2D|Lv!PXh$U!hKR9+dt&+6EL|C{3Q4(@IQf{2LCg^(i!Z*TQzbSb&^}~R;jU3 zCmpHvSktm-S{6;qqG?$)jeD~6SC7J3G%bs!Wzn=OnwCY=vKj%~^^Dt07EQ~dX<0Na ztI^Qu*0ij~MBCQ1Y|5IJMbolqS{6;qqG?$)EsLgQ(X=d@mPOODntk{^*0ii77Kw5;!yP>MAzi>75YSMoE~v@DvI)!1#@nwHfFZrhrc z)i~}HYg$&LxovA&R%5ztYg$$#yKQS)7EQ~dX<0NatC8L5*0d~|mPOODXc~8xDczdJ z&1FJs8uyn8t!Y{Pe~L77Kv@DvIMbolqTGn5g^`tc|i>77Kv@DvIMbolq8uzT} z8QLeBmPOODfi*3Qre)EzY}%TZO8oFmVoX<0=(wykMdG%bs!Wfl22-I|s~)3RtBVST7ER+e zI;C6FvS?aX5tMDmCs{O&`{`s`)3~KhXidwaX<0Nai>75mYg#t6re*d2EJkZuHngT? zLu*<#w5DZ!V{&jmnsz^$c0ZbSKbjVyX%U(hp=lAC7NKboaax3?MQB=trbTF4gr-Gk zT7;%WXj+7(MQB=trbTF4gr-GkT7;%WXj+7(MQB=trbTF4gr-GkT7;%WXj+7(MQB=t zrbTF4gr-HT;znp%#42utrbVpcMrc}urbTF4gr-GkT7;%WXj+7(MQB=trbTF4gr-Gk zT7;%WXj+7(MQB=trbTF4gr-GkT7;%WXj+7(MQB=trbTF4gr-GkT7;%WXj+7(MQB=t zrbTF4gr-GkT7;%WXj+7(MQB=trbTF4gr-GkT7;%WXj(*^7NKboaax3?MZ{?lniipH z5tR(;_r2LenBN zEke^GG%Z5YA~Y>R)7~!aS_|GT)iU0vHI}zaC5)Y*{`*^YH>m&qmfZ{LzrSVczrTh0 z@9*I4YAr%}T|D_)6 zpqx7>=MKubgL3YmoI9jue#Yh8AvH6)oI9ipMwfF3<=jCzcTmn9lye8=+(9{aP|h7{ zZ+c!W&FFIOP#ZJ4oI5Dz4z(!TF6R!)xr1`yC~-_%DIbj?xLK#DCaK9 zxr=h{qMW-Z=Pt^*i*oLwoVzIJF3P!!a=x2#zMFFT_Qv(VH!~XDK7BKz(SG;Mj7Iz2 zcQP97ci+hrf|-=b)A`}8e}M*H2jC>q^9 zeb3;U(EZ5w3_8W-^c{jmm(zC$8eLA`A!u|teS4tM<@9ZULdxm;{`5A=>HGeaPC0$w zpKX`Z_x%}NPT%)ubUA(BpV8&?eSb!mvsvZTnHnmm(W^<#D(!J$mcRPjceA1tqrY@F zD?V8hdS$gaIAz$-5R45 z-5Mj*tuewrp6my8Ym8C`LERc7dl(!6y~^FpI%hNMoXxCrHnYyz%sOW?>zvK3b2hWi z*~~g;GwYnqtaCQA&e_a5XEW=Z&8%}av(DMfI%l&Y5a(V1XTVudx5g;lYv9fDqiwH* zH_My0y&m4I*u%f|s(7%`~{|@{PcoY0C=x?dbiam@!2L2>?59l`Btk}bUbxUqm>|xt0 z?ahikYSRj|d(ux8uLnr*Y<3jdXM zrMN=2+P~VT+Q0E(QgmyKY{&V{iX8lmSICXjY$cy4PKs)w68>3bwxu zH7jy3J^=dbK(itT<8OfUDMb!0`TI%v0QPTV{|@%=Vt){u{-wylZ=ioEayuS?B}9Bjj(A_v=_0QZ5qHAX3)0(EPQ>`x1S zO*0^!uAcI4BHs{tTcs%fZd^-J8Pa3T`yQMj{?S9Cgx&P$!KDb<&7XCyfYo(umOOIlGzr>}Kw>o4LZB3jd7jZpBeHeUh)^eu2p6!+)JP|dD8(x|yQMs~m#|;K_DarfDUZ`%1OEoR2(E!T zX+(e3Nh3m?G$Qos^lmAS@!OzI8jD`+37`-~ZTeBXcZes~{OL>gCjYX)FMuhkH zubTDfoy>Z6OL=TJlK#`!Z^r%^?0fl@P8!iO?)AH+JVxEdBGhdx!gqo?X+*Y88WH{~ z=$^P+a~z}lqi=W=SJEQqNPAcVO$J z5!pIvMEFi@oirj_CyfYo(uhzejRWE&2pMYey)p-vi+y${rFEV6adh)}n&2z47v@E)}2J!p|{(mbvdYteg9nD?MX z??H>+gBJM)!{fmNXwd^`(E~i`Tk~`(Fx ztwp{y&uC73Yo2X$;#>1ao^99Kcjq}rYmx8HGg^y$cb?H&~qTFKdzS&NEtze0QGFTI9R)jMgIGooBQb`R+WUwa9np8LdUWJI`n> z^4)nxYmx8Hb1kezzB|uoE%M!YF0-}Bcjwu*7WwWx+twoAo#)b8i+p#UZEKP5&a-VT z^4)p1twp{&&uA_3-FZf9k?+nkT8n&lp3z$5yYr0JBHx{7v=;g9JfpS9cjp`zwaB;W*|rw>Ha*+c zBHyNG+gjw?^lV#;e4CzaYmsl$Gg^y$o1W2HdPZxJZ_`^Bz8&=J>Ag}9qvtZdP0#4LjBnF3dM@MJ^o*X%_%=PG zX9vDb&*&L}Z__h6w)bs%M#uBMP0#39{k>|RM#tyxC6@MWda{WyeVd+bN0q)!&**s4 zx9J%jL;5y7qvJ;3re}1l=-c$x1Ma;Nx^~=qC3Nk6o!W8lm2B6Jd#{A99rs=dT|4f* z61sNWdnI)3xc5rv+Hvod(6!^!2d#K$We7A?%?ZJ0@sNEiXw+G+t!FPM8-5z|mhuZDIcYCPa9(=cl z+U>!2d#K$We7A?%wP+7;d(e{7$t^<1+byc8Q8$kWJ<_$PzDAwgBGkz(LY>?q)X6PE zk3=nuL@h+cEsR7hj6^MrL@kU&E!vIg=dJTCD0~ar-h!&Ppwcbqa|_Dcf+n}1x-IB! zi`dX_#fH(lTv~!GsFPb{>*N-pPHque8(Xwj)9E_7MW~Zof|j&SZV~<~|0?|xpnG%+ zs?vg)lpc^gX)6ZKgT2P4=^q~c1XbGS4`@?onC%4G{vU1_xG~th{ z<@}~{H~xh1-?NAFLE@7KiBBF>ys;KMD7McFy>s|Mv2A=W>E3buVCvVw4pKV7F0dQy z0eit5PtIc(!IDwz>HT8Q=pEM&iajHFu>><5{U%iN31-*0lL9r?nt47c4 z9wd%>P~(nr(fDHgdC)tqAJk}Kd@FcA_%`qz;4gvi1m6YzGWe9=FIJ6DgWfs(5Uuwi zTJJ-_K0WzRupev}=MM!3#Q#IV)1*A3vON?WbPC>o2=70X{)kfA;J*$2+k%Jmd|TjF z(H1-bdgj{}Jc<3EvD=k;f&|Q*wSHFEU*sI?fp8!3k@6{WevLE|t z@vv7Oarz&soO|UFr~DE4S(S5d@W^|^|JozlY zvUm0d){VWvSHR~;`6_llPY#eW2o8hK^VbpV7mR7|jM|&_&Zxb7aoda6_Tsg@@|sGO zc3kuXzIXy(Jb^Esz!y*8izo2K6Zql@eDMUncmiKMfiIrG7oX5?*Mm>!w??<#eRyXd z-r0wD_Tim&Z_B|4sNLwR@7D%*>aw4@?58gKsmp%qvY)!_r!M=c%YN$eluyVEp7IHq z!Bfg*MEDr^1Zc*dQZ7!n@;s&Y2z}P2@J+&Y+IBl_yPdWzEmRv;uL9k++r`6qq1$%5 z*s$%k-A>zXr){^>w%cjj?Sb2NJ8io?aNBMV+_u|k+wHXNc4>~^;I`dP+inlsw%Y@@ z?e@TJyFGB*Zl`Ux)3)0Kx9#@8ZM!{i+inlsw%Y@@?e@TJyFGB*ZV%kH+XJ`lcG`A3 zZM&Ve-A>zXr){^>w%cjj2Vmm>JRA@Y-N6CzV6^HUpgkNA54Nqk2WUSBP~8Kl?g3Qy z0IGXHJe=1vR^0>QVMOTOeLxHx7g}`>hykNj_kb8MT6GUl_XDcCZL979)!l!!>K;(7 zZCiB@sMbcS?g7=>wpI54bv!^F51_hFt9B#7)2f}2Hu*Gd@@d-S(`u9FmF|)2Y1-t| zYLmxhA0YiRYD-V6HToI%tf%#Uy+`jienjb?fuGO7%x7TcGxV&_(6gR_+h^eR8RdRF zct*J!p8%}}&nS1NSQDP1{LfJSKTt{5f5LHu2ei=f#o`-+f+r$yQ#+gHHARk)Ts-tO-8{ z{weq@_~+o4!LNY-4g4zjyfK~j8`QsyKO*#sc6h76!h=GhgDFFY(Nmc;-ty^Ch17igH;GzM@=&dcW~a!msk%ukzck z^4qWS+pqH5uku^pymLP2mrvJ(KV=)<`r)l#?OExt*AILBu-6ZJ{jk?BZ|WI&)A%Ex z*R^~P&iP!Kj`Q2BYG0G?)aB z=nbQRcg~LnGuYq6_UhkgaFvv6px5F?gPY(RM!jEe)BBB|20!cHrazBur5#NVfiHlE z!LR$x=_%fDlIKrhdzErDeH!~OvCm-7@cbt!(of6(7o<~D#^=R0DeXny5e^yWWMu2Xi|Bu7>0>}<>P7lWQ{8-@s zUlstt4r9ILGRHWlh>TfHSjtqH+bi_dFF4yzXQJm-sH*eV&4L9^ZXs`zZVZ< z!S{I2Iw}8v{g0Gq1KcG2F8Bs-`xopjqgu7fLkuuR4B*=k#GYEU@l$?V`akmIe{#NQ zkMCpYc2W-TSI^ML($A3cU%)>E9m9{Mt(;@&KjBIDvaz)1+GA(0GTzf3- z{oZ3~M`B~?K5WN4W9dHwt!!iIKPTN$%~;xz%vgF1e38HY1&GJfUYQ?LOLpy!VdMSu z3GA16@@3xkKd}9uEMw`DZVBmA{OUA#1}yLlEhK%8H_U@Y(ChGHY47eHOM4xDEM3O_ zYkoyrN-vZCDqMNheJoA;NngaK&7{4Tdn`>mN&Ej(#?s#gZ}FZx;P>qDG`>#%BftG$ zr2i97{xkLl_9pfZu&oJW=?Zo6dd^td>p5fT#BT^wphv5*@JIb*=rL$4{NMfC(Cb=b zq1SoF!Z(5U@TAAbvCvV|SlH-#g>T08?uD`N|KQ1=buQu0VQ2X3Tl8d(zL}#B=IDbt z^}aQwTgP%~x3nBBCr3NU(L!>xja=HTBA0f1$ffPaT-qMY$uCB0PA>f|Z~?UPLla-nPSA}KGD;`8T^2R?sZh)R#6(&K?udK{G=N2SLD ztKWEFl^#c>$JO8cjB7WJN{Cd+Dm|{&=x40b z<7zENtMqu5 z;BW#CC*W`b4kzGn0uCqOZ~_h|;BW#CC*aU${_AaUI01(fa5w>n6L2^IhZAr(0f!TC zI01(fa5w>n6L2`eNH+n86L2^IhZAr(0f!TCI01(fa5w>n6L2^IhZAr(0f!TCI01(f za5w>n6L2^IhZAr(0f!TCI01(fa5w>nzSrP*;Cl^(a5xEvlW;f*hm&wP35Sz#I0=W7 za5xEvlW;f*hm&yV`w{d`IGlvTNjRK@!$~-tgu_WVoP@(kIGlvTNjRK@!$~-tgu_WV zoP@(kIGlvTNjRK@!$~-tgu_WVoP@(kIGlvTNjRK@!$~-tgu_WVoP@(kIGlvTNjRK@ z!$~-tgu}z=&tdfEF#2;C{W&bg)`G+Ea~KsmEFP4C79B>54x>ef(W1j>(P6acFj{mN zEjp~)`Bzq?!>XOpx^!5&G$QmEaac8VihJB))afwlbQpCyta>@!8g&?rI*djgMv)Gq zNQcp=!(o$R;3LF8M~HlmsCG&r@;O4}bA-s}NMNlvqFVc}-fMS6wLUNWE9_-?|48tv zay+7V#`f#jSHSC_73_%O4deGy`-K01{g1q1gJ1o?=|mAnh$4mQ~rd%c42p8_h9#8dro~s@qpj(MQqPdjwljv$}o8y0be5hWzzo#_B6J=a0LF3 zFfJU?NUd7S3r;U%dvrdMew9+$BS#pEk1!S=VJtqPvDoSVi#Puh_CI59U~gjo0NY+W z!svNKqo-|;o<}r#+V+TfL?fmckOx&4jg?OSInblzk?<}0t8XM}7kd1iQcoWdI;xpc zA9srNe2P9kr9STTtEAXRQ}k}%KcXkquZ^E}I{kWzemzCMo>ISd`U~J;@aujX{d!9M z+Q0SqGNpdqE&NMxhG!@PeR+!3K1E-ig6%0<`xLExiheysYoAI}!t{4|r^k^g+WD0F zuX0iURgSdtDfM659+9WifAu8&*SDyw1-?Z^s2091bT9KwC`OOwN7d4lPX9ehe>_T0 zJW3lliuaGw2an3ve)0-<4Rr52rapCC==FhP%x90OJ=^}go;fD=jNbtN(x{T_S1R*b zkf%T9nUCb@m3cHLPp{0=EA#ZqJiRiH7Uj{ReBk*=Uj98U^n4^AIEKtKAIYnSw#)W> zBpHoqzJs-)Z{}}w7OUryDpZ-&9&qwlTd!G479)-^{AIYQhdFCT|)IQIAB#-9j znUCbto{!|2kK~z;riXk$n0%>7I||89VZ6&qwl%Ao;ZC zBYEZ{dG$X3%JY%DMpC2aBYBOawml!otH&9w19|#gUMlA|c&y1w#6L|0hzB_?Noj^HH!0icGJprF5h!akrpC^bDP7o)YpcW^7SPK|9L7eas zn)VW!_7a-*5}NiBn)VW!_7a-*l5~DOcnM8=2~C@ZjcM4JhK*_1n1+pM*qDZmY1o*C zjcM4JhK*_1n1+pM*qDZmY1o*CjcM4JhK*_1n1+pM*qDZmY1o*CjcM4JhK*_1n1+pM z*qDZmY1o*CjcM4JhKfOfgg133*F6f!y zX=3lwMBS%h_;l#;_jKsd_B1WzG%e(`dY@Ao{acOK#tbQMk$r}*a%cD|cSbyS2WQ0X zi10YJxjiFRo$m6V(Rk;-T9M9(Hz8l>&hUlqjCga()1bfapMj+_@NkA&pOMPxZBjWu z>9OyO>TA3Py1r+q%Ngo&Ms4P}Qalejqq^v~s*9diEo{F<_E~ztS$e@)dcj$G!CBh> zS=#?uTK-vD{#jc7Sz7*CTK-vD{#jc7Sz7*C+Wc8s`&r_Xv&1K7Y3FBY=Vxi>XKCkW zY2jyS;b&>#XKCSQY2jyS;RPa)0ue}o2&6#C3q&9VG2b2(#QccR^MV33Do~>W5lDdu zq(B5xAOa~6ffR^93Pd1b|2&9m91X5r{v_NYq5P=kEGX)}$0xhRN1X7^=6o^0y zw4wqLNP!5XKm<}C0x1xI6w;1B3Pd0UB9H(9f1^xKnm)!@+J{Tfe55P1X3UZDG-4ah(HQNAO-qMfe55PuPG3L6zDqzB9HwD}p@{0#H= z8MSsjLkpi#3)hos$xitbzd^0nb~m=??=xz>PWSwMMy=Pj=kGIWw?@z3XPCdwq&SMjM|3n#E7qFn7_~9>lxG|%rYjduF-t@-%UC&^{_muJ9dtx7tBAt*m!Knx zSw$2^M-j8)+2|-@miS>-3_Hc~!z}T`Y})g|+4NoTUwF?JxNT&#on^G0C32W0a+oD@ zm?d(URpg*I5IM|>$@O54k!y|-YECVGO(|Y^m?PGjW8|Gfjpv9w=g`=SlbNgvSHlPAF7c>K6JNaWQa= zT4dF?sCHu8tNKN?6aUpKLPd?OM)&=qMo**XUqx1Zi>&$VF?aPa9D!F5*+&eKD`qTOK@0%!x9{p z;IIUTB{(d>VF?aPa9D!F5*(H^&aUZg=CA~ZB{(d>VF?aPa9D!F5*(J`ump!CI4r?o z2@XqeSc1b69G2j)1cxO!EWu$34oh%Yg2NIVmf&y!O~Fk@Ok_ZHB- zGHjP&yA0c9*e=6%8Me!?U54#4Y?ooX4BKVcF2i;iw#%?xhV3$JmtngM+hy1;!*&_A z%dlOB?J{haVY>|5W!Nsmb{V$Iuw91jGHjP&yA0c9*e=6%8Me!?U54#4Y?ooX4BKVc zF2i;iw#%?xhV3$JmtngM+hy1;!*&_A%dlOB?J{haVY>|5W!Nsm_M-G*Jy?`J2-UBR z-chy`{JqwNUXd?GgbniMEAohJ@pfM5(eM?qXZv+*uOz>sh|Bmr@E^bpKf^wvSJ+4N z3j2s&5!-s3*fxI3Pl|0n`6t-jU@zDQdSC7M>93OhD(Nf4nJYw?D@2$pM3^fm^0t)xq0dnH{4Jvyuq#jOy(tq{4b z5VNhIV=F{!E5vClL}e>PWv}7E3zYc+Wxha}FHq(Sl=%W>zCf8TQ05Di`2uCWK$$O4 z<_nbh0%g8HnJ-Z03zYc+Wxha}FQCR3DDwr%e1S4wpv)I2^99O$fihp9%oiy0>oEU1 z%)icD`*n>(>%r?9iHtYI#_KA%?VI2mMtt--K6;%w;OiP?oPG-Qy7B88N1SpFoCm!! z{JKi(bg%BduCc?m|4Zd{jTgqm$ZY6!W<#%Qq;N_D__M;xl=(7czD$`fQ|8N*`7&j` zOqnlJ=F1vG^()GJnKECd%$F(iWy*Xx?J{4c%$F(iW%2A^xy+X-^JU6>nKECd%$F(i zWy*Y+GGC_5mnrjQ%6wTP+In!6etngGeU*NFm41DdetngGeU*NFRc%JktIZhQudk}L z7~QY0(yy=5udmXtuhOrt(yy=5udmXtuhOrts$J=~YF9@0>#J&4M)&Kh^y{nAL%-Sm z`YQeUD*gH@{rW2X`YQeUsx(bc(yy=5udhne&Ii{RL9Q`^TvNT)f@`Xg(X*aw==?Qw z{+i0>6we>8>21ch2(RPQ>-h9KKD~}lujA9}`1CqHy^c?>-h9KKD~}lujA9}`1CqHy^c?>E9v!JEY%K zdUtSB=|VhmQyv+SeN7&}iAQd#rpIO9B>fGi>kWEdZ!qo`8#mKleY(l&(@oZtZsMt% z@|4~tPZ>}1+cThh;!SzY>F4}@@nEz{--L&oc<`p!aJrS`rq*YS72e?g3co2o8WTT* zA8+EvoARUHEI%55R(Ok=-lC?rsOc?gdW)LgqNcZ~=`Ct{OKtCbaEqGWqNcZ~=`Ct{ zi<;h|rnji+Eoyp;n%<(Ow-j&t4X)`eYI=*B-lC?rsOc?gdW)LgqNcZ~=`Ct{i<;h2 zi}ib4(_7T^7B#&^O>a@tTh#OxHRYDffLk(y+tl>7YPv4lYJZ!W-d0U*TkUVt%eYT7 z;66>Ezd7Efm))k9-KG||>1DT73;l{-cAJvlrkCBO1DU+Ww$BwZOVL` zUUr*acAH*yhxU1g_IZag-=WNRDDxf4e1|gMq0DzE^Br399a{1o%6x}1-=WNRDDxf4 ze1|gMq0DzE^Bu~3hce%x%y%gB9m;%%GT))hcPR56%6x}1-=WOkqs-r<%-^FV-=ieo zC;j`Rf1mX4|1e!|SPQ?Hgj1=pP6zhx>>x>lZj1=pP6dDi3^ExBNdf<^_osnXl zkz$>ZVx5sZVx5sZVx5sZVx5sZ zVx5sZVx5sZVx5s?=xZBze1pEWL0{XTuWiuRHt1^` zcz=Vwwt@FI=xZDFwGH~(27PUVzP3Rd*q{w;(APHTYa8^nO=`MHO*g6OCNv3+HQl79o78lZnr>3lO=`MHO*g6OCNGV%DZZ}Yr$Q{%DZZ}w!L0-m$C9LW941O%Daq}cNr`1GFIMYth~!ud6%*BE@S0g z)lqLy9gQ9%?o!9Qs-11`r@G5nd6%*BE@S0g)l2D&m3J8{?=n{2WvqOIc;*e_nKy`M z-XNZNgLvi*;+Z#yXWk&5d4qW74dR(Mh-WH#Lw8W&yI4ihntMFZ{!gsL>-^D5_iQnU$ITcz|h3{gOz~99xd>5+(UgN5$w0_b% zb1H$qaa6>-e{~7lJ98@Xf>XRRr=m7#^v;|LEwd7MXHG@lG5Wh$CGgIiirT85^v;|L z-^D6{S7IxC7pnx`nNyKB{T_c8tH`Iey)&mG_Ke<{Q{lTSDts5K@LjAz53TTB ztdjQ5oC@E?D(bVUFWv1D{9-e{htCA^>P2oJ98@P<3>jg z74>o3-kDQT`!{-LPKEX4iu!`z;GH=Y^$6RZ%T)L-R?$j`)BRnn!gsL>-^D8GHBP6^ z@O7i2wGsc;|0z&WZ!$XKs_xz1upZsT@^v;|LE7%qFKHFXy zu1IZMe(%hwNNtSXnN#7rScUIm6_lrf@>KX%Qc<7P8~9dIQO~vQh^~SnRrqdFQBPF8 z_%2pqJ-njc?I*o6r=mV?+dFeA>aE?u7Gv%fW9}AX?iOS27Gv%fWA2uE(0Z`Nn7gH( zV%xK`Ewyl?XJ=cCxm%36Ta39|jJaEkxm%36Ta39|jJaEkxm%36Ta39|YEgO{W9}AX z?iOS27Gv%fW9}AX?iOS27Gv%fW9}AX?iOS27Gv%fV{Vn&RjF5%ld`Hhx#Dg~$0ntC_*E8uU+JKT{id=UG6;QRUO{|$Z!{5{e?jQtVpR_uqs-v_-cQ|k-xX>dPcY+JOe}+53h5o`)O}Xt=Q#U}**{dl>>{Xq_ zV)RL&)s&<6s?NwVdUd55{3z)EXRHQ433^?H8^(oRUE!W_VI%fWJ1cTfF%}(rH%#?TVgKrKeOmDYUASN%SjD z3axUM4mX}FF>gRH?~g-t%kpX-3;yq9{~R^@ZW*I0n(>93y6Ez z_1h0ni{Iw2zk~g|*dN5Ee}(j~kp30Yze4&KCxuqShk5e%`PE0UAHih}WO`3`!o@-}hNHcF!V&7Dp}q+8Chy?Z%E zb7C|n=E)e%iP4-G&56;RSZ5Zk>v{7Nr`$GTG$&5EZNxgA&wsV%#3^$Ur_4#5GAD7$ zoWv<}5~r*=amtz#r>r?KniHcramtz#r>r?KniF#>RE*}tDQiy5sZg;_L$Ynni8&Q2 zPFZteG$%%L;*>QfPFZu}lr<+#S#x5Y%V)Ia#GFnXqd9TPniHq2IdSSFXw8XJ-vF&S zamwE@V>Bm5bK;aWCq{GPlr<+tbK;aWCr(*&;*>QfMswnnH78D4bK;aWCr(*&Vl*dC zS##o)H7DkD;uy_|buORNtvPXO4YcOODSva1(VQ5~iP4-mWzC7voEXiC(VQ5~iP4-G z&56;RnA3@4G$#(MIdR~<>oJ-W2S0^v&4~kRPK@Tn!Ovh@b7C|n4y-vbrxVAVP8@SO zaU584;=q~{>s&sgH75?NIWd|Oqd9S4&4~lr6`B*HIWd|Oqd75}6QemXniK03K9vg1 ziP4-G&56;R7|n^%oEXiCLu*cq=EP`D99nbY(3%s6)|?p4iP4-mwC2R2H77=MVl*d4 zbK=mN6NlEEIJD-(XigkjbK=mN6NlEESf}tAtvRty;WN^w(407YKPlFnIJD-(p*1HC ztvN9#lEoqY3(bkqoEXiC(VQ5~iP4;x(~0BIniGfCoS5^<;?SBCht`}pwC2R2H7DkD z;+WHkW1Yh16l+ebQ}~S5oLHyu89yzop*b})rzRyit`z@&L=7dWp*b})r-tU#PQsH3nvPJ-qnXikFWBxp{8<|JrN zg61S>PJ-qnXikFWBxp{8<|JrNg61S>P7+vi5;P}4a}qQsAZ9XJ1F&*tyod`oAnXlZ-Ebj?*paJO4ljG z!ViJJNBW1cKZ4zg{Sf*7KK94>l};hnuXGBrunW{F#IpZ?lHNbOsPd4yWKC42#V5j@RZoB_4|P`_%esZd`b7LIX@)|koGJFP-} zg;=OL4dHjW+V5eX!`4@bRel~@?;pw5vq+&<<_q=ykx;A0g_`9MYL-K&IWeJD>jLM+r*h=uwJv9K1b1M9(0f$IJB>q<~LfNXt*Scu*f zi|kipc_DgJEYg{!XB{IY8$aXoC>GiNtdCbL((#H#w)GX_Af{NPU;Pzgp}s;a{2;cz zLM;13*!l{wY<-1Tcqb+L3bE{uU{_)5E5s_%SBQll!`4@bWq%yI7W)&}b=aT8uE)L$ z`)+U8-tR*AksEYw$sgScanP-8Bk@*kn{ zAE6^m+_6ZguSf|s<`Oy<1+h;Xat(E&ECQew8x};{7mq1T^Ob ziqghsKz+wU_HpoQ;Mc)t!Eb%>J|`n z3y8V}inltOBCW9mybW}8Eg-rUD7xC#cQu9D4Oyt2LxqmC1w`5cB5i?kJeN4q7WjMb z!n-+gnQK8`pf_qCWFbmWq!sguvG$Gz;@aa<_TPf{f&U%+CysnjIxo-{@QmG*=qrV? zQTve47>xrYgB(I9_T>|)Pv|4^&q+`^&L77eMdpC z1$#Tc?f@UoU)8TWDR;(F5I9#U&`h}TpTUzLD%CR!m+SeLP+u_;{@nNCClo?QvjRV- z5V{91(44uCcduO#ILZ}h{@f*c4kf%{^fLvaR=EiEu8q*WVS%0_7#C6UUhF>x^^Ts( zZ>L`!28 z=T@EVli2mxcVXYnRV@ScRc#%kFMbPGfvdqa;977U_*WotNj;s9*H<@%&H)OPV;eVs z8$oK5UaTPDUaWv#tia#Wm+fAxfL^SCUaTO|ZdD{Yz#X7=Usdnrh#C@6Ln3Mzb3_ee zj;J9KH6)^jMAR_m))Z<~J|=XA91>C03sUZg8WK@MB5FuP4T-2B5j7;DhRTiY*AX=& zqK3+iZ9Afd8gbi;BWkD-x6u(b)QH>Yh#C@6Lyfq7Z1UYN%(Fx&}R?G&-V&MAT5@3*7|~H6)^jMAT4o9WHl74K>$c z+YvR?_`)TQsG-IewjEJJ&2`vzL=82*u$c+YvR?$inD|8fs?4NL(VKhD6kmh#C@6Ln3OZ(SeV2L=B0k zArUnsqJ~7&kcb)*Q9~kXNJI^ZsA0kpHT2%EL1E0}tiqT_RfRE+l?pZ6VAM_!Ld_Bj z|3tnDW4@QdnD3=fa{@l*U%)ScTFIc2$H4<&KRCb{4uXfkuYgZ-p6_zZIq*EF)df1w z8{n_Ni{K@r#>Gahz!WY57lZB>3YFCxKkD{*iUBq2S zh2Bd-=oyv5`2DKELVa`CsBhE@xAW@`e(l2kM{p14Im9tf^6OD-&ruX=HI7l=K@w`M zh45SX4MIoeLX9l^>m=v-!+pJt{SNr9F^GZgTMIRs*73pT?NMu2Y(M0)1>M-YI3@+| zrlbe#1^dAL;4ypGD8^@a9y|r=8%iqiOiQ8Oh_Od~LrM4&2ydgn#Qc=d(QS$Cn=U??+#@3Qh{!!6a*v4IBO>>R z$UP!*kBHnOBKL^MJtA_Ch}gxn({_lU?n zB65$2+#@3Qh{!!6a*v4IBO>>R$UP!*kBHnOBKL^MJtA_Ch}>R$UP!*kBHnOBKL^MJtA_Ch}>R$UP!*kBHnOBKL^MJtA_Ch}>R$UP!* zkBHnOBKL^MJtA_Ch}>R$UP!*kBHnOBKL^M zJtA_Ch}>R$UP!*kBHnOBKL^MJtA_Ch}>R$UP!*kBHnOBKL^MJtA_Ch}>R$UP!*kBHnOBKL^MJtA_Ch}BVNj(MdG0r`bn)x?6_ehd^BsF_)+qp+F<~}+}?vW(-NRoRb z)a!$*-P8bJ(A=eNpg=Qxkr-RBT4R&B=<;?dnDt3 zxG(1(N$sCybnl!b_eg4|2HWmEljI&ra*rgrN0QtlsdsFBjB}4<;M^k_IQK{f&OMTW zbB|=;+#{(OR9zvtN0Qtlsnx13ckYoS_ehd^B*{IJ5 z;M^k_IQK{f&OMTWbB`psN0QtlskNg%gL98$z}=C1B*{IJE>oO>k6J(A=eNzLKA#JNY3+#^ZukxV%E zNG6eGU41KshMQ$bRs>B3%6^GRwfMyy^luF64R~$LhTn2 zv;=;B)S~(PvEW{n?-6R$Cb#=iyc1Mk<_?p5#Oa{Ikk8q>exf3I`itNy58_@J`Z zd%eGg@FDPF&^hP5^iB7wZ}KtP4@KAmYCja&+7CtOdcRkFlkp4S7s3CRU;h{Om$0=T zijFw|K0$du_JC3MrR&sv8MSUOXwzE*9YU?<75Zsun_`Gj``HPd=eH@67(I$sC2ZsQU>nc-+IZ5} z#xuS)#R~nZSYh;&yEerNqo3Bb5i8n=6>W+Gx+>y88*!kGr)+I;t!h@eRy7OXHPRm2 zg3$L8c&4$9=WA^|pK6mnb!O?)=%-O_(x=hSq1t!?)h2z~_EV=e>C@;ZO>NSr(W+}h zb#17w4b^?tZ)XIb70*I>H|l-!V7=5eEcA1w^-|Zk(C1mNtj4HSIznrEef$CJ4%Op& z)Vn_3NqHCLR`U9IuTizEv#FMi*7l~@J$gR1DfSugv$6YSuLu7I+yK5}j92)WcqRC0 zN^;=ujlo?m4?YEc4%}!=Jm6mw|BU@b;eGOWzwk4lJ>G}M`(pNZU(6owi`nCS@@T9C z?eRXXZ8X~Bee!7h6!Lyg ziiJ=s28GALVeka_Jim@$`R`ltZpMuwo)WTM3VQaA6$16i~ z`Gep?lMIt)(;V{>Hdo^BDyZD8X{&NMqrOof{0X+! z5Xznae+l|o`PSe~j+p~*QIZ97;O~w8u7WTGi$JXyREgFK3bk%WsFi`j_fvAaZ1(&T zTF-x{e0W^=Q}DVGPT0Lm_6|yZXw=z^w+pwa9*2dIQT3$~)s)dsFt@4yHJ+v97oelW zHr2SwRpZ8oz+GZ*oBC7ZF^+L9ZxgFN#!or7iCh1wFCYnBzuVMH8eicUe2GaP|9hkQ zyMEz&z$HGCXO!)_<~>2Xu36}Jf`p!zXpjF=XKweqJVL#tD|DXF?zhZ>c3rcM*EJj6 zceMLm7@=oJ+k?lzr$Em$w9~V<2QTp77r`_9>YlybZX1mo7;nTKu5^-M1g-z6oQ^rXs1taryqa7?@t8}C_6G*jSnaWL1G-M*ZNlxUkq)8z zwe3<-zwjvNd8F-J^LA;;+K`Pg>yvF%ctk1=oCr8L`SV7uC~ZS$~Q`Iv35vDq#K8qLOb ze@|OD1^%9Lv#~vq0E_I=Z~O`0gKbW>tDWi$Xmtn7?0}ga8mo>6J2Xl)PJq_!4s^Ri zBUYFD3B?X{yF;T_m;4sAhIhcy4p`cu(Wrh!$vYT_?$9{YC06wgRJ}uEQrmmMeV}!| zLnBk8b-qL6Q`_GFJ(IRWns>>Ipw+%ZjM@9QL92a--!~Ngl#*XzUjrR^c4%a3wB~mN z*8C1Mze9PfY>id*t468Dg=&vGq$T5fDe>&t4vkgEgHG7%guPC5)rqb;86$L}t4?&) ziLN?X`Ot~3I?+`pjCI0TC%WoXyy_1+(N!n9>O@za=&Dm+k&<6UFdt)Gb)u_Ibk&Kj zI?+`py6Qw%o#?6)U3H?XPIT3Yt~$|GC%WoHSDomp6J2#G*4dYJ)rqb;756%1TUVXv zs*|?XiLN@)RTs>3!Auvr>Oxmt=&Fl&*oCgT&{Y?@>Oxmt=&B1{brBo8V5tk1y3kb@ zy6Qq#UFfO{U3H~S6%3;i&)x)uDZ}wmw4;fzpSe+ zbk#)^?Lt>w=&DPzA3n2n)ukB^qjlAVuDZ}w7rN>~S6%3;3te@gt1fiag|51Ys9osl z@5S)d;P1ul)!-ko{}KB^vX=+xPamZBe2|RdL8;|x@SxOUbcXOC8N!45?|AT_{yQE# zr2lpZi;c>8#)QWewI0&Um2GDi579?IL?8W-W}@^jdC~FmV%+ZI>8T%5cA?{yUHF&_ zluv-aG%6Y!-TywM3_(ZIr$40Jz_xq#hoz9KLg&B_(@Q=qRoMO|=w9++slp|fz?()X z!RT!H;ovDBquR7R3c3e;Sas);Z-UmpFUuCVTAmSGi<= z3v~9_?XPkPojrD|7L3jwyQ%AL>bjfkv779%o9wY$5ku!e1Knt#J8-|;9XNaJR;)0( ze!I~|H`?eXd+b(}@UL76*<&}^V>j7jH`!x1*<-hA+2?e>(5*Q@qqE0uvd8Yg*<*L$ z?6KQl_j0u)rxf_3fYN5cA}7-C}bxJ@y?Qa0`Dv-RCaV#cvz8SmsHUq9L632U*K20&!}>* zu-z5^9=5*bD%&kD$?~xMLJR$noD-_>uzlK%eyq=3Bi|u*BT~eK|${EfsW}$aU zb-vnPf{wboln46Ej=j5-4cd0R+ND`3+m6G#=(Bb)|GbOXyNmhfT}0qr(w=-td-A0$ zQU4+i?;-;4k`Ddr?fUf*TKyxm`bUV6j}RdrAwoVv+kAw!`3SM`5u)NFM7&3cbtzPl zLKP`gkwO(IRFOgzDaD8WAf;UTs?e%Pp^6l$NXhT8O00?$sz{-V6sky}iWI6yp^6l$ zNTG@psz{-V6sky}iWI6yp^6l$NTG@psz{-V6skxCRz-?lHH9its3L_bQm7(@DpH!0 z^pRFY3RR>~MG94~MG94<)Z32fJXS>tRiscw3RR>~MG94< z=!;XRB84has3L_bQm7(@DpIH-g(_00B84has3L_bQm7(@DpIH-g(_00B84g*MHP>t zibqk!qp0FhRPiXPcobDUiYgvO6_28dM^VLY&aj&^?B)!+Im2$wu$wdN<_x3GmXkJjVwOv-kT) z*VaRi)}t$Qx#vTA=+S!U(R%37dg#%5=+S!U(Ru>+Xg&03J@jZj^k_ZwXg&03J@jZj z^k_X&k*-z@`20V?c8}IWkJdwv)!C;M zp-1bXN9z&8@^k{qO z(e~1#?WITCOOLjf9&Il@+Fp9Jz4T~%>CyJ8y~r;;+Fp9Jz4T~%>CyJmqwS?f+e?qO zmmX~|J=$J+v|bd_i$Z!)NG}TMMIpT?q!)$sqL5w`(u+cRQAjTe=|v&ED5MvK^rDbn z6w-@AdQnI(3h6~5y(pv?h4iA3UKG-cLV8h1FAC{JA-yQ17lrhqkX{thi$Z!)NG}TM zMIpT?q!)$sqL5w`(u+cR$$5HFNG}TMMIpT?q!)$sqL5w`(u+cRQAjTe=|v&ED5MvK z^rDbn6w-@AdQnI(3fYH3_Mwn{C}bZB*@r^*p^$wjWFHFIheGzDkbNj*9}3xrLiVAM zeJErf3fYH3_Mwn{C}bZB*@r^*p^$wjWFHFIheGzDkbNj*9}3xrLiV8$_J9u913KtK zA$=&M4~6uhkUkXBheG;LNFNI6Lm_=Aqz{Gkp^!cl(uYF&P)HvN=|drXD1@D+19qAg zZda@9Lm_=Aqz{Gkp^!cl(uYF&P)HvN=|drXD5MXC^r4VG6w-%6`cOz83h6^3eJG?4 zh4i72J`~c2Li$ih9}4M1A$=&M4~6uhkUkXBheG;LNFNI6Lm_=Aqz{Gkp^!cl(uYDG zqdh)Gdwh(T|Cl%#4;~}tKSry0j8^j)G5;}Q{$s@a$B6m+nYG)`tlj?jY5jLUGZp*E zANDhAx1U+N{p$Dit9pE+XYKZ@mp6LWZom3;qi5~*(~s|`AKy*Zow+X-GFQNxu@)yyAFY)V_`1Q-QkuTFmzKrs}jPkt` z_i*5yxP{W;xbP_Gx#GvADC1d5egS%B?{S?$4x@MPquK0lJ&gj{*1IoLM9upl<4Z7T;<^zF890wF7drJ|S)U*Pnvd zjot%Dm;|>|vIF$f)hB4(Ptbm!ptU}s)~d5f|Nid<&~Fqzp>}HY==BNO;1jgLCz!Q( zf?10v)CTomwHh6%)@S>6+5Kp*AMN#1U;V`Ae&TaK_0>;&)|V`GRsF>0epK3zO8cpo ze&TaK@wuP6=qEn+6QBEu&;9VDS=YE*)hxvZub3gI9pZGkW zh|wPm_)AJck9r2Q=X{mWvjhXGi(%nWO1yr4KsDkLt9^hdF+h|U@Hfy@;<4(0b|kQU z9{c;C>uW$G6#wgAIrG1PKjPOPgFgXXrvveyVUL6V&c7~T{~Yve(m?zT@IN@uuPE2o z&s2U9+w0^9;$9~|5WfPx$&vqw{Tu%K|8bpHDfulWUgJHWXzBCJV&CAHIqX|t)))jn zTj06$fnXk3=zl4?8n^gt!T;b$Kj|0<{4{nzJ&`z6?Da8Sl>7s~{u8#J^$!qT2Q;?w z860B=G`6zsNIRghm2Jn{0gbI}JL(P)bq6%Ia*3bp4=8e|7W9=f+g|}aCpHj#74$6M zfWC5Oe1;>BfnTS@^L_)t3DA*zK%+CC+3|cpqchw3)|t?;Vjy@4` zAoZwkn)wXwQwB8F^O@bV3}~!p+x^Rc#(K7IV!vxI`huDMr7xHn3tUcn8BnYDukJMl z)b?%rS@{4x&Hz2mfTDp*91RBa1v8()J=B24hAv-XW;8;y{eIA~;-K2yn9%c|2NlhX z9={({OtbA-or7`DryZ2ejgGDd8M7ahK6Q+Gb7KF3?sO!h-GhvF4=Un~1&0*zjFC~j zs&P>BJcrb`+V*_rA^O%s>RWBQZ#_gVaY!*xwxXZP75$9vVGq&69-@amq#oAg$2rnt zx>;v_L-e+Xq$nTbKKBqg#vwARL#j=knf&UI z>eTiU(7o_ixW}(>k6+<(l`OW0eS}hDJj$V zTchHhaVMxRnakb_>U(jr{~0_9egpJ8{8RL3PwCoh{|dYYdN$xGsnO{9)u*IMV-j>u z_!RsNNo;Mn}gKmAhkJ2lpCZr2dT|LYI6{N2C2ztztB(Bk1(1$qC0ZA z+s+Z#J_6fE6i;08u8}dz5ymV>xT7Q7(GmDR;ys>%qr~~6MEIjb_@hMlquk3;@jtF( zJY#>9+1I1Q^P|M`qr~&0#Pg%#-^ZK;J&S&nyEw}AA4M%k(aBM+{3vn$C~^KMasDWA z{wP;|lxTmHXn&MAf0Q^s1phZtn+SI$oHvaeC%=Mm4q|1(@UJHiL-1uyhk0(O26j=}#i_&)~!$Kd}M{2$|*kHP;j z_&)~!$Kd}M{2zn=WAJ|r{*S@`G59|Q|HruUWAJ|r{*S@`G59|Q|HrtCWAJ|r{*S@` zG59~mT^xh|WAJ|r{*S@`G59|Q|Hsk)arA#2{*S}|aqi_f`acf;$I<_B_&*N+$Kn4t z`acf;$Kn4t{Il15z%KJb^M4%uv%kD-=Q+pW|2Xj9~?*j$I<_B_&<*RzeX?c zHRc(<#vOf)JNi0fy{|LY`#K}IuQP)44)6VecX%HcdOYd%oLt&g?zkeP)lR*z;ZJ@zk?%kEgunyV2t*@A>W{ zJ)ZKO??#WOyyv@ZkEgunyGuNtVxM=R$5ZU{F7$ZH`@9=Hp7IXwMvteSje9)hz1{s^ zkEguDyGuNt@(%B|J)ZIo@3uXj@;>jjJ)U|t?(vj&c-Pq&PkD!T+a6DOhj*jLQ{Lg- zM|wQvz1?klJmtOJeT>Ib-rL>3dOYR5-HqLpcs#{^?m~~J*w0<)@f7>H3q77-5|5{zWjy8m+--Y2#eVKWkEgt!yGxw+KFfIO*}&r|@9OT7VbJ3#c6AqeJjJf= zLXW4|)m`ZE)U%AI*u!16$5Y{p?A|W)c#7TIg&t3N zuXcH4JjGt^vI~7?##7#_UB@$?@?Pz>oy&QzcB98r-mBf`@py{8+JzoZJ2@VRD{fsr_m&EVUb*yADgMMvtoWy&PSGzI+2( zhkA?D=SPRbWJJS^vxdow^bF1am5Pkci-x5cqw}I+)vVFutYI;1+quv%xzMn9lT8*h zOcpfEIBQsU>T+kZ!;G_@Q?%I-Jf~YZdL41resOQvQ*ml13oN{mZQtiu^GH}~}gzZ&` z&naIW4o>LaJA_`Jc|!NqFZ2qB6S^=b80ANuP3(KIJ5{WG8jM+Ruae!;^8( zbe+__yTtQ{Cz(GyN$+!#-sdFqhbMKv`c?O9bUZn!JGJf6)=Ax|(GlaM?$Nee{YmBz zPcnaalKI1vx_AA`e8@@K?@96C60dqXDITr{r^ruE(Q}=m=Q>4xa*8@SMXWwW1U^Mh za*CYf6gkN$a*|U-+Ee5tr^rc8Q6s0QkyAvxQ^dMc)W|6^kW*wJr^rA~QAel9Jx-B( zoFbl_BA%Qg_ZU%p*rORMt7}B@K{i)Dq8_NZ zxP57V2cheIL_M;P@eJpPdSs*acM!UDkEma^eFb#CJfeQtCEDLX_#4i1m6G3L|Bmaq z4$e|O2j1jtx3IHD#Y3H6@z6LA^s1o|#Y5v3pH2O;k95C0LK_@W@9Ywz-%ZzGPV zr#3#tukNWw)Kj~}k#mHIH=;h;Hnp!gPurgJ98nDS**w!SqDXGrbDkr_#t}slbMhkS zRyLwm<`U0>j!3;mN8=H4=@G>ipTQ%_5k(l=Zi6G<-$Ce%ZbUtWx%xM3^drr?9L=cL z_P@}HdTra<-$Cg1JHjmJh@Qfz#?^QGU%vxAVjWSx<0Cy6I-=gkwr74u)Cbx2ThJahqx9yZ^yZ`V=A-oHqx9yZ^yZ`V=A-oHqiQKvgHd|( zQF`-Hdh=0w^HF;9QL@TWdh=0w^HF;9QF`-Hdh=0w^HF;9QF`-Hdh=0w^HF;9QF`-H zdh=0w^HF;9QF`-Hdh=0w^HF;9QF`-Hdh=0w^E9z2O%zHKh0=@*(u@ewj0n<-Lc>9t zxSA#kr5OvP zGXFH0f11ocP3E6gjqC~1#FMmYM8}ior->(N^87S;ewsW#O`e}7&rg%*rE}pH_Q!N#tME-fbtboxP{&ZPR4$X|ne;*?XGyo>nXH zzdQq$R$H*`>^)8P{(@S>aPWd!giw0EDs*P@f?Baq3Q@TfV)RO|7sQoNUW{Hnm7z^# zXj2*5RE9Q{p-p9IQyJP+hBlR@=&~c)$!mo zsy?kOR5t25&2x~`JO??AeomvD(`e>2YB`NgPNS34%EA0!XI!VL<OS zoY5U!)vulzIHPtaBu_X)hHysucZtXQXQX+f$NOibQlrQFXQWS~$604|ZAOp%&yX#g zAzL^@ws1yQsB&_KGvo|sxY{#Z?HMwMGh_}gQ423I5BUjtGiH35G2_dO1Yc$( z_zK6r!tt+g{3{&)O^*L2$A6RKzsd1qDjy5RR4!y}I~G4Gmc}%_W86B%xOI$i>zHO3{HwVg({(rp@on%Oqr49b zJ@!0{$5+MbcWEQv1JkPzKXTIya>PzQj*6X}#&Gu5^ z_qng{L2uV~+nB$N!Auf5!1Y|b5xv+bNmIBcLWzyE>yJa7kWP7f@;kr zZaWuLYcBB&zy+ep1@7?zQRRZprXzJW<2E0!y3>)WyJ2Ape4O$Da0v7~?FHh`1+{el z*L~#$)!-hXzaMx(vx`24Yf#UoLmMyTH4>7kIb#g6huY z*6jt}?Y*EHlt=ivpc=I8Sb9ORR7Vooehy&m_Yy!q6U~B@$CSYs= z#wK8F0>&m_Yy!q6U~B@$CSYs=#wK8F0>&nI8+wAbp(g?}Ho?sH1dL6<*aVDCz}N(g zO~BX$j7`AU1dL6<*aVDCz}N(gO~BX$j7`AU1dL6<*aVDCz}N(gO~BX$j7`AU1dL6< z*e_u07clk<82bf`y+QdKl)pjw8d^-HOX4s$>3?9LA7J_4EZE|)+Bw_WZ>0Pld2d0`Umz)5)p34O*}KszcqdtDKgmk_NmklVveJH%mG+aWFCD`w-$_>a zP70g+it@ULFsoP{Qz&E#g-oH4DHJk= zLZ(p26bhMQtTBZ`rclTf3YkJ7Qz&E#g-oH4DHJk=LZ(p26bhL_AyX)13WZFekSP>0 zg+iuK$P@~hBCnW2AyXRt=`I-2Orek|6f%WErclTf3YkJ7Qz&E#g-oH4DHJk=LZ(p2 z6bhL_AyX)13WZFekSP>0g+itnJzYW}mr%$h6mkiLTtXq2P{<_|atVc8LLrw>$R!kV z358rjA(v3dB@}WAgt8c$r$eOdfbS*e$j%lLuZV54=nsc$qx#GI`)- z^1#c~)McXUW$NoP(e*OX^)k`*GWB&?_u_Lp54=nsc$qx#GBt9U7<-vK@G^PeWn%1Q zqU&Yyz{});SI7gekOy8N54;k8L+8B0y<8y=yh0v$g*@;IdEgcDz$@f|S2W7g@#KM5 z$OEsC2VUVWu5kTV0_TBO$bYVIXLdVPKj#FijkoMqShB zYMMAOO&pje4ost~Y2v^%abTJ_FijkoCJsy!2d0Sw)5L*k;=nYjnIB<;`xkim#BMw|64qPJ+Tq6!#BMw|64qPJ+T%+!;QFqsf1J{TH z*N6kxhy&M%1J{TH*N6kxhy&M%1J{TH*N6kxhy&M%1J{TH*N6kxhy&M%1J{TH*N6i% zC}akO%%G4N6f%QCW>Cls3YkG6Gbm&Rh0LIk85A;uLS|6N3<{Y+Au}js28GO^kQo#* zgFCls3YkG6 zGbm&Rh0LIk85A;uLS|6N3<{Y+Au}js28GO^kQo#*gFnP+p3b~F#uA`9aDC9Z{xsF1vqmb(; znP+p3b~F#uA`9aC}b9e%%YH46f%oKW>Ls23YkSA zvnXU1h0LOmSrjshLS|9OEDD)LA+soC7KO~BkXaNmi$Z2m$Sew(MIo~&WEO?YqL5h> zGK)fHQOGO`nMEP9C}b9e%%YH46f%oKW>Ls23YkSAvnXU1h0LOmSrjshLS|9OEDD)L zA+soC7KO~BkXaNmi$Z2m$Sew(MIo~&WEO?YqL5h>GK)fHQOFGxas!3jKp{6!$PE;7 z1BKi`AvaLS4HR+%h1@_PH&Dn86mkQF+(02WP{<7was!3jKp{6!$PE;71BKi`AvaLS z4HR+%h1@_PH&Dn86mkQF%%PAu6f%cG=1|BS3YkM8b0}mEh0LLlITSL7LgrA&91593 zA#*5X4u#C2kU11GheGC1$Q%lpLm_i0WDbSQp^!NgGKWIuP{?satV>`Q(-|(lO!pu)Wst7CGK6X~4E;{BFfP z61)|6rguwsZTt=B@8R4c-@C<^Pi{#w{+GXpb4$w6l}I_pEk0hkt~^Rbx*n-WM=IlW ziDwIM1-r35XLw85ugg7icuP63ZRd@*lnLARmrrhyL*CM}F#GcNaBe9#cDZL4Zz)5z z?K#F-74NTT-3Tvyr!yMf=R2 zlf0!|+O{*&Tgs?yJ1@PZ`VuOm*1yP3Zz->~?YYWZ(w=-td-A31TK^(zy+zh~OFHzg zx9iupX!UQ=>fch^91q@7y%_EBE!yT=w9U7~r%OCf`8&$lGD&9sFZ=;I0QN`P+ z;%!v%HmZ0VRlJQVa;PGQDsreIhbnTYB8Mt+s3M0da;PGQDsreIhbnTYB8Mt+s3M0d za;PGQDsreIhbnTYB8Mt+s3M0da;PGQDsreIhbnTYB8Mt+s3M0da;PGQDsreIhbnTY zB8Mt+s3M0da;PGQDsreIhbnTYB8Mt+s3M0da;PGQDsreIhbnTYB8Mt+s3M0da;PGQ zDsreIhbnTYB8Mt+s3M0da;PGQDsreIhbnTYB8Mt+s3M0da;PGQDsreIhbnTYB8Mv8 zK^5g9sIrF@( z)<=3(XFl!~dU+|z|MIHNyw-sj9gXwqi|xg$I`dMROFToEk9);VUaB*CRcD@6oq6@q zKGLf?^Kq~0%*Ws4c(3Zr$GxgEFO~W{Ug?*YN^N^pXI|_Xy{a>>l_5s2>db3>h;6Ux z%(JR9&#KNmt2(_?w*G~l^U|}<#;VRdvpsoMb>>;snMdJy)rgPp;%xr_dR1p$&;5iTBddpMGta8dJgYkM%#7vLPJQGIM|xFfo>{WI+No_n zxy~y$^SyXgXI{CP(W^T1T7_cts?I!lTAn;DPrJ^mUF!_A>%7{v?S&laRh@a-cwQ}0 z_rb?|g!4eXqajm3c@?J7xdcM0w;!QCbN z=2s%&h$K9m9~SCM8bZDKB^;(i>pW#^6@gH3NvOCaRF*5$mo$W0nI_a)L7}ofp|U>V zzjC~ylWeX06l&$CP%A%$(wI;yKZRODDExQ+rInwu_2!pQZ+;22dQhl{B-Hv(p(2t{ z>pz84pw@rN*7{GOVv$g9ehGiWf3^Now%!;L>di0V@36J1Q1&dg-u#k1hpjiiWb4hZ zM1tB(P@4&AGoe_de^HwW)uzto)oa47_UqMa!tLfzwd^CiDAAi=vi0VdP;Y(-6@`R) z^Gm46Bh;H;LPZ{--ux13MW|43ehC$Mgo-&rz4;~7icq1xq#@LsUqZe4C47owz6$Ei zFO?hx^(772dh<*8bxO2GRJPWL3Kf5Zdh<)D_#@PtUqY=a7b@Ba^(76VqK#0|MyOSz zLX8518U+Y73J_`(AXKywq76kGpG_-)g?jT#h#nkmWTOE^8}p_Wq(Z&X?vFRB_27e$|^_vTvjOy_D-q8Y=l?Y^@!YtvA0C^VIIfgvCbU$vo$H zvK>$6ImZ)fJSfz7P^gihP-{Pgjwkb^H)9gixKFmD$2@0lLXGc)dqIuqWNS@`P@^`X z#%n@Hk9p3Zgc@fFHQo_wY?YYj97(8=l+e**o--n$)_w>bJ?0Z7=6fB2Y)6CnM1%Rn zf%(cGT%uLk!b`Sk3-i6!PWHo!Li17kd~`k^h0jOZ^HKGDR6SokqyK9i&PRds)$7@Q z8Pr-k*;=bC)SFzw?@+F_cCx>Vtx>jYt71NSn2!?XtM*k+ZO+#iU%yg!^VJuOC%kX< zRiR^hf$GBO*j}JJGCIN+s78cD?*ig>0dd=VOuO81yFknv9k&aJ+XZSVw)LD;s3)XC z$8hf)ZFCIx&e29a|4Ml0Xrm)}0ashV)fN!X3y9|-brDhvA+->y7RD2yXP<*rf zUkLw&@Lvf3h45bp|Ap{h2>*rfUkLw&@Lvf3h45bp|Ap}HohZi>-hN?e0#}Y~SPr`qa z93u&bNsV8|6G@o#US_te)uepe8F5;St&`c4UDMB+vXr>6w6rq_SG*g6T ziqx)k2F)rD3$2+V?zf0LE#gj#xYHu;v50#tLNi5yHB*FUiqK3EnkhmvMetCBW{O~= z2+b71NfDYU(hRe_2i8mxEES=dBDg9-Ges~~gl3B1tq9E&!Cn!XDT2cyG*g6TiqyaR zoYqVc+!mpkA~aKkW{S{E5s{<_%@o0N5t=E2?IJW&gl3A+Oc9zXLNi71zYzWx!v8`z zTnL8?(ab`aTnLj3VR9jwSqPsC;d3EeErg|o@Usv$7Q(|q7+A=?FXXNla=#0?uZ3u4 zA(~l;W)^Zs3%Qqt+{Hp&zrKHmW)^bI@1eJSk5~OA-oxF!hx_^?-OJU)AL(9%xyO9v0^kMZYW5v`-5;RkSW=haZ z3H&dH|HbgX7!DW1;bJti7$z6P~gVf z42AC%dq$66-YfR53Vq~z#hX!U8WZmoSNc_48K0u$4EQ>D1$+zCdPNI4}rVD6lj)~s1@kHs$bh9*d7xtQ7bTNJ-pDoEs_3x{1lF z6vZw@u}e|xQWU!s#V$p$OHu4n6uT6~E=93RQS4F_yA;JPMX^g!>{1lF6vZw@u}e|x zQWU!s#V$p$@8f#j$C=;9ncv4b-^YL7Pe1#9`q}r>THjAy->y5onz&teD%ABG-Ot{k z@(!V9Acc2|lRIJ`1+~+t>`!9f1!|{Jm1w6?;c{?=<}~i`PNTwq0lx%(8Ptk;l^+26 zLG4Pc5|3@~h`Ao`h@A(20KNhK3cLtfU3bK-*gL$_sBjUu7}T!BD!CK9+t=frMup44 zzu*|n#HvIyu|kiU@9<8eLcI|n)KgdC-}*@JG%9QW8^I>98EgSt!Owu71^)*89QcRx zwEO&t4p8&Ukd-F@L%ekUK6G8U+SG+Wt;y}_%DV3 z(wO-#h5u6cFO8Z1Qt$LCH2Uj_eF@LvW0 zRq$U0|5fl`1^-p>Uj_eF@LvW0Rq$U0|5fl`1^-p>Uj_eF@LvW0Rq$U0|5fl`1^-p> zUj_eF@LvW0Rq$U0|5fl`1^-p>Uj_eF@LvW0Rq$U0|5fl`1^-p>Uj_eF@LvW0Rq$U0 z|5fl`1^-p>Uj_eF@LvW0Rq$U0{~v|_kHY^);s2xXUk(4&@Lvu8)$m^p|JCqc4gb~f zUk(4&@Lvu8)$m^p|JCqc4gb~fUk(4&@Lvu8)$m^p|JCqc4gb~fUk(4&@Lvu8)$m^p z|JCqc4gb~fUk(4&@Lvu8)$m^p|JCqc4gb~fUk(4&@Lvu8)$m^p|JCqc4gb~fUk(4& z@Lvu8)$m^p|JCqc4gb~fUk(4&@Lvu8)$so@`2QIEe+>RV2LCniUjzR&@LvP}HSk{p z|26Pm1OGMfUjzR&@LvP}HSk{p|26Pm1OGMfUjzR&@LvP}HSk{p|26Pm1OGMfUjzR& z@LvP}HSk{p|26Pm1OGMfUjzR&@LvP}HSk{p|26Pm1OGMfUjzR&@LvP}HSk{p|26Pm z1OGMfUjzR&@LvP}HSk{p|26Pm1OGMfUjzR&@LvP}ABX>s!~e(O|Kspq3;(t7Ukm@W z@Lvo6weVjH|F!U63;(t7Ukm@W@Lvo6weVjH|F!U63;(t7Ukm@W@Lvo6weVjH|F!U6 z3;(t7Ukm@W@Lvo6weVjH|F!U63;(t7Ukm@W@Lvo6weVjH|F!U63;(t7Ukm@W@Lvo6 zweVjH|F!U63;(t7Ukm@W@Lvo6weVjH|F!U63;(t7Ukm@W@c#+;{{;Mh0{%Y%|8?+R z2mf{OUkCqn@Lvc2b?{#Y|8?+R2mf{OUkCqn@Lvc2b?{#Y|8?+R2mf{OUkCqn@Lvc2 zb?{#Y|8?+R2mf{OUkCqn@Lvc2b?{#Y|8?+R2mf{OUkCqn@Lvc2b?{#Y|8?+R2mf{O zUkCqn@Lvc2b?{#Y|8?+R2mf{OUkCqn@Lvc2b?{#Y|8?+R2mf{OUkCr6g#S;%|0m)9 zlki^;|Ml=+5C8S>Ul0HF@Lv!A_3&R0|Ml=+5C8S>Ul0HF@Lv!A_3&R0|Ml=+5C8S> zUl0HF@Lv!A_3&R0|Ml=+5C8S>Ul0HF@Lv!A_3&R0|Ml=+5C8S>Ul0HF@Lv!A_3&R0 z|Ml=+5C8S>Ul0HF@Lv!A_3&R0|Ml=+5C8S>Ul0HF@Lv!A_3&R0|Ml=+5C8S>e;54U z1^;)!|6TC^saQ?yew}^F?>ZJQsI&{L|nHm&8|s ztH2!Po`1U=FL&eR?!*Hs`82+k;cFSbmf>p|zLv%8YZ<p|zLw$ZPw=%IU(4~e9AC@vwH#l|@wFUZ%ki}wU(4~e9AC@vwH#l| z@wFUZ%ki}wUw?|P75G|#uNC-Ofv*+#T7j<>_*#Ll75G|#uNC-Ofv*+#T7j<>_*#Ll z75Mrye67USN_?%v*Ghb?#MerEt;E+#e67USN_?%v*Ghb?#MerEt;E+#e67USf5F!( ze67OQDtxWN*D8Fi!q+N%t-{wTe67OQDtxWN*D8Fi!q+N%t-{wTeEnB^t;W}Ce67aU zYJ9E6*J^yN#@A|mt;W}Ce67aUYJ9E6*J^yN#@A|mt;W}%<7*AR*5GRmzSiJt4Zhak zYYo2E;A;)O*5GRmzSiJt4ZhakYYo2E;A;)O?uq&N!aXrRU$`gsVQKXq#j!ErpGd>^ zD2^HblyWQlp4gv(o-@BErggl+-QXUu2iyzlEgt>)ZS1q4R}kH!xTNzdE*bCkF^Wq@ ze8vA18!z$yg8k?G%TE*TQM@wxslh#pS3<=rqo07>!xNBuf;JzYxC1N&%fNE50;~k9 zz-q7ttOe`9da&K+SG+RndxOF+=*rhpJ8P+(wbag9YG*CAvzFRfOYN+scGglmYpI>J z)XrLJXDzj}mfBfM?X0DC)>1nS)J_An(?IPsP&*COP6M^mKNrm}{p&eT|QI?KH$(I}I_{P6M^mKod#;Bf!bL|?X07A)=@j_sGW7x&N^ym9ksKL z+F3{KtfO|;Q9J9XopsdCI%;PfwX=@eSx4*P9wF`NbNLIJB`#%Bel~=?KDz5 zjnqyfwbMxLG*UZ_)J`L{(@5*P9wF`NbNLIJB`#%Bel~=?KDz5jnqyfwbMxL zG*UZ_)J`L{(@5*P9wF`NbNLIJB`#%Bel~=?KDz5jnqyfwbMxLG*UZ_)J`L{ z(@5*P9wF`NbNMiTNAuB!CMo&HNjgGyfwjF6TCISTNAuB!CMo&HNjgGyfwjF z6TCISTNAuB!CMo&HNjgGyfwjF6TCISTNAuB!CMo&HNjgGyfwjF6TCISTNAuB!CMo& zHNjgGyfwjF6TCISTNAuB!CMo&HNjgGyfwjF6TCISTNAuB!CMo&HN#soyfwpHGrTp! zTQj^h!&@`FHN#soyfwpHGrTp!TQj^h!&@`FHN#soyfwpHGrTp!TQj^h!&@`FHN#so zyfwpHGrTp!TQj^h!&@`FHN#soyfwpHGrTp!TQj^h!&@`FHN#soyfwpHGrTp!TQj^h z!&@`FHN#soyfwpHGrYCHTMN9kz*`HvwZK~oytTkv3%s?!TMN9kz*`HvwZK~oytTkv z3%s?!TMN9kz*`HvwZK~oytTkv3%s?!TMN9kz*`HvwZK~oytTkv3%s?!TMN9kz*`Hv zwZK~oytTkv3%s?!TMN9kz*`HvwZK~oytTkv3%s?!TMN9kz*`HvwZdB~ytTqxE4;PB zTPwV^!dol6wZdB~ytTqxE4;PBTPwV^!dol6wZdB~ytTqxE4;PBTPwV^!dol6wZdB~ zytTqxE4;PBTPwV^!dol6wZdB~ytTqxE4;PBTPwV^!dol6wZdB~ytTqxE4;PBTPwV^ z!dol6wZdB~ytTqxE4;PE?uq@kL|g1L;Adm^%U%!u4Y&b(#Tc*fG4V?9)0E`E-y4Iw zTpoN1{2aK^n0UayCjJ@wi^BDIT#v`~F?(E($MrFLTpzQ?^)Y)~kH__RTpzc`^>KS# zAGgQ#cwCRi^?^OE5A1P09@pb>eZn3$;Bf;UH{fvt9yj1|10FZvaRVMV;Bf;UH{fvt z9yj1|10FZvaRVMV;Bf;UH{fw29yj7~BOW*6aU&i#;&CG$H{x+49yj7~BOW*6aU&i# z;&CG$H{x+49yj7~BOW*5aT6Xl;c*ilH{o#;9yj4}6CO9=aT6Xl;c*ilH{o#;9yj4} z6CO9=aT6Xl;qmioapQ^4tHl{VtlZ}FYE4Fcvr(vb%!Ph~>GNt$Mz4qeyxNiREchLx z+J#Wc*LkFTW1CB)d}AqC29|>rU?o@uR)aNQEm#NE3-1>*_X|G*T5tEm%>6KPKg`?@ zGxv)b{VHaR*4zCsb3e@7FJ@FCW{jT$HyUB)elcVFi^9!#+>FP~)Wv2zZpPzgJZ{G0 zW;|}j<7PZ=#^Yu@ZpPzgJZ{G0X4QqxkH^h;+>FO9c-(@=EqL65$1Ql=g2yd*+=9m~ zc-(@=EqL65$1Ql=g2yd*+=9m~c-(@=EqL6D$E|qWipQ;Z+=|Doc-)G|t$5su$E|qW zipQ;Z+=|Doc-)G|t$5su$E|qWipOnu+=j<(c-)4^ZFt;<$8C7rhR1Dq+=j<(c-)4^ zZFt;<$8C7rhR1Dq+=j<(cx;!#_axe-aN~z!dLAR4+rCpOZD($+omsVZX4TqbYqa{V zJ@&tWe*yj_xR&Gpca6o`W6j`yqr3(CUhG!vzt-5WJ=TWpl^E@6Q}*~MxEtI9_JDgq zuNrD+)~=mdyLM*n+L^U$XV$KrS-bYwSMfCn>djOA>jRxZ;iFb^p2`f@2Cp>)>wN?@2Cp(Mzc`+L_0%S&uNeOjevG$DcfUH*q6Y|;M>0Dcme45t=i*7pjT40$Ngq#JM)?CalaYb z&a7s8yad~8d)ni-VSA-qd;ERi9j@hg8CXq84Ok1-f%V|0z!jWlCAbRwb8{6(Z*la- z9BF$Ty~Wr1%!;TwMiJHc8J|aS)%It7J;C4lJi#XH`~0iot$s~>z$J>hwm*nnhW#Pz za_kE5PD(1VKZ0F_{ZZ^{?2lpBV1FFD7W)&}b=aT8uE)L$`)+U~kW?X|KU#G(#jQ3pqM5Q{p9MIFSV4q{OUv8aPs)Ilujh&dK@#H@{um}5~# z%(1A0Skw_SCmk`zqK=q3>4-TNb;KNtI*3Ibnt$-W9E&=LMIGwjZ95iqsDC#)7Ip9h zp@Ue|K`iPZ7IhGdI*3Ib#G(#j(f?oFna4L(td0N7l5|O13T0mdqO2_^ZPTWLNSdZl zEEFlbf~0NQ2GXP_ld!o#Q8vYZg8Kr32#AR5RW6I-g5q@-H?AlyS6}tIAd0)cXPz@j z3*PN_KcDxH7e1YNX3oq!&urf_Gv_2RG|3`ElPofjMTRC>WFU(SO|r<)B#R7Wk)cTz z8Jc8~fh;mK$s$9OEHX67B14lbGBn8|Lz65rG|3_ZS!5uK3}lgkEHaQq2CPY>{gOon zvdBOd8TgFDKo%MJq{BcK8Th=zKo%LuA_G}uAd3uSk%25SkVOWv$Uqhu$Rb0NEHaQq z20kk>kVOWv$Uqhu_}s+MB#R79vdBOd8AP(kKo%MJRK-9R8OS07S!5uK3}lgk&shv) zkwGMj3}lf(B#R7WkwGMj3?f-%5XmBgNER7HvdAEkMFyNZfhBP6BwfiO1J-ZQZpb17 zS!5uK3}lgkEHaQq2C~RN78%GQ16gDsiwtCuLFGJxH%Vog$RcZ1E zl0^oSEHap6k-;R33?^A*Fv%i=NfsGQvdBOd8OS07pFJ7KA_Jd58OS07pFhb_Hp2qbSGj=HOiAvo{aJo)F@YyaeSr|$7ecme5Mn} zXF74fW$ax9J8dNw+CJL z?FLA*58eG}?Ey^lBib>9B3wGxyy?K&7>@Md2yhb zlwU#jHFOW7`zE^Z{ef^5zOf2i`2Ij}<;p4!G?TL2<;8(!QvLwt4^fu8yg1NI#{VQO z2bxJY72Qm9~+fnX| zazB*MK>18`&%&4iC=Wz=5Xys59)j{vlygzeLwOj=I?4`|^HDB9xe(?i0&M8gXo6Pm2dUL zVI&TMvnLC>>Cy$JN!O+g(&WGHWTZw=(zFurO_^wE5He+|rD&x}W?FYRH8bPkn`X3H zC0n!%EvjUzmaQ#TGVDFIHA+s^I%*#%*{1c>zE^UFmPa}$ITPejO3u;-laK~qb;Z-b zt_ZnN$wccw)0IrMEZS4aOe>^=mCUt%a0X}QwP;=GVkKKOJA8+c8K0tUhF@AV?m;l$@bm$o42XQ@fCNRdSX#iAT!<4S{H2k-yGf=ZpI6wc+N4kw8OZ)V|H0 zuRHWya2!MJqr>5bpx^EZN1DSCUo;R7v8fceAe+JauKLJyG5KJiTq%m?|$E zX&4qX%MimVD?Hxu)!tl4sg-E~tpWa`@V7|wYjv6({(KPjfmEx7wPtOh7Qs}F5Np@A z!C$_nYYzB>_o`8HXhR`(G^7qgX+bE*u6aO?KyK;E@&X`*v^=c};`|`lwQ7hDX|V5r zaDx_ud_G9)fHbn~;o!OT5Fgg+!9BGtWIbie%2W%%uYnwP$SdnDON*j)X6pyAZE7(__JSFn z1MMSwK|nbH=$Ax$3TQ1i#LDzihpgp4YkS#$QE2_MwPEmoKK{=G4X5UoeJ=Yg4|~4} zQvSF3qEJ`a*U~E4@(p02*$a7CW)t*yCDumTE-e*V4D5R4u<%V*6V2>F(HIE#5 zr}u6?Sg-$6yIaf3!@4#=9fPOXAt0s_=Sw5_o%+xJU^(n+zu-$T?&rIhTwg zZc<7-q>Ok;IT=mHkP0%EoJT6jI5M78kqP8{GLcl1Nn|paLZ*^wWICBaE+7|@nPe8Z zh|DHFQbTG<9r2TT(m)zXfXpFtNsu&=5DAlJVvqJ9j;tf=$@Sz0awEBk+)QpE zx02h)?c@%!fovpql1*eYxr=NecayDT8`)0oAv?&uWGA_g>>~G*2grluA@VSJguriI zlgG$z@@KM#>?Qlie)2eZf*c_5tCQqu@(ejho+ZzbL*#k#7xDsmk-S7+Ca;iJ$!p|w za+th9-Xw34x5+yMemRW1OOBHF$ou3N`G9;#J|Z8JzmZP}{6Y%(jC@YMAb%%clCQ|u z1b%gbd`nJ{@5uM$B>92-NPZ$elV8ZMwOMs@0-`Luu*QYS5<#neSh=-G5Q9YN2bBk8$x6m`>5>Y-)SOUvnKI)+xzvGhDz zNypLgw2Drk=hKO_nogpV=@dGZPNUQ540-{DXX`dfGr6X@Jh5 zb7_z^(GU&OW@^v~6*Nj?bRL~g7tn=t5xtmRLNBG4(aY&#x`ejSrSuAVC0$0B(-m|j zT}7{=SJTz>8XBi-=vsO$y^gM<>*@9M26`jCiQY_ap|{f8=utNkM5%P(+B8-^db12`A6XQrXQt`(cSQyu6yWSx{vOskJBgU z0r(xyr{EVcpP>iov-COm1<2>&7YSdWFVdIj%k&lcDt(QAdl)eYQi*^itFY8145&VMC-{>dwQ~E#jGx|CGg8rR;Nx!0B({Jc;`Yk;{zoXy7 zH=zGOf22RrpXo33SNa=#XQ{>rd@Ut|Z|JiyD}1Y3DobPO@Euth4898qzA-49wPzhz z4(kZtmeE;$djspny0advCw#uXH+;t1&ib-`>^%Lo%J%3^FDo6i=og=`VKm|emyWtXwb*sv+Ox`h&|8#!d_r6vX|J)>=pJZdyT!$4zoAdo9r$2HhYI1VSi=svZL%h z_C7ntK42fRkJ!iTZ|oEHDf=Jx8T*`l!T!#^WM8qb**EMs`<9(x-?8u6N%jN#k^RJe zX1}ms*>CK3u5rRCXPk2jxAGL8%F}o{xA6>~$+LJnp3U3y4m^i<h{5)RC$MNyJicjF@^NGBgPvVpL6h4(t z$soS^9J6?1AGpj%Y(d$hj^GbbAv~?;87mq^Z0ze zfG^~W_{IDZeks39@Hk(?*Ya!mb$lIP z&#&h<@EiF}{APX&zm?y{Z|8UL4SXZNlW*di`CWVqzngF6+xT{VPfA`W9If-$^H3}p z%npS^aSdv9#We9 z5m-k@(|k=J30UFVFtLD=g8sB-U&J2@`s<_VDB%Vr)h8GJ0Wp_12V=qlEB7X!wQ*r{ zqd#PYG6LZ`iwOEeBVXi?gjqP`XVLj#OSCcKhxQA{BD_8@&(B0)fkpV|`9l`J-1YEK zAmoR#g5gk_@HYie;z7R<7QYem1yi72K2Qr)@e8@VpuXto_jOA}o-Y{v_xE;NO~h9_ z*B_PjN~-}8&CO7;SVtRdP6C12K%_R-l#Uw=0oxS6r6J;*=l^fk18K5!ztqTTe35hv zp{8`y6b%IH{IU~kpqjE5vHQ}^?yC#W4{_N^sj}gNa5c3y7J-hbUC0*tLr`>hu0I6D zrU*Z7y;AD}urm_@k(S(5+QN~#dT3YK%$W_bKrrZU3S$eT2g414T3--GQ%Wop&~>wS$zJ~+C;NJ@5{`7Gqb-na~gD|IozxPGfluuqvnrn_q0GF4f8`Ygv@3L zo5{mw@^EXB*05<$IFZX*7nm2Q^IOAaBgD*%F*9SVHDg*VnPVYd1nxj1q%BNDr?{JZ zwUKZr#b^3fH_SNMCg`QO!woRJ=BD^e-|E3athJ^hPpcwZZL7>Zb>S$l1;^^C^+Dm* zTGJ~ty}Cpw681%{b)eoCP4Ox_;EYAuWA&PL_|Z%ELSa5=`cO38pA=KP$~wQY&TAIz zN6$98)goI%t85)@mfV0IA1!Td04HNKlH1gh(aVax;}FXH_ICD5Fy$B(Wc`R*aQl8kl1n+iHVt zPOF@8UK^t`=AIIes0syP+y`o{m1ZXf(aWf8n=aTUV68NpGl(9qlnoUG$69F)x}fQe zH%kkdrHyY>Kt`xdz&hS6Eo631$k!Ye(MTBXlFS=wVE#};N|hP{VKoG*%#I49ms!;q z3pMy6v8JFe7R?N|4bdtu4g0MVO-ta$0<_JT*hYCqq)os&(X=FDdevqwfu60pwK;8Y z%aivzIbTz&)wEBALpmh2wc5-s(94+AMnOijO~5+IOczCuPm)6>3XXNMIp<^OrA$_J zkEyy(HtQZk&oWuk#{!3mp@z)KZEKzxYa2?LtR_Uv^lejHYhat-MxNeAUf3$9O;2FK zI>T(0Md+o^NDj&LMM=>*!>rjN^enJaX%N=>U>K}S$GeD`7s-iYirc)0r1%sxO@!k$ zn@KX1GpgIPUk2Q4VL_!Pf2*w)Q@Pn(7Hp=pq-k8Xl+|nm3pQ{@+jg=F!{2qYuS2AKd$4Z4&Thc$-B4Du&Ui-l%y!vjSj*QF20NRKe;Dh=mauliOrSuWIr) zmKGEU1r{`lCL}Xdl!N7aIj7g(*rWp8=QPCh3Fw7D%a5snlmV&)3}SgGt;} zQ|F`OVsw0rP7A=~K`ZEl0Grqtwp0fintW`MFP5S#ViOtz%maTDM8H(#F3FZf^F7%UrA;tkR)+rlF-C8j8^cft0YSV{?E-8pBptwm1147W7yYs;W$2%}~u+ z_ydb9Vc7>6vgCwi?M|~aLltXwpt^{Gbj*xmny)?(aOiq|K|*pml2U$BYQ0*Rsd6}- zvSpK@A{k1iFHTCXq*RiSiu9zE)K!$w+4GDa3yuPk~&;T9j>GfS5k*7sl%1jQIgbAlGIU> z)KQYuQIgbAlGIU>)KQYuQQTTeLI=zgHHI8|;;KVW=y2!>9S%LA!=Wd1IP`=Lhn~>k z&=d7==t&)pq>fgboryTT#ATgoE{o@z-c-D~Sm&dcHZ_5RwD}3iI^9gT(DdM09qihz z{wC>RZD9KAuFTf$FKi;x@N@uA1W>}=SytqNq!Q9R!|fG-lwg*p!7$9(yP`15Z8@7hsbd4fuj} zf% zsq$_v&rH(fIvS-6b$Wta3OJCvWFSql%Kp{;9iagkVu&&kGxN1H{7 zt&QBijU17;Mt_Dp^+_~uhCJ_S4L}1V0ya4RNywSl8p#kgOCppZ4=fS^X=%Q$>&i#V zA)K$m1*K>%<3&=*((@Cz+fa@%SNqdOVh zm~_#S0<%QDz$_8`0^S%7&y`(P;}3@CW2!=xs!%ue6*^7(3!N%lq{2mJJqnA=dK4C+ z6?$P2wj=o1j^Jbcz{hq3AKMXpY)A019l^(T1mA3@!lHyeY!`^fcF_xqmHuL-zgX!n zR{D#T{$i!SSm`fT`iqtRVx_-W=`U9Li2)c+E~VF{^tzN@m(p9J^pq$)umqOltFT1rDN%Y#R6R?Sz7nOcMCmJ0 z`bw0(5~Z(1=_^tC+^U{#RZq9l?^gQVO21p_cPssFrQfaeyOn;o((hLK-Acb(>31vr zZl%9e=`U6KOO^gorN30^FIDJjw=-vcaQl@F*KR$_9^W1CO%7<5jxLTXmPIc2L|X zRNN>mQ#O<-8_JXoCQtOjGG#-VvY|}bP^N4sQ#O<-8_JXoWvU&@R6lr?ey?f+uWAFY z((hIJy-L4VwSiaZ_bUBfrQfUcdzF5#((hIJy-L4V=~w(LELZx=mHu+2zg+1rSNhA9 z{&Jpuoso$xa^>;eV_IEnW`a2zF{hbcf@9>)Q6nwl6 zK3)euaUJc0Fxm$`+6O+`2R_;dKH3L9+6O+`2R_;dKDH0|Xdn1!pTld;Q}C63bDlz2 z={M&ogq41Co@er4!)wk{@Rc3rJcY2b!46vC<>%y|l7)eq)8g|O-ebDlz2={M)8!)wk{@KryU^Ay6WAIy0QVbu@jJcY38 z2Xmf6SoMQBPa&-8Z_ZN)tNNSs6vC?h<~((H&3OvGs;@aOA*||a&PxcZ`kM1HUsv~q z0=+z^_4o=mA+T7iX%mOr4jI>>HJx0?oR$pFvt(QrE=-dpnZaZsnRqpk-@KU2nw?nN z%Ik8I&^{4S15Y0zZnEd}m`YD7EadZ=;gM;IT+`--g;hp?2M@l$OU2ba2q|)vi#{xH z<#kxw%ImnSl>)A4WdgaF1)tW}%iB@DBVSLQlsIUOD#6kqhitnxC-^d)ZXVxDF;$-4 zOCh`Mp}mYC6;|`Xl+}DFWoz?5DlPdi%4#0or>GNqt9eSFqK@X%TaV*u#n?1?VulAo zTuK?zNo*h0hF5ncHnO@CM}}T#&SdZtGh2-ik6VMcbD5S3pO47YQhtZuoyNCyGvKAM z&hSTNh;0LxLkMK$rfY>-kw${PXbAFVYjj*yrCsYhv1*(h-UQa59QfDPP38-ckN%Kv zAm%H@9BF8c4bo@9`^X)&F7Sr3EGZo_t%KG{>#FroS1j;Gv$UUrB{^Vs zH?W~sFwo%BcA@(Sx_g2!aI^#HK8x;)!EkL*dmY_(!t(0-=zfas*K(j~KcM@YbO{%- zOViQqfNpmobO-5&?qGED!ObUUqdN-Sa&QYsCAt&Qofeg)%|f>x-4M2qd@owQsom

dg4umb* zSop7L@4Uua)yUu(y;6YyqX1H2=+ zk=zMyVZ8-!B#nmD1m64EhPCUirT?Qhg=88SYcSS9GSi&?F3}Zmg+ZDeNYe>Y5_spR z1$vjli~$+)6R-($Lz<3|rZbH8t}uGL!^rLlR|sgn8Z|%;NC7z@pUMH!zsixNarq__ zv6H@#gOdK_Oz1#(&r+5v=PpI<L)Rv~ugPkV1i*7pl+NB#>+RxNm*do1!)@)$%eaCFqnQ#8|gYUlE zPptXmtcTy2aahkxno2BSR5jYjCUa{Jom}ncqIa@FAU!7wURn>p(~Qtidqt==&oM+F zBrmX>eu)eANr5K6y*dhS?7&kWd$m6@4_;#zc8^={-6c~m){7jl)|LNebjgHUOp&87 zzrb1IESaHS_#Y}Q)bmZHL;jsoX(_znpKBkTuP?cyZ6%3CV@pk`*H0Nip6wRs`H}U*J%h_KnfC z-(S0P*TeI!|7P3RTJPw*xwdP^pEu;{FQ<*Y>h+Y5x)1%KW&5SyWw6Jeb!>#9B|5Uv%?d2oOkfTt}X`RN2b16rh44k5pDs%v_I4E5nd^}+hU z4QFlWzpS6iSQ`nRl5bd4h}>FV9>nXNWu`M_5gB@VLMcntvt)cb8P6HDKCbtc;r1NH z#O55my`vp8D-Hqcq-wVVJ{WT9P+~2FXcL}3@7ex~-}@-D|AC|3@83u_ZfVKQSlVex zae7PE&|NdS_#S@C^4p3d->hBx;FRv8wtRl=K3B=ESW)!s8>>Dl-hI=`L+eX>?RxCs zhSgKw|LJfYFLjP5uN2(b<=JuD2OKpPYT{y?Y0~b?~n9>fSlnUHI`fV(@YS^lqKi`wm_uMjfTFS%zp8fZX zd97^m=Nn&ojy}}!rAY@nZ(4lej|)f6j9j{+%k4uwcOI&K@zQg?AAI(sRqM37n$nlf z{Bc(GiLMV$ZP)zd&)?mYMn6@%lkeIgrE39ZC{o1yQoUSdTou;>tbSg*G zwnGnW{>uyY`_eC6xnp_k>xagF^WGEf_BZ(UZmR3~&YyogRB+D~`pRjSU43NkyG6IR z+yBZJ3y#m-R35HZ>gEKVth?%V!?S?lj_#D?Xd_M0)6{-<}@(?qezK zZ|HZ)k&y#l>Am2KI~>n_^S6H8jy(0?XwS{vFWS(1%}2Ao`|^@+F1@FQ#J?M7JNk0J zDO=aSuye({onP+G{Pv@9Z*Tayal_7z!yjD!#Ge&0j_6C?`Y(wg$Bs#iRNV@*n-WcT z%eX%LY~7_7Z7AH3zbx^|q(5-O94l>yipPx z0}uiO&6VrObr!Vkf4C8K zM-SJ4ljn}rTlg>V=U4OCKk=+%59D<{Hoe`TD|ht!rzK;kmeZM_uyB ze`tY%fGwwU>n$}B6H)tkKWrx>a~;F=64S)|N$|#=kRQ8?3BTPJwaYt;P#>CWdrKM? zY4+I%)(+B3z`8t{ndJ;fmY%4nCtL@s1-OgJ#R5DnDap;3OND1?EoH-MLrvUH{Q5w@#@1`PF`V-#Pw(b9nFglW9Ny zl9M-M|H@0w8GdH(@4uaP@vSGw!_TBYy7i2(|}#a z#uZ*ZWVF5Pv7`0<>sP%{wY$&Lu4gB$ITrc8TYYTKV-<}rxfW(_*S8)SI(y9RZ*K2M zwk>_rwN@|5xt^VU$*4(>-248p9!vkawf)4A^uafW{Mz@CyD!|-&bDn!_Jpj$ym5EG z_}r{BU%z_Kx1mc0?IAONaV(#4`06Vgrmg6A2lNKrZ?(-{Hij(w!AnxQFnx+X zFmZRMq;t=I+JCjpLLZz=N%h{{|9M*I>r>YWFv*(|c}WKM=@)IBx#0qRx;|B(+&K+K zb%TFcL!cg3uYL3swHW3d;~&4)ec6uH*UWwLrNwhzAJcW{#ohAsGdrK5Rxj`_aQM{a z%RGT`vLtyI1Mqa#J0|qPYDF!j82c|F>5zr?;joO-VHvfd-!dHTFxvkB#O7LG0Rm7i zh+%ouPq%OGt@m_v*SkUljQ#dFBp9Sytm>m*OZTsy60z2Yp1tZa$p_v zv*KUpFe_Ide^uDFWlwvO#4 z$+F>7)aJ*sMM5+CCz}7|_Gn$%hV_90=c>wrduG`;R=zoSx$Dgv?;7=W zw+dUo-qlqHJX;Q3wQb5*p)uC2mQE$TYlrvmu;#HFUpkcPyfpIR=&8Rhe16r~PewK8 zI%_ZAx%j20?tAO!lh6IK@~t;FZ#a^6{LbSSfAvD_iIe^bb^UJJd+DBgA3g6c)4W;Z zUYTAwEt*s%AAXJwx2p}s8=T7u68j!eTL4=Vd3(wI z!_@UudlDCM24g99vy@ZO2^>fuQw%YL6xa^Z{* zgDv+sFY%xE>y1qhcUo6*>x$;=edpX?v;LtY554}*r?cwv69tJMfqODYhrp zwS1rb&F(di+;a0<7mmpJ<}+&TI$+$0mEnR_uPrOgT*0bA; zhzy53XXutZHA-WSj5e1!aISUu*c@4KK+ziRq@U56kvri2H|E37j&!MwKXZSlsRQhP z@}KBdy}oPPkp}xezGSg?_@38yfAvm}{WZgncKBkf^$M@yevbZ@m$m-emG@6P;r_fS zf9RO~gVyeOVA#yM{)KtFuYc%~vEqjJzrVwM@?_&9-z~N-aPO;L^Y~>8CSK5Udsg4l zzwS%Bwcxe#32TO1Zpt1qJ@CbqZ`Hn%`=s^y!oPRibnEeNCXG5gy2}Qe*5~T_ua1uF zu~Fiug*gIgNB z)u%fhMNW9wJL3;sFsV!G5Zm4_yAR0fv-+3n>rS|)WXq$SL=nX7f?iL|U%B&^aK8`d ze(Zf`{Mu1p-|^M(J_E*1*>U!-Ti4CGI&v&Z*%YRJ^}>z?m??B<4oSB4DA zdG?Ead#2ydHV?Y#i(V^k>c4z`yIT%*{Q33QD=MQ|&z_SPwm-*S`1Ip;FZV5Za7wqs lKkwMPW1DO5uEQCd-mblO*ZPMVr#<<>n}dE|yZNA|{XZ)^Il=${ diff --git a/selfdrive/assets/fonts/opensans_semibold.ttf b/selfdrive/assets/fonts/opensans_semibold.ttf deleted file mode 100644 index 99db86aa0282e425450c86508d42da77a9f4102b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 221164 zcmbTf34Dy#{y%=sv(1{>GLy-knM@W$giIE(WspQ9K@y=EwF?cceXFXXC=yHUJH4u! zYA-_-Rn@9$sjH}~y{cNS(goG4t=p13`Mu9GlL+75d;hQh#L1cGdCv2k&-v`1&-pw- zC?O;mzXZ}cr+4>m9XEd1iSPwa6JndxEhjgRB=EZkpI44i(cOxB_10w?GjWXTq;0p} zeYzNuI_}4@j}ZQ&UcFONw@Pd32%!gXeekf+L&oiV=ePTWnD*lOf?-o8IZVsK(+G)D zm`{LaZGKQSE(V$i#6(O(O8TB3#!$@zk^tQ*Yn7KuElr&`x_RhYzXX zX=D#PALB_zB~Aq0*L;iPNjQ$H96jmjx$7Lm3E@HsF|2=b_=GWKNt)*f9d?M&eHl-U z9X4dmn*6?)AMmRBjvn&#II%7LH|}4H`yFG3j2@oU?S;vN5Brr6srk6E6DM(9Z$CwN zhl7xWq;V65k9+!!4Pyw2_!;+v5{5e(cJZUD@rMQ(JN!m8Y*~byDEe^*>(3|s?fm_+ zy2Dz#x&nt9!m+dX;6C-@x*9^XQTNN_=~}z;B>y$#H~%s_!|xzfB!oOhMBHg2DWpGc z<;k~%$5meVCs&RuL|iYraX!Z1^JmEjdKVbbsU%)4aGY?NaJN0g@i-pbj6J+f=iXfj zPSn>)F|w7+RWIhs9fWRS*Mw4WA36t~eu^AX&RFp**3!v5eg>H*CXp0j85t{GBW2=E zGML^W^SFhi6s@B$loa6FV9rIdxfLXzbK{;EV#2v{wDoBH(E6e!qD@8{h{o<=*ZZ>Z zTo%d3_rYi*SkJ#iOsW(zRxH3u^T`p>LZ*q|kR!rWv@SS4O{Pg4Il^5f1zbgag&2kN zeaR8kP;x}dK`SEDgq!|exi*4S2=hsl_%qon+yfUZBYO0La0shkPr7j1$a)4ddbdzS zqWH1(wZb7fO4tV2Ye@}%7jV_0Z6qVO?}$s7NbI7O)Nt*|daix_d|`$1y+*a2)Ufly zRb_k)yN92M`>&Cqd^}0Swar34xNIS@3Y8>G!20-eB!{NPoV|qz-ZCXK!bNci;d`6`%bt> zMl{la(V}T%e1>C2i>8gyg3+4wY~5`B|I=gbY<`A=KkXThg63@fq8{@y{4hBGN6+|K z;i>=7GhS!wK~K=@xvTXzu+B9K-rLt-MjwphcNH46C#?g04P>VP^0}VL2(HgpWC6S? zEJlO80A~&TfQOEM$N7H5!1b?}86B0mAL+#}2;X>($s2I0$X%0OwVF&*?F2p`pG*z{ z{g6QaqyV{Ovhg2#$Sji^Cc900g>M-B7!Un_=$X7LGRNed(KaCWO!k=kH|@F8So>OX zRD?BRJivIK@m<5(8eu(2t_rMuOkKiBDllCjY^Hys=v$nn#Fw_XugyRD;B`$^@yGoWS<4w3%3q6Zx zN?LqhTz^UGkMGrFES{lZ=M~vw*Kv-mQAz~7ShJV|9s)loybD+v&#Lwjwd$;YjOfCc zFrpW+Rs~lCeE?tL3Fvb?OBD~A{Xohk@HT78Jty%DW)}i@WcM@Mpy)B+iaoOtR~DT2 zk!tmLazwov-)nHM8hs2}66vCzj@}L3&2-Z@q*6E!-To5raR)X5axRS}oRCQJ#ZlmO zGzDjuh*~PfaSD!^-m#-^uqjrO#Q0H)0uxtHQ6q93sg`xk?S9b_oz?_v!yxRv2WAao+y2-aZ#646X( z`DjUKS!gL}iC8~eQUwo6&+UM{#4&{zDNMt6=6kKjiBo8S55||V#^#|5i3#)%6HY)@ z`wv*lOu%n{srGGDDFF4m+`u!)IS_eSWnJ!CT>wP|QS5po~CbuE0) zI;|ov;A@5c;4gTXGo-VG6Dx>TOeR{@H1K&m=)M*6oF#&4FOJ_(@EQZYG6Ba&r0;u+%&?i&wY3G~`1GEIFBFl`2Ge9Ck_)9Ha;oCyE#APG~sNR*@|Nn$Oj7W<+>{zXaYkHFEcfli4LXJTBSXZnfh z87AxENk5EIGGJ8|({c>r-?{3aQ5R z!BU`an5zLV!XC&^KJd!)8+f3xZ?M4uS~k)YdW-1}rstTh`9FOCM%eo!OrJ1)r|6sp z`cx`@au{q0r|2jGy$v5nRYbCmfvg{AOo{v>{b@9Kj6>f7j}fj1a`G;JL0DL20U9{M-Y zzlENn--C7^?MoaNv1_oWM|e{`#v%@-fp&x}Cx9Lw#J_0B5fFiY7X3$L7LiCE$tT^( zbL1pBO%rJ<9YTlEnRGe*3-!^TX+0OgWpanOkGT`vCGHoV@;tBMjl7Fr$XD@;__h2x z{xAG%{0{z8{xkk_AxP*Y6bt=@LBb2dQem0!p76f#sc>2hj;7Js(et7|j{YS2U(vrr z{}I!}p>xUhH`I)j}dPKPtrnc!^Y92m>R zO0mXROKf;-bZk;=e(d1b;qjl`hf`QzS6`3yIIxZa@)G$QIYXOKHyuhVu#T7LF0A7o z7pkn|Bdp^eSO;lb$6RF{OR$dh{L5I!>-<@)g9rw!qeK`W3>Fp$FAB@Cjw8Zp;Y>7% z?i4*M`laaO(I=ztME{C)5J#}X?r{gHJ%9$1ID$vP^q4uW;m z*4Nix<$Kg$t^a^KS^ohc=#%R|sP~cgK*J&R-LXnizgnIr&y}atSJn@!A6h?vJW-!h zcZS&OPS<@(G*^|HjeH&LAF}4#@^3@0KJzUy zF5k|$YWQ~g)u4ZNxpMo;PgibT`SHq?E0?cayz=Fhb5~AYIeul`l_^&y5ppH;itdW$ zpJOh|m+xQx_44t{@t0#ShhGl6Y`JW_%zyLUH)p;%_0>qkD&Nr zpr_m8{k-LU%6gZU6!+@cqo}Z;dw#dP+?=jmI(xD^b?nf-T~^!7jPy3GQ(7grY?hc1 zALoj7#)MkUCZi!pr`4!ck|^*TB`qC3Iyl$I$2-hEIms<^U3r6j zjv)>oIw8T8k1IIk8sc*dcK8y|4QX2hxE};d1y+<+vON zXupzjd|#a7@;ZFCl3&5GuOD?v{@&reBqkqw%g4Sbr72tE6p8J;VUjF&&`Q&I=#s)yZa0-JPDUb zSLKmDsjE+=Jkl`|tAb^A>~8sf)uIC?GIVf~zQR>8q<^`OAA)TwfA$t(#a!lQTmCXQX)3Z-ia+ zab111wA{%)5qY3WRaKtLkykaiYRG~5Swme8ldEdCUSBmX7w9I%Ion1!&5dL5fIq)XfEFMJ7kW|frtj~!%a#2(^FN%H!*!R*TW4OeV^*p*ogR~m00>;i2IdzV-Fg!t|iu3TWe zdWdhgf9 zjbwB!Dfgwg#`&zSE`Bb;2?kc~$lm43E&j8)K5JJWvhjhtd?~rO7p$LK#W;o4z4b40x9CTYZ*gVVl{uHdqS+^X`55x$tg5fzZT5svZ*r_bXBg}tuw;a9e`R^Ife39^7D;>2YIa{*-f@{$^H$dK#nrW`lm8a(sxNf~L8KLduG;PKFk!B22X3r#b+4#$ z^)BzAjD|j$5%CP0+d>LyVOf{tmQZb7cDv|;lHDG?9lFU*y#7~%2yA?|}NFm<1PI5>mIsp(#@6)=5ck$_5UD)|-c0SvGUSj7} zt}Z?rLUH>n$X&6I;&<8OF+K9aV-nI#ed6QtW5R;#V^l(YjKtT+6ct9s6y`<51iLMLM9TLO z+R`wlt zh1IUCza>wvza!VkoAHeQpC6WK!smT*fcVJEWF@|xBFD&Sa*(X2ZQwVvPh8;VF*1YP zr_<=q+-U9vZV&ejZ{j=ggZL?kWcKmD3l3qp@V=-P`-*$SFQjZ~v-G*jq-v`gs;W|5 zQ;$*a)TlN2nwgq?n(wsf+7a4y+V{2hbfLOIy7jut`e^-R{rf?dpp2kVK^ueqWoT*W zXIO0T8BQ5)8$*q)j6IDzP1MxhwAl1dv&($Q{D-BrWt!!H<#cdD@Sxx=!M|9$S*Kb* zw5e>JZR2bohtQDDA(KLmhJ0yHvX8^hR{O7^MWL^T)`mI5HiVrG?-9Nw{LAp#2q9u| z#LE$1M%p5KMQ(|FFG`5YjPgb;jXDtZujm%hp6EW&Pa<0RD*9Hm9Ak`e#-zqn$E=B| ziFrHblbEk!ZpFwBqr>T#=$PwR<=F1n?>O%G(y4Jybk23Ia&C7XaGpTa^<3rX*%2?nrzm@nqsx zi8mALni-mfH%n-i*{oZ$@@AFIrZrpGY<;uWo9%D*akGCk`=NRJ=9`-DZ2n&JGtI9w zzte(mVQ3N7qD70&Eqb)@wiwl7dW-ojmbW<7;_DW-Tii>MlI%&bNv)FFB~4A*mGpkn z*`!NJ-zWXiQq$7ba!AWJTE5%zRLieh{*+9T&B>FK@3+#oifq-aRa&duR()EHXf>tP z{8npPz1(V7tM^--X?3yH^;Z8*;Zw3xR;Rq0vOnc`%0E(mNcp3+u61PVR;@j)i&~er z9@+Yt*43>ywEk=B!>vDU{Y~qi+t4=VHtpI}r&?2wrGB3JUFz>{wL91y?JjaZ>t61D z-+ehPJgr;W+_X2-&ZozxXQY>>k4k?weM$P3^xf$nq@Pc}lzuIP&(LKAXGCPUGNxtB z&RCdnFyn)aPcpeoZDvYlX6Dq)nVIu5|7c6w_G1tNV`b|LlIJpjpA7f>#SJ6kI7(6&efeg&hiW3STYURd~55 zs;EcNf}+3mF!$)$V`Gm$dUowu*7M_@U-XLamE0@6SGQihdcD@Gws>IinBwP(|62S- zab1a_B)TM}#8XmQQc*Iw?dHeFk<*UlCmDhTMy)C?*y&Js$@XGx< z^y|~_`F__Q4|{yw7UbodjI+TSM-0c|MdZ?0nG;#4wyCI{ei;3J_DZ~_|2d; z|M_R|n8BY8{$}uZL!KJ)*P+2f`$Rcx==Uva$R9~IvZA3A*hh~N3UwZo5w8UwnryYDo^-RBK z)<5%)>GtW5O~R^{K@lY%wIBp^ZZ*2IxOh9V9#y9>K5EMHi;@R^0x z3pXv?S;bd9RyDHfnW{xqo2qtJ9j-c4b*1W;YN0x$IXuDx|N2N(JNc8?6R_K<%pF}udG_RaplgHM^}Ea^81y4tP)q5S4FLAzN+1-!c_xS zja@Z+)rwWGtlGco#Hx#{eqJrCwylm|ov}J^^<%3mS5I5LaP_Lye_8$4)o-u zH&@rKF|3JRld{IMrew{KHKW%|TQhIXvNc=Ryt(GXHGf}od97}3$F<|u?p|kHm$Pol zx_8%yug_mUcKz!0hu7C{NZc@T!-pHS8@(HcY^>V2eB-}1)@_=xY2l_-o9=FwHiv9Z z+?=_&X!C&0V>Zv+ylnH<&2Mi0aP#TSmp9+s{Kpo$C3s83mgFtzTRLv(xuqYhD)t0n z=e4lqJW-Kok6z$Kj_1@GfmacdlA7W+TWD66*==^WX&vk|J2TOa@ZD?oS8~(p=8OC8 z6;uk>*>mRAU!^;h=NL(IPq3Cpj)OCsC=KHHAXSMsD41j?kjpht1HZoP}yEc|xv_W-mpo*?XZ zU>=QH;#53OvfZarn}AD^<8-3Y(al#k=O*HpxUcSK&cqsnI0Y-eC+mENs{lX@%*nx161d>di@MP(&_Ne$4k|2mql4vHP+8idP zv=XHdkI|AJV)sM^#qlj#NcMQWr0?bBrKCu!-5%M?YbPm5W`fm)rnr?amMpW~9Uf{r zm1H^vVkqmwWh@a(vq~zPD?K4GJtV|#PE1HhPs_+mciTejs)R(dJtRbxhCYK@aaEFp z#J?Y(_xqN<*B>w2w&sfi^G@#TzG*|z;pI0=2KnT~ZUc(T=&@yoLN1&W^3S!%qI613 z_O97gdxC3TQ5Ej*q?cDlb>BL-U7<@p62V=~DvGC>dba&T%Ia@Q%dm5$fp;5Cnq&Qs zd0Hp8NNO1#V~ZEH#H2OF#J6ZErL>BCDUl{7Ci8=X=&m3d6x1@AZ)s6kgwR+pGiaR6 zxOu>Mw;8{gpfoI&i3<}LEX18^Ho0OYQQ_`%lQT8s&rebprS^7R=FaWXj(+gUU)H`# zvp2m)@3!wUXHJ*)^n>kN*49wZ`q$+zYR`YbCkbTLa^(6Gm#?_~-R-aGiCeW_u3AZ( z)A$!xUB76Q*a6%l3@T?cB5E{=c83({iR34V`{!&e6eR*OjjIy}oS1 z!2$A~Cr``YzA0Z?R@(bZf*2XPf{s>jU`4SeFA5yf5sWDzb4<4f@%9RUGu2|2tp&I(> z&O>tYufNI}Z||TV;kh00+|0)3YIVGzLWzOVAZQ~~)rlrK`l_jp1+J;D{B3X>-`kA^2e0O{eSOeZm23p%AcZTTEW zj~qXa(Ta_tR;(q|qmu~1D)Ct05j^i*Z&vVfF*~+8=(T70uhPumNb53R?aRV$)dHqcx3sJTXv2rty)q=ts ziG+n}Y(2ah6>sd}<-`0&(hq*%NhZz}3rlKor&_4;+pL@svVN=mwf49Bztz?SO`ku1 z#*F#%r*jwOIr0+v934;R(6RC?d5L_!o=^e0B7v%88St+M{Ca?+B~Fit2(a{&>UDyO zY9!S5GK~hS1PNhW?sS>cG9^isNZq{thT7isy(x6(hrI8#VWI6dtfC4&;6-3fCt*d~ zc*0fIaE>!rBZR0(v$luVtm48c4e#k?PsW-^R;Yq$zn;YNo$0g_=T{u6#EgI&AgNR~ zr;t_aq|;sT#RD~ zTX_R)imeKPTOv4PnZ0tSDjLp}?shZ+3~erOTUYpe^5^ocUtS$>X7G-hgCEbFO$RrQd}S)o(l0A-k5HyVmP$tJLS_P9F2#oq;1#a<;8J44y~?n4`smpofLz zdlEI28gwebBBE4`w+2(uB7!-jVhc4|Vl14+!W&WI%m@V!BW1tq@eum%hxR9Ly za&h1U30;zk3Zsu*tE=EPUOOiD)v6;q$g60!e1vAd#eY3eultfY8!e!?mu*ND7S!Db~75NC46 zf{TKgW0R4=6 zT9Zsq6t6Z|lblj&8`11^CMD^RDC^}VDqVOlukPX1Gmli61In4X+oHnUu*J*?Q!F*l z+!e;JBbEWJkzqQ z;^|@2#S`znbY))O!;|0o@^9}vbF`><&)6;R-rrL>aq5VY7qWudRrA@y`lOY1O-Y~J zv(GT55t+4SbuP2cfB3byv1ijH_jOpby8hM*7tcTa8;?;0GA70bLLaSJH zlb`LNEQ4Ll)qsyl;DT7>R>2otv z=Ool_u$FiYrbg3(pa*a=r$e!fO)ZQ$tugXxG&U;>3!2&-e)Ad@{6N=oioJXT^GU=^ zQaurR64@Pvp!hQK)2$kS|oEWeb$jra?udVIq?ZCc0EbPC=T+SI1- zXX{+trAu_@H2VEf( zY;6kNidoB#%AwQbQov|J4aaE3rX`Th9;Y)hf~bOtAvjWKmMGZmZ~@{>CT*eDB*aCR zc;gzJWW~UxAOLC_3qabKfHnBXFmryAODZTATT@y@6jw~m9XE2&)*fXizyI)hOYi6b z*|%2Y7xn1Yt%x4-j9K1uU}b(;zl;Rm`1fBcoII*e_rWE}@{u*Y^1Jme0n}sb`$~t! z!z7(#lOj(-1Zi(=rwYk1xLOf|HKbW9sk29|>u5HohPG`h=yXXjseA(7Yf)m=6lOON z#(+f|8Ab_Q{b7tENQn*d1WzQy&fBbtFmWhv5I7seE;Z98xf}$ZN}M}YuuxnN&Sbh( zI^6H&Cwon@>f5~7@8x%XKU?&6en@4n0gGh$)${VP?KFeNUi$g7f5TZBdYLZ1e}VRX z=YH+}BNlyj{;Z|k)up%QmgV>C`PrMFQW_B|r-Z)rx6Q9pevwap`ycYx^6`G#`qHIz zIQCE0{9~{Dru^y;H2$`E2QY$cY4%35>C5Fg;Bb~(xd2;ggno09?w$mz5Un$XhZ_a8&M3HI)nP~-fQ?K>sEr~o z;f>({2%aR1w-nv>s9(Z>Vu=_B>?>kvzY0fwAmE&s&4F)6=pNdN2F-nT{WAI1Z*@Q4 zzP`F@)z;JU>UA5pi2HnpXYB~lM!mlL*f)H?K@*vVAVGsr z$z&E0jf%VwROA&N;HNP&MZtbZOgRW|g3s!9h$G}N@(c14^g}v;&aIVgr+08B?gx3b zJX_o+FOXm6g6>~rmKn40wU|vuI(i(?qFOC991CwGO_3KykmJN6FUM1Dk(WN0H{dS@ zd__hPHakKcrSY}3$N2Vjd%48A3oM-cM4oV5#@hU|-NS4e(iYr^GjO|kt&YuQl&FrE zur+A$&*(eB$paJ7owxWb|14~d%#&;eP)}?F>V-4!EtCsZbL#LQ0s0G! z1;pxfrXsIS5JP~>2ZVfhIV^TV_C=9o2sJ3_iX}D{cx0NLyqyc5`^#c^ue_G7rWMyt zmF?N{qx|!4*C)-D&+=h)u}N`sAsvAl#HHmQm&#w(%fHG$L{XHCE2|f~D7bce!qmt# z!PiAPMjxc+i@a*JsFirQyG_MVNs}pp=wCRTT7;Blx7g+9x`DTEb6bDrR@5QHuiL?) zFkSJpxV6d*nVv|I)ADMaj^}uNkVcS%LNB6Mls^{wDT$;NlQE>O8hm~~9n&+-i7+xM zvz=R8x5ww>dhXh_u$_?7e&NFQ_s_N?w7x>Fq&qN+o@EKNyh>%j3JCZFKA9r9cp_{7 zlT#KsxKq;swN+9N?NZk1!=KN~m0>4rzl#g+&AfaofR!jb%|OyUkvcsk3^VW#^#&38 z$$+;RMO_obuoO%q-}xb?Dg`eYnbb*CVw8MCPG5Zc_Rt};nwsR<+qu;f>n;IDc~6g} z=j2ZB`R5cOFsG>GInb#jih@e4Ai(2n1xnz}kngk|xy?N(?z?Y4<-b?jihHf3lPAWa zGZ=!bM8m0(9F;Ude29&+Xn0Ad;)wz2#cVgzsZC&JI+f`#CNk7zv9T}(g`P+fnA0qo z2${3wa<%yaEupI=80FIIIzcUW7mmq4|5TR+5GD)N_X@akqv^o-`yB(=n*(T=KV;Wa zlZhZ_qf)C$u!YyF;e%0i14l8$`5CGa0)Su-3BZuRflT5Y`C?rgwP?5it#(S{^cRK2 zoe!?BQ)B9BcIqtQWTvB-l%0DJ$Lq0DiG+q}Y(-uq&W%N0{(*2kq@$R1Bv4aL<9P9$ zyg`0jeoNj28&*j3XvO_)Uw(f6!WZYixX4|?wMmeuQTRc{sJvdjBmY3H)QrN65cx;H zz7!S$16mRc9E2H(j*)`ctU3Xrj`v|Ls^B6o=+TgUXWFDeupsM*Zpx>9QO$Yr%6UKL#G;Z3-TYi2mDqVvq-sLXbYi zJ6Bp{0D{7byg`Dff`l*#7)qGXnLbk7VSlK|cmY5l>je`VP&tpH=i~=;pnO=qnfM=Z zbXQ(kAkU}y{{>NgOo>`xN=#Cv0k9hoW@c;*lWY>1qu|^A>gug8Z@!Jv(g;Z4w{(;Iv%HlzJp0VEPu2CWJ0R}+ z`{(lQNp;h>d~k3D?5!ReJC3BmqbE@o(PAe;LcBf-aSyb%4f`7pF%$vu8dQKnKUb6d zgpyPD+g~_dN&pwl33~bZ@4s)ZxH4qP{AWKnzKseOKRZ)&bls$83y@W381ee7pX zEDmZ@09PmqG{o&No5l9k@*n$w&(D6Y*-7!9h`0qRXm~>qa)e0MK_xI(uMv%kK7tx@p(!D6rojC!lUkX(OWTBIsDm=h z{v=-Q#LlNui;lO(9D2Oj#57MN@pzn+glaV=#MBXyL3&Yd3XK$_qfBBbuZ^(k;XU|u z&_kL~QG@|a=u~`5IG0Wy8$B%M&J0$1bdn_3{%&e5YLkt3>#RG1Nmw<&~Y_0qg?#j31P_6|c$dsFs%Ehm$k8 zzOcb}x%cb7;F{NUV78di;1Fh2BX4Y@9AZY;H4fT9t05v)@yyaUA%YS$F;#$hAWhWC z4W#|3Acy@dMk;5O9Gt~0(OUm>-76KR+_f(CYY83ry%9o!^f6k#2XoDZ%9D<)jtjI^Q2iG?6IIE~FqP zlt`k-!m*j*cJeIwgs6utvudF1KEuD%*I@<5|*3e z5lE%8$lMyj_fJt5Z=Lz_ewhmI4Xf<4F~6wa=Y!6DQFm|Fh9%qAl&>G&-S?N*cdDiK zqeiC2)}*vKaIDV$($d+3C281*f)WOQ4d7pa-I-wQFhfgdLd|?oG#><~)ag*0CFl^H zjac)%#3V)Jd0{*KfgeC;urtC03^hx}(^QL+_)m1Hm>Z1n&z*tnwhEv!J7nT6o&N5} zGoMW|CHZcsIqkSjOJ;Dhmd%(gjDR)&7gXliHFL1bv!wafkXPP+^+VGqZ+-L*9CJ!W z)ZgUy0?RfQ@dfd`+QQpIBpm=U5fgxG0IN~Gi?NCuql5+yGn*cvpTv#0FW-k_!tGkr zZPgI@%F?P$i?WwmX*`?=J8jwd-FEVvgYWb_74HCMFsD!k%vk)GG1)b|UT=uv4Zw`X zOe8%q+N5v=gy1G1{5fXCKm=-cCooIl0(}!xv9YXdNCG`v)ambUocVHs-hA^wbKUq2 z%jR+mmOcBz^H$oD8mWn<{AFq`UGc}wWv?85dB5|l@5I3aM*=Wr0WVhYUpG%;m^KuI z>i zP`s{m;0>~%gndX*Ik|K4otyji9eDTIr#n5?tGGKg@GsR4=3g3z&G$qO8^&~j zUA786fvY6amUJZ(JROs`_)cP0ygnv1xMdg-gTrFtrQDoYwYozAV!e=Nkr_r~Mjo;+ zA_04jB47OHPqQbbbj-`` z`{dQnQl1Ex!xujL{-Gxp?HN9G_>&cX8~((IkwWQgmup1U>mRC9vJ(fa8jY4{ z?IA|gorrnfV3Uqet&N#v<}NF?%dZR+P0M!XSZa+0FVF>01sQOUgvmFb7`L+e#tpr( z_3IPpa;|39bGy&fU4+BHRJGX@6r)N}af4K2 zRWnsvRJ&B)sBWuND$Ym&L^d+KfsONq>D_#jol?5u#*II6J)LrMJ9%=2QW~F~lat*c zHbl;7w}m1ViKl zOu$6QZ!xeV$++~Pn7SzpnWOS@x~;zPW?lmvvNi0WWruL?e$?we)vyML{Fq;;?3p7+ z!ts)5&;$28A{8w{Zi8AS2wF}@IHMH6zfz^s;Bo^9MOYARGhf9Yd#h;mJlc~Q<*xLC zd{f>u`-dO&T>f@iA;;G(q}N8t^CWAX<~;K%KzGV)0#8Cba7YGQ(X8v1?&8v?kt|=jEGNFTec2lA4rFzH}2d zh7gK79cH#aDa??6{C&euv#9m{&os35B7(P2`TELvToSD3nMG9kD`M_e@=5ugJR9%V zPXAD`@X&iJlodNjw#O05a(Jp}v&!s@<#hzRk$Kn&QX8=u4Flg`Ndpqy#J*$O7PcWa z(WOwq9RiZTM!?*&UATaOPfOq~d^X8oxN%q=rXTaw>F;jHzb~3SYuPh%=UCS)ik90; zonj`}D7GH(@&~u=b$#;I@wX4cmj#{xXBpts5eGaGM|21u9v-GOh8bg>;SqLYOo-lM zQRR6pCOygX>L1_?!KUJjG&mv(po){^XBCq@V0!^_CQPpxTOBTm8@O`zyp_+*J$mZ< zo2M&Z>8uVvdJ{?2%9_{z8h>i<@pt5ThhWYO_-WIleAyo#(DN;ahQAWvAfDL~P{?Cq z9K>lY;PD`>O~kqE)a)!4Wi}GB!AvnN$k>>>(5;m{HDmFv8wX4~yw`w5 zQEVlsWRK?fr8mF2^up1a3$4cteQ*A?V@G!uz4^?+Aulg{wgYXy^{-t|_M6k9ZHI({ zl~a~%>b1LIR9b#^dig{KSz`T7?q@L{eB2TH?)qSsy49MImIyL>G#0%PWq7cbc-#Ad zpQzN`u~NH$XQmj!c*PlWAy$Sd&ve^ZU;-B?r*GfH>0RVKYql0IqwVEmeRf3bHrwf7 zuB@`}k9YUf`TD?PrDQYwveC+WAFVxhYBpPSYO5MaJ<*~u5}RnqYjm&!v74V1iU2pb z)yyC<*M|9G{9dQN&0CXBd~~aF?8@q!%X*X_Kgpe|>pOGi?lWBC{he%17AfXqP8}pT z7!;?>UD1k4jS)6yV181w8?v+k?Teft!eloKlPTRM_y7G$JH1-d@yb29pHNyiV{1kJ zVQ!B9=~fgiOvKZpkgs$`5j!?Z)ha_oq*fzn4E9JdCYl7}NR z<>MR-W0HJle4Pv!zxm|F?(e2>d36WdeA0IMCC=%G7GV$kD25BSCmfbY zCM8$gX0@jEby-fFEuZUIke;(6w>g%*_=PE%o45`4Bji`j2ldA)+59>1UaK*GV>FLo zUegfGBcd}Z(R{v_SxLV?*ys`YZClf5p0BQbn@g$tg}2pR;@r#lpuOAb*iH*cMl}5c zqUlJI>q*pwS~!EsW{c!PBl+kkGshYEnb^(V#lOd&Ms|zWhKA`_aUSA)R%Y`cS;Ty0 zzqg#`OlLd}F9gmqEky8+7=1*9F??qD((qm3?}eWZm%_t?!Pvq7X)W0Fh2=po znT{Q5roGbkK z6F;WSOM8p^*6oz9RFu8fXE-1n%(WNV@Rbl=k0;KEK*S*NX0xu;i^$Q;X?U~bk=SOx z6oXf^#!3P!_e&y7m$8tEm_k1^v5Eqvk`U2RI?Q2+ohcQz$ruaGOAAt`cO15+%armt z-n1F*MlS0-qiiO(w?oJGo(hl8?9}e?*cewPvwZU)20Mj;inrU$V-Ywl@C!$Y1o_L- z1Emt6GMi74cQ~1Dh>^c!SMhR>>~zaFsI#yjzo;lbzXvz3RxP$I=-I1#ZdnOdyB${L zE^@e$q`=eM!09+KL@laKktmxIIS$1u1iO!j6*(cy5ZuG7dl9BjuR`)=Kq|{q98_={7kH=aIz;?vD*=j1J~T)ybVs>1n?{nTFk;CKuT zy(iOX$BwOH$3yK8ANgQUbUa|p2Y>WMrA-v+<7pL+jWN41nA4bo?V(akv@SF(w3kTHJ#}`+jx(pu9yV#{ym>=0hG`j~PM877 z3?Ywu+(c#KbvnHQwZ*0iwM&*@OEKH#4~_xu`QTu^O=~b3ioGhMQBQ4>zM-x!fZqVJ zn_}BvM~@txV%dReydt3d;0%{fJO3(=zbb!6!{qO-$k%9ueC@J4SdC^F$EFmvw$dWdPF+Us&|?YE%R z#QHn@Ldk_X`Yh7J(=yGT5YdX5#niA&mW0sR!y=sO_U-tvOlxWjDO#;IcK51jbX<3D zbQ3?b3DKCgtmG((TP=?m0;r83~yKCJ#x@%W2#BiNYt+O^*Y6@yG(N z#$RG%mArUsMvtmK3o3b0tENFZ^x@Y~n#9Q{iuYIlK!?%zuC3FvJ!!4G(uMfu>EdqP zRh-%>vr}fer(Jv2XJog7X=FP@QVz6B2(q9Vhy$DP#*~;uyT)j>$B1pA+yi>nF$L?PpHYejn|SFV(zGov+o< z_?qqVS4;zB;RT`<;>W!StOhHSNqV3F%dEVmz`WFS&K1>aO1JUjYigd%&F%Me#*2%qs${v_=)sTo z=M6(LGe(Z8goVn_Z#yw>#tgYL?ZA23l$Vw!F&Innci)`+739~0*jrD$qz&Q(okk-B zNrJ(s7uBd@gGy>tNCCb^LX@hI8CAMcT2Uikr{Oj7M*0CAUc=giJ_#H5h?20SK(K!=2z;qG1>0PKvN=}!&zy6Rnw0`Og*JO?ukdFn zq0{yd{I#V(eO8GQi^&G&)0&9L|M0i4@UD@oD3OdSuX4r1xrC-iSRI!CWL3asc=9;)C#TEs01Fe zL8A{>R~>$TLHWA!bt4K2MpWkKR|>P|AAP^7`rXIYdh;ru=vFiW9y5n}N6=rm0`23k zYh!O^=#5mZ6U`=lP^njM3A~-LrODeF4@&R->Kr@)da&@&MblAP+2kb+c>;fyTf2v@ zkw@Z14OvE!CAiLwH!Zfqg9yQ1Qm|yUahx8pbEsWoh~aEDiUbJ6uSs|S&U2ytZs+ykB(SiNJxn*Ix`>0+*6{*`f~+NWidPn$Y-Lhm&*XR|qzxh!rg z=5#>=#MrSk9wF8)?W5rz`ft1*asC z^95Xt8r-~+UIPam{OihRmd$wcRD463PGB;erR0=|p&-qNB2=xu`kqbT{EbSl$~QZ5@v&6=5}q zy(S~}2}R~UN-N^EJ7PmspE^9utTRYbe?vD*>y|i*sFTB%v;|ASc>kqwG^e*ccxhGD3U+Tm#JzlOArXuHP zB+1yXC8$9Xb?}p^s8$<91FEJBc&mnlqP!JvH8$!qMY}NRRdlQ=!|fENE_`ocr?P*X z{PKG)N3NA-{xO?(TkhS*UM^xh0<~K@5V@))7 zuE`rX1R3QW&{<|cYB%cH8vuILKt{0h!N_k+TKvTRgL^DxPt8{`> zURT3h$r}2E+)-X%L&N3kHTVOvcDZB-?N0{|l#9b3e1&a60f5v7SWD#W+;&hZflSBC zS}Lvs-@k4@(Y(oXW_Y^k>C6tb!r1)4*g5{OUt%no#Baq|)gI2ohO&|Hbfik?0`^q6 zu;@GRE9&-BiA)9$Xx`+g%KucXITL?tcQv9u7Cq#95+Y+sgeo{VB9?F73CCmS5sR0)!$Bk-=gn?ft_wY2p+RXtu7uqw6N#E%!D_`y!Tr736=edhV)9No=Rjj4b_RxfGNj;O zvsr5}P&L$yNT}Xq5p7m2YI{+BE16JJWHM0+DaT+5g<~j9L3z-F>RT3xHty^z_0gz0 z3WN+SJEKGnPE0Ir3S$*g(w_Ql7JH}b-ZgTDKXVT5nmE!F{nJ!(& z%?5U-K`)~U8f!`bDOBVc4)0Uq{1G_hwF+ID1?aM0!5FnQVC>NmQ%KMMK7tn3|KT6e zh;{!n7}ou>j3R=9b&fh4v7QFRu2mpu>4!xAhTMVE0nNy{;2(mPsO%o7RCbSDzMLMWkE6Ex zk6({bw|wd)&Vu^xwen1E>~U_UJYPnY8`a3&kIVf6bQ9;O7^k;k*uon2_*WXnFUu-#m3~?@$d+SaX%cR z$VrS~5|^wDNrzRMLk;-rrfXqCB0WaRiz*Gv4yTYopauy`8K7t_rp7bzQaOt>0O<+& z;0#nqcAp{dr@7PR{qmt1+&P*zQ$9%Zrpx=}12bqIhQQmMR=*cjowbnF2>4w+J;~VE zh!L!jRuZYj9|q7G#rQaTbV!Wg3^Q8PNL2;}Ia#GAk9yB0g|CE#^i9Khf9e8+^=DsL zC9FRy!>1)u_+@xw#7+^RasGI=1L#oeTsNLF=E9_t0 zP#jybaNvs{;_pGBKDKmr|3x3mFJ4(tyR!qeQuB9n_|o<$l7-wVm4^y-+Xkqcso6p9IXu1@4O3{Ui zI&7%&b=%xc>wK5tMT{FYw{IV#D4nj0nfJ~c8{gQ*tFQhlpBDH1a#^-Lw`eB3Tvo>< za;PtHlg^&lcp}Aw8CoXerJ|T*F+D9T-rOeH)}~pWw+%7d^S$PVtd73|>p?QkubJ6< zwTcb3W4r9(EKZ`oP6Js(|K=jx$~5*Wkual2mwp+^S%dmN*7Ebe9Uk3oYuER4r%kQQ z=~n1@VeHHoZcuvr3IgD31@qjw?INSy37$@a#&vt;jm{s(w^`G%yrBEDW!WRsGyAyn zOP(5ef1pJ||`!~7P=77XMdVNaKf4xo%zgMoiAG%+> z+wgo^`mJ(3<>Bi$8?KX4zu`Yef~0p)1~A*|hhSsF2wDs?#74C6kASpdgmeHqnh6B& zgOZ7!Y^O0qNKOk0Nlv%n-D0gRJXy?YYjnm13CRUsL5K@V3+e7nON$FKx5@VgsX(wG zQ*>xIZ(Q?yZ*&}p=T2ftY5ewcQ`7EYVg^cYSe6b&LrQ7|u@p1{|t2oN9y2rWY>2@paEhy-aWA_5T+0Rd?uL_nn}Vnn2gh=53wwIBf$5m8xX zSr%DDR79%ES|D@t{?2n}CKGh`{oa4SXh>$}=IPJr=XWT)$;lJKNJvsGFm1V#Lcw*g zJ?Tt?PZK|08bcqi7Zwf31|(?bp~O9Ku#_TWSbKbgf!?Qc2|rhtFbrM zVYO>~HXCA?4Tj{R3WGuNxdA3o6!DOM7^XT-@bL!Jo(xYEXCd(XTVLA@ZgS6T>*a=c zr=(tSE=nWv;>xW{$~R2=)j#gkcYfvOpic(&8}QWR3xnQW`SSJW=RQCG*#*ze7uzZq zl~0)cy9>-RUVd-Yig{ByWG^e|w{Xscr+}t?an_0rt6x~Rhwk+zP|!*I-jP#V%gR&v z+9iZnH#BSPP`P>nupzkj$^Y&1$>aa$=d3q^!SVNL4gQ|@&)a9^5a{uFQp3;bgsArfj03+pgVf!Bi*|=acBkRz#Gx0dH|xJVp=G_*^OYLj zU)}=0d1?=1h!Er6g{U^h02_wfi;rOlAH!rk5g7ySCE0~2O3VY>H+XKc*6j4e$u^ta z4uWd-z=0~*<0UUv*KSDcQDKPUx#74kt_rC!bBt_U;pkzXk1RtDolX;uErP$7E$_5` z%%?wGJa&4#Rj<8tNhh(`XAoSZOqXf~_Er9lY)u3ZKUX|NX{#5M@`ds78+N3ByqnG0 z_fB{=e7@>z#(eyz`I0`XJ%tm`^;yg%XUJj{%wSH~(r3nwxln#-PI!`1wCaQ6lV7+la`mG>WgIMp1H$w-6s* zIY^|MQG6wEOwmUPJP>^CBU&$7(0rkFV-!WShGILZ6JNuSZU`^KGQ6+yo9j5&#BUx7 z6dLTYDYC_7@n%Sp)#H`n){O(k2z;VFD_k~PvMt9Zxg>-=IfNLG){hW6;2fkN`$*E- zgoOHtIvzBDKs9iqdhawYK-dqgf;L6PiD%@gPE${=2i8k9U_37*cG|_*Prp0!uYW&m zmaG)&cX`#Snr!2^CC|*AvvS6CH*_f(00#-{j0>9%UB7MH`dgh4IR5h1)K50Nc|cha z(l(`9e%c%J_3Fd*cbp7c)V>2XhfX_}5m+B6ZqXbFD-JsYop!Z_(z-fz&&&;4;HO<} zp;YBD5gwMa~sTTm4! z^uZ&|`B}wi!P|QyT0p;3Dhr=gwFO!^wS`jQtlC0E(^Fd@I-#~u`cK|Mw}vgyol{%r zE9R&zM6`I`0$(|5fmRL-oJP?n(uUH3^03u5a3AtnGGDpdMlZH6<$qTk{yVy9g?#>S zFQVn%KtSdz7_kj)BH2c_87)KZsCo3-h2rj^J=h@a

2*ci!cGMkX>Xb0M%)u$_|@c9f*tE4f6lfc5dq>3*Twu6#{7lQKR7YE7M zxITHg!0=1W%atH;XbSi5r{wG!qZ_CLaBs zBs>rZFv03@$G|{@0C=-YPDze2Cb-QOb5E!ymIPY@Vuums{6@n237;igOQ=iG2nqIt zlmsau!H8%mHAovbf9TK&AzdXLJ`uYAeAEp?pF?9t`~=j|hQafzR$XE*UiUnnc#X?}Tmr`v zuk&-l%;EheE8b2{DbzOl)H&4s4pWM{ukpliPASwj`Y7+IZRo;nxbVc^IjvCJD6O-p zZG>q>9sWXmjMECWjnc5LAcx!NrDRj)JdP0BK&o56@kGa3DA^Rdk9SMdcVp>YoOxIt z>3*pF^+mlqenwTwLiPfj%;oTEMa8(QX$06193Z|GJjPuvr}mW5@*eE62=0S*NB+I|7QZ9S)El7uUF|gHDv6^Uv2%iDn5oNc!W~$h0?d;#{qYiQ z(0n@44h~g1P!59ncQkwDH$HpbqvkF3X$CINitE>vKJbaYY(}sh))NXb#~-jDBP1P(nfxV38b4rJO!cq?DtnJR7Fl2J$%ZVO*%lIQTOTm6JT(=AcV0U^L^*;AJ~wh-94lT6 zu9>@fuhQ!nmWVtN;z*2$@IKOkECT<79{99?`vA}aqd2l0U0>aBB)|ZL4p^WX>?lbU zLvQPoA({-Nk9W-0j2d?6@{qxME=zN|RnH0z5M$d{Pm(f1D+9YTaYSx+h79Rf_b|eZ zutuPS#1TnXC2a#Ik@he#d^hQ=BGXuHgP&FPe$ZJ(wuSnaw6`PwqDRPTN7NpDVIJJD zM=dLXj|Tlk?gm0nHEnPoGch9UELzt6h@s)mjHYn_Tcl$k$pssK3^{RZk}XC`h&Q@y zUL;&Nqj50E1sg4c;VzI>KnO&ue$i|L=WL-SuM!N*%C^^Yx_c?5Kj}NJg zz-)?2DkA$9sYwy}kbC#SU>y1#=&Gkf);rFs z({;6lQsJQ5LPQqeEpWQ7woq#3EqKExM{R*lpV~rymW>v;{g599vM{P`(D_r_=s!la zMX2U1k|)rLE*@wXZsckX4CGh@o6D6L11pguQBF;DA2`r_F!2E3?j1P3Oh>e=L z-Hn>Nl7LVV*GO*F62V)>W^UwmHcM!Rc->~rWTUMK@-B?VOiCyce8}*WWf(PNQn+Dt z;q#)O(U$kjs0T5dk5ZscmMnQK3TMA{*o}2Fmk$t%g?FKJoRiPM^Oo>l+&d< z=yVE`Av%Cc#D&imQ6->h;M|}EPL)=29&)$RfiigTKK_pL7ATV{kI+Q*2)Y#Vo<;7% zSZq>deUGf>&BJ5n**&}kf&;>sRXtWUt6>bcwE%zTk9^jw z<$q~`^?r$up?P@LBVm^TS_fu_F_2%F!DfJ#?}4m>ydu1hp85Ou@fSUo)cv6L*yO+U zShAk?7_nL;g31GX11&?AAu69r?Pe++C|d~c-l@L(8oiqcUNV}mkSh0-)P1A&W(oI( zEF?8CXkAV5QH{KI-?cwWHv+u_pUI@G5|kJIz3bcfF1F( z&#~NZ^WAdMjv~wOt@_>x1BBv{ISvT(DHp}*huG$0$CQDG&~G^FDG?alIaY_yEyu?r z=gVaC#v&};=?=uln9OEVPvrS)-BzEQ{7dczSx{kFKZKN)ADs_HsDYt;C`5o#C_27F zNl_5}A^eLy`V7sO(dG5^RaN24D3+?6<;hVyb{$#&4bP7HX8pl!w7#m3kXF4Noj|Ou zdTUt3i>zAye#H}m=mfHIC*REoFXt_AuAsKiM_8fmP(&+NTOh8Ww$R7VTZjptKy?hH z->NN?3QN@%RR1AHsoF0|zg1f(P30|k8n$pX(n1-xN|Ak19RzU&wGHw+scn?uK+zNG zFzAWf{H3hFpkN&IjH)JwTX~eaMAy2y2*R zZ;c)WD_O!@u<=ole1*@=@cx>G)PT(>0XxQOk&zeHqe71~0pftFTBiz86n99T1_bPj zIjb)1J}`Go{!q<`{kKNQ8~44Fy(0-N9t0KjYmP#m=oV-cXHH7eOM0U#K?CfE#JEJT z-?%tHPr$lu*EJB^R3`f;k`tCF^CIX4lrBKYGTgjpXZPG$+_`gEkAnv{?kjz`N&7ns zOS=SbDQ?d`=ivLLmnL){|NgEd+xDb8@2=ccTdFK4#2m=LCA!UsjrPF;-&}YkkZTa# z2%yv>r9rDVIo!UOL{p2Ln1IDq9AmYn_pWe5A#CbHu#2y$uc=_QTSe>My8QvC#a?W+ z>S4f0pl1_g4oH@hJrr6+_E5^PfE?i?K_ZNFN+N?QDZ6!ym#|==BnU|&U#jGagq6A? zUNi)NO3QnTa_!T>0}EKAX0-}_L~Ln+LW{C?N`j?HsA=C(36%hzli z)A^RjDwXAOZTkmDO`i%3)Yc!4%_vhG@+?>4qC9Kn(k9A}xgeIU^7FA6swWyNLRc)# zh4!#EFAI3Pwd>rf9+jn4yUZrK;-cm>?aoGPar5SRO>{4Er9ADu71;hn}{okz)!Mxk*(6FHs5MBt@P0%l0_fB5(Hr#9M{ZaQ7tr}P|;_&DbCxSO;t$OC=)q`5zQ^J~c zP?AT_or`Kd3+~UOuQqL}@4R#S+Sj%N66S$1O`2?K(c=AmAxIeA=n@-U!Jz9irqLyn6tD zESv|v&v)=1n~}NeGysOlOb|~nn_EP~YzPrKt>Snp3|S4sXPQ7%{j~nbl$3f*f8hRU ztKTnRazTxJs^{4I`^0|uz=JihQEgkOZH;WQFoTZiOcDSZgxMyFS^aa{6ltA`+(jhN zBSr4JnfJ#lwO!s@z3|Sv=W0{q=RVf_fkW|whmP!zu`@r$zD`pGy#P2yBB8CLNg`yB z87OX$`NdhmIhv|%cvi-<2eo?GEs!Z?LX8}=WVe}SA=zR!NFZkUNyC6$ggoRXiIiLe z_%3nSOS|<8G)?>Uf8ajdQ|A5hsh5|u$d4&3czPYJVYU1#$Hy=MBT1_UL<>0~tPP$4 z6>-{Dhk-3LQ^H^tu&s(C~!#y0P$d3V&T8Kdr-@z^L3f>vWlu!Idhn^l2C z+66>KTdaanHd-a8LmYt}Lg;mLF_e}qe2Du{votVILku_JrhL z@DmaKOJ4T0{IFwe{_ZaH6DQ~*TF=ssMvij~>Qu;--b^ir!Laz~!_E2G#rRf+A7e(f zc}o7Z{6z1VqJKb;k%WuLIoqM#g*H4w3Rxl%OBs)_0E01JPD_okP-IvNw%Y%4G;OD#_X5;;+&me-4p2;SO zlg9F=XKJvdPw{7(3O7Q}{PVVU{(;!4L_7ogNiVgPE9#8m!#%x$Ie*SuLBwIGl@HZc zAgFSiY27~{kCsv^4Dn-pENUwZlD+!GKY{&lLc2@MVDot!cPQ6zyUd_VOr^_tBu|n| zLjG$ltuJ0<281q+*D!Bjb?J3FbT|#2UsQt8qKX6nt_j&XETj=_gIeZy$mzjF*ED;M z-GVud+Jbdhep|Cw)QXM6ZFA3`mOOd*oJ*p-FG!JU--P9hzO&Ic#f++msA{|laCN-0 z-G~fc!U2^q2tfW=R6NiK7ARSTZnp;U;XyhOQaMf*{*6XTm3svDOUM3%mb&Jvf1W&j z`oyU-Qpu4cx5twup>?EWBE>5@R(>up5*=K{eS-$bL@N>UAa&XvQ+eKrp?axH2?x8Q{?f znh)F9{=AyJ;s!A@xaSVT67DFMme*EF@7Bgk!#Z*Ax}MH5~?7SW+f)udk!PQNCPlrM(Q6`e_-)1qZ)b!eGpHU=$| z<=-zN-Pnlv0yr3M6wv^Cyrfg-1q_g|-5=JqFiM3ET zm6p;;MSl{(&Z#V)U8oT|u-bjcba1U4)*hvmPelJ@P0^Ay1+Vc%D3y2(Jr3&)3zD`I zG!wm$hLe4FpsnEcWy@)4200-USm+5-v!?n+u138pd@jLdcfm#|WE-=4SEL%tj3bPq z%jhy1JTg@jg4aN$zGNnZ)ar;Sq(H+vutTvQJXzRGO|C_msF z;0a&2g=&mo1?NZ0cnfzFgt$>_{sfYG)JUH5u%?@EPkIG1V`5{oypoh?u-OvRa7(;R z%+45_iYb+m0{j@53o-~;N{ud78B&yY2*-zS6R@Q?a3kSLMqx{l;3#rH5|Skm1D63! zPaL*vmN>}Vt4CkTGskD`i%)CXI62AQH);6jIQzuSuYF|x^i5^Pd++W8 z+M@-5J5BHCe|Ii?_4g?Y@;e%L811DMuVOy5YG1(0;RHAB6Ug#Qae6O#x3qd&k|r}l zla!pC)T1If89BG{0%1}LrWhbAMg`tQl9HmY1&O67hGf@xWCx5MX_;gmY2*Vu6X6-t z%||LKkpOYSH%y}(XH%5lfB58yOU!gd`DNjYEPL(BA;q(wtkNcb{x{`xYi(2I#V^0_ z61<>oeeT!ylrL%zmNM%Ti}%f$QuzqBO3-2!CGb?cfb171o0!Rt{3@GWt6@;NJw})*mesavu9Vz3n$XRNrO!HkLmAbi zo#GzIlAZud{;t=#{IrGh#L`*f+pNe-pG-drO%V#fGF0Ed2Xu;}ch1;?_bZysuT>o)Dt^G~; z<+m?({GmMY@W#$fK3Y8WxwTkFe#daS{WuHRDISeYFxn7-iM(R~_4-AasQd|jP=CMQ z921jNR1sr0>xvozr-ji!F{$v3u)H2l&DB~dYUw2a?u6`R(86dUl7987r7X7Q-If3O zxlWiq@AxmDf3>r8{DPv(OIM03-|Sz$YTyUGU#os#Zi=bRM^9Gw-Ps~xUP%${{wRcN z9)Wi|l_)t17)U^)6XGp`#qGnLY1rY+D=-wdU>a% zZ}q8enVOzz&G@?J1?Fb9v*tZ7?of^>-@iDxvP)tLKdoWUEk~~ZYrMdC3h%)e7Zou| z9@VN6bX+8^x8g>ro>~qVIBvr7`4PZC+=geLn6~@lddNWVc%rZ4wb`ItP66el0x5`a z7rcn9#abcGx~KwkGZU6r&z*jOvd3>Fq z{86jiBr8%K(+B@}X0A4PQl7VH;VgrgZkQvPm9fes)X`Xo?*+=3S`+2rAj*exVWh0@z zZQmiu;6avY6G@)}KCEmu8(qLk@d6MKteh@vQ;4#8=Ze%ge zsJjZ`J#uU~gQcbLGn^GD;Cax$aYO*6&NY7;Po_u&8`#zCRI~J<{o3VqE5HBg``WO= z#EwmzIdSFw!4IY{E;MNUoi51Pv+nI{-tXwLaCzSuUpJv{4#DSvdI=6lT)AF%q^=NT|Kvr(~(Q{HpLsKQVR9Y&A#-> z_ZNUswxRz&UPbMRj=(wBT#UL^&4hbk1-4Q3z4VNXtSrAvn*i~|Y>V-uR%}Ysrj`sj z7WMIpaeyotX?6ob*orDF(HBjPsv}x^`;80JUrMIo6an`Q&^{`;fEX3}B?Nz?Ud_x# zqgGU%e&)sfh0Vlk1s^CY)@<7H`nzq$u3h`ooFCfv9z9VR!nVx&sD-iP=MOE(Ht*T8 zdiLnyo0mUXI=p?VfAZkPe=DudZJO&U#+l$z0PtUGDGC5{j)gu)m~bAlGw9s_F)~}7 zZjH}t_PC6&Z5LJ8;e{(|fJMmjazhr`h~Ev2PK^J&(d6Fgdk2O5Q>L=TFXS&i{l zVA5Ibk}oR1fIA}cc~pmbK~*wA#WFKhU`-DANrm9Rd^yvVr{6sH>SJc}Rc83*TV_^_ z^B*6*deQW0Viw@?z8v`I^U66n5ipgR%F#)?-ci07_V&R;FhCHcohlu{_!5P@KpX~U zvFHSs&J}~G6WMO}8q>VM`-I_&Yu zJw{Cb$EQ$V&2KI*UiR>d3q@h%q@u+1DZ`e&Ke#%lS#C^|UyiWWtXj^HmOr0=;1zax<&QI={c6O{d)_*}?d`3v{PH@PmxaW- zi&&>}U^O%ao}|fy8ribTDOhZlB1DboLB{kE_8%EYJt^aq3?L$@9x;1U#nAg^zWs*s z^;*d!RR`bQ7XN0}jyJ{9kpuQpPh4i@CpJ6aMxKP(1xE>h=WMb~Fw{qi)4hv29h$U^ zkfOrR1B&i?QOZo5^UIA(GZ#L)AffTq%y{Jwx5CWgkl=>(ubntwd3w{z3saTD3LI@% zZ^f-yCyzwtbE?oI&?p(w07?eOx{$0RyGV1h18V@V^mco)nSmOBD3S=Q>a!!aCG!JbdkGrFJVD zSUG$l!ra{KD-VE$7(9i>N2dLAit;9l36XEsBq`17Lo{!UUiN8izIYyNZ+Do1;u`{jBniHNB5MKV zLxrKSu)IhgQGTi+00}Z|_sx`WG*IG#vxehE!+SIx&$4bPMKylFg|+H3c-nJqXDQoi z*|*h+#ktM0OXMNV@1CxlLj5dJNgdR~xW_m1Wp-b1rZkj2T~=ay$IJH{EB_s2oj6z$ z(qb7zb(H;)jb4}0=0ZGLoB*(MTRe-k1J%`HuU~awc0|^kb1qfL#Ii!z$;?HTjG%!; zfjz*KAZt3L4ZF4_HTkByaz^>)EUI7paQ>y&weFiMY#-E2_~}jMI+*-5<(OT`VE;0( zWadHvjN@`T8fIE)o&g`Dd!yJxT5Uexr*7ITBclo z9!T^j4jm#3iGj35%I#6LMPZEcEjR@E@cpVXh-diSd8iq3aXHBQn=RgH5%KG#SinKXPIxlX$R%L;q00B;%TtdU$=SelSAK^}QnEE##^ zjqrTYDAe?P%9~FFSA*RRRJ&UsT_4Z&JDbBD4-i-{&?mfJCxm>569x~bTF{GX7KMl; zk9LW6IdZ_}JkCgPa{Sx?M#d-tvI1taR!+RX=YZaK_8mP%slKkPK^?1N_VB+he&kL% zntadQbH)t~cA~O4%Epg&FZl2z)`)Cn>Eyd(ck>xc7RE<=>M?$@(}}Q7@#=1n?H#h& z;X`#d30`MPpz**S;*qT|g;*ma=a7x{;|6V|@G>>@jNCG?)YMn(>+#V~ZlE&_GX8L8 z?YFzWSGFrFx3Z#h7mf{{u|ih<{mId@KNq58-)uJiTXx4=!;ZA|W86Hd3NcYyiiyJO z+wH6WAM7IGnrdjH8TM5a^mP|?_h6^upn;VHvXTW~e7vmn2(ry11AV|x2@A4EMuZ`- z>M(ncWX7&ViWBlZyKUyUB%Ha)gbkt-MPhOs%DD}Mb|6dC*T2%;qnt-z_A+H}Vyo_h z7gzQy%x_cNe^f^akPvR>50+0@|H`_Wfo$)ov+~8WC?`1M@bK8fu{*^n?5p6m(@J2% z%tvwic_zP(&>-Pa0**qK4^X-;muy0TG8Ep1am|MD+e{{m-vrYxLXe#@A}7P>7%GAh z;sOrUZyygPjG71OJ`k`lwdnEBfQjv@vN(7gHS%(Pp2WN?H8^0x+Kp?~LDv_}3vN53 z6i%2q`9Y#pu#NKD;Q|&_vf#49$E7nMAH(CeqPU&aY7}%%i@}J~Maa1IL@Ii8aKV#S z*6=boBwQWnxB$Wk&{)n{i}?daj*<9~QhkgR7o{Te?%{kuY^|CoCE!`T#q8K*y1 zHwE|OJ$gcHBb2F6sFBT>L5)($?bartMIgo?=&4i>%3xT`C@m=YHB=FZo9{XAik84J zY(8XlF*WH*mn%x~HF4f`rIIbD%6Br?Ja9DYJuvG2%B!)zM%Y_WKhh>py+PQsQ5#i{ zjno58Q#EHxFlI~t%}md?6T%jP*XbNapz-9@!B3PsrN@F3w~2wEbIX=BYd>1d_9{S2 zI;Kny-Zx?9RLVnX=m!eDhV@?55*@)P%~%y0r3Itx9%y9HJGEBX!ORvW!;%W*9fQR$ zBYGFLfgDhZaTsZ&s%?N)Dte*ROVld?5H1{k0L2rf8uGLx((*o%05K`=_H4G|Hfh*whHE8TYZWbg|A(l5NMR8H_m zIA-+c0V*v7e-xW3zXva#4_*W`_6_ksu%md0e|HX=#qWag^o`L`)$MtpyXlZM8pR1t z?D1?8(Z?*3^cn{(m(_E*^M=jM;ue}CmU*765{z>HYDCsym* zz3h|kskD6UBh&U@96GLD*LABtq}zbg3O^TgDAY!@=!`~#O~X*bN^m+*TM~7bjdohW z0unp1dJ(BOq#+~dT^Fj%h{BAiHKzdrAYNj=uUz_|Q~3cECG}H&$(El+J;tB6{&s6j z=nk*sH*`nnhK4Xy)cn8Dm}sAkWS=CUaib0aWdy8dHi;Obtk*5s(*}3YR$)xEft`t(>Fd7d)&3kpP9TN>LkRA1pu{mJ$Cr|Hs3*%y z5)!MxccdS5fm03kkXg?iG{$Snh`z(OJi|Fbzq`9i1Lcds*-ES366pR`u}n0mv;UJ< zuaNs$;3LK74ZLij)l%;%$gldk-dCnR&oQX9@ITY%4SZLaA*Y8}OE0Qz#CiprRnS|k zE=`Qj;&f`fNajP)+HjRux+C>#Nf*OPYB3jIsFDdmxC8JlR>{5NnRn(ra_>E3@0#8! z_#Fhp`&yWc+8EXoRPg%yua_mA%&d3>_*wqZ{}Th$Pna`&*X-+Jaf>DgcZ%h~?;n21pDk{qQ-(XH+s@~PiYH8ln^XfmismN5 zQF`0dqE0h)nNAcm^et}}tv~g83P`hNl(R*Q zhXWyoC_jtz2D1UDnNl}HR2yV5a-P*|!~2R_N_ms0zkcAtA3d&#TI%tZBYH(4e}Q)N zK(AC+B|ne^3?c&bf;!C;JPfjqP`zNzYgmu@Plbe0T$G1`HxN%WJ-B$%S6L&L?SVkm zDCpd=_La5ouT%x9V<8a=LWxA{%h3Ue!}^HFdQiej2Wd%=-BN4}4<^vbUXA2&%HXjL zMW@@=fIyIFxuZoTC^5P6BGB0D%J6HO5haiuOy96(!%OcjmRDZCP6Gl>+4hxEFmdLT zu|cX!&80eC*^tJ>E3VRbWSqCqXi%m)YA6)u+2Ex8)iC6Dm9vo8+Fkn$vRY>CjU#Kf zZalb+?LB#px{s343c-oCgA>J4RDjRzM&PUkVsM-n$WUG{O22}ABUlcyu<1`sC}Nsp zX@thAMpzIHARVSH`9(9BvT^^wBfqg8Y_zgmdF|U>Bj3LF`)m5(5OJOL2U!{T!7yct z@`|!VnbhT2V)~WukACzumviebBUSGh@}(%LMMV39HShK*HeMB?t`TsHDcnNrj!(152w_~Z}Qk|31m_8z|-e}U(yq@ zs;MI+$6A<=((qh%XL_4-ABc&X{0zJ%4%MSUB_s@1t8;rt-(t?sm^D?|yYi()CR_gA z2R`{$x%3|tZ5Mq^d!@^?`x91(E7`;BnfxY=KWmkc_|cL6cPa2){73nUjoySbt&(;_ zT3-GIcbNPQRNun_T9SkevgVS@i|WwvE|(Dn*Kt5ZXM8-W+nD1M;^9(50*J{JS6pF2 zCA8uSa{s6*I9KNoNP&~mU^=7{Va465Oa(6$AOi_q2tQk?KXJU}(cjH}^4hn->!OwI z`1G;Il%JUA=fwL*Dd%rao+h;C41q^hNfVWnOLF<%+EMr;?3!PhDj(ys=hC-mv6}5hmk!#y z&S)m-n`zRFC|_xWZm5;CfL5Xz|1aqqG>hK~Rd2&gs~uX-yvRRAteVnqYdo9t8JJAkVIJ78GwW~fhaF)Y9-0r1YLm;+R1l^wUaCWhS#ZHDJ);K6hdo_gb;dXl@&e&ft(|VLV*w z7En$X(g`rBB^{)0jZqYJg5D$?rH!OUZmh(PIJLe_=1=P%{%kXQ-@Q_j1he3mf$g=u|S zr>Bpalqz13szJRU+UwnGWk=a5^>%8o27(v-FcHCVB$&7zpb#L7F+Mx8HDFS)S#-|O zfhB`=JtZV!jTKLC+Xl6qu;NJimi)-Ez^|xkB>62_Nx!rFQ_g0|KkxXtRg;sf?e&y% zEuJeAhuqpG&FHwcB)CN!^!WPPxtRQ(e&L-bqyVbl6pKaHFmhXIEM}%Js$k40nZi{C zvCs_!15QD>IH+E4wp=t^x)l5kORRKb@7~(R&M1Dq+qe7bX!pmXPads@8oydCLoB}5 zqmzqJSVX-EBoC?z9vv{X2YLKu#g67NmzA}n(Ew-z`BqWS4z!^^m*vqH$I#OXJvgm^ zCL_T|%KLJ{n+ur`;gKFus{`fYopIMjXpO@(F*Q%Rpsc*CtmJf2s@{v9c!m}CLIX33 zyz;Q;?}0rZNI!`7>K$lows{i4|1_}z3bR9|PED~0sITocdvT7;_C$}?17b-UahINNrL8I$1W)+LQ zK>aSP-(7sYHYw9Jsr)=ZQlv`c(0xQz_pwQ7q#%Higa|$ap=hzaq3$EkS#zd#_+YD~75|h(vm5Rx3r*qnP6h-LBfqO<%9Zqpb z0>siplpr=``yK0sUb=Mm?y*}B-~^7_oYR_}#vwe>F@NV;wmNjywTJoKp!?9wWER%z zL>tf)aQs+gYEd+WPC6IFL%NUl@E_+cu{SQUZI{()@u^W>|8yPAjB7rUXaNi2t7jn1 z$Ec0Fi|NKcb|QXd#xCl{^8+vmh0SoOdLVh$EQ(r;C>_DthH*xp3-q zut5D)EO3uCYhHT;HzO$YFH{bzQj_Kjj6>CY;LG*6QHcZ9_+n!OTQS1V^j?F_ThqfX}) z^>!~nr46XjXf`AmAT2`Cce&s>bHQ!*zsoO&{WU2ruIg~+AJT%@^uNu1c?C;yDY5K= zdEwl9)^zFm#vQ=Fmz9g|f|?#If6H@EL5^*Rrr zL`dhs5iuv2F+x&(P{+XzxH7w)L-s|nKUywTrVYD+NqoYhad|wGVrlUjLBS|g%FPmF zDujeysr+{3UrL?l#-&TY#xm(2-!pU2ICa63)22PSU@CAB0oKRBqrotgZeQJ?qNVR0 zIPl&(`}bqyPLSK{*iQ?%CbS*V;)K3qg-wQOj26`M5G@W1(ySeN6Z7Z+hJb>+d}mei z@fX?-Y;tNPOyZ$_iBug&YMK^F-+!>y56%Ai0Q>#&*&pXro~{!{JitCkd1cy5Z-SI; zW`pjygB5eW!(~#AAXtoz*9v1`L?WDu5N0aQf*G8N>Lq6gQv$`hM&4Ky3wIIvh$E(v zrg3JXEj1RNJ5-N$I#b=LMnFcTvNuxSPyHjP zH%r2eUB_+*l&U?xX*cm-(l#hNj~(OdFj?DBk|Tb6EPNxZ4hO2W1MW92)(X;OwkB9{ z-mF#>BnO2;=mFyVu*cC9s=-;qjZlpMp|F!Ex1cyz`5hJSP#yiPr9G-2od1l2{h-8{ zo_ccS`X}5h4c9l3Wpvq*|IG3&YghJoze~st$a4g>gn@v$RAUB&9;KzIe`Muc1Th)R z_xKll0uQZn2t1NJv>`lNJQJ!Gjlb!G&&UsWUAq8h)hDEoXCTIHPfQdZdD8=+Wq=gR!)R_fJ!g5Z)40(crW4g zbIEogCPoiGA41d22u%}nQ2 z^dbQ=Ch0~0;-9NX2&6qI(`Cr+kk;WZM0Sl%0y~3-X4Wv9F-?HNLe;Pkkb!e_n`}nM zNR?mwj!ls7~eD_oNo-fSQL^1@X=@R^^0JW+}^@u zwoCQM{+AXgV;QLg6t{6(8x*&JI02#xY&6;+s?drLgEHUvI5_1PtUe=r7or?0)Osj8 zE*jGT6;qy6#}dKCXo%^c!xKZ*v8cGdSlx1VSlTAegY<=*U;#P7RK1PwiwdV)E)8La z_w7@k)cwyVb^otVigmTfUMj8o0=?^S9!)yQpcVDvY{YUQp?e0b)6&8b;Plo!|=?7+}o|2tUBd<4MNc za^=cwgJ>dAmu_~CYO^_zF4cJZv$%)rg#SeUy_WyIR*U+{Q2T@ewLmMERuGfvN7}$h zTi*1|-IFzYyvLQFSt?yhp+NbatrD)H99mMqCTKL0UMB^#W!leS>;iOk{UFkL8@X&% zi`iSdr(HPtwsM+TQ8tK=e^Pk-h(Cvu1(u8G@iVW>pCM+pW!ALrTk`JnS~YvVSAKek zxrTW0IOZ==4JR$^G00ceL5)ONN{fsLR&t;~e~d~}$4a7y?HY*r;AFt zx;7W3lSg4T{^zmC5=Hl5;XRnC2csE)c1Foe`IosL)(0S?2X&^J(1a)QMZ3VZ=S|;& ziEGxVi^tc{_C0aIY~^<;i?1P78T9HJv>&yY4JQ&>&~P_ZZKrN2Z1e-$-eNZWJoyjh zHzxn=qh*$Vrk$D&*<&RnEED3u8^P10HyDxp5sIMDQ5kAk3*!P}K`5;nmKC1l#=U6~ ztBRV`mhSSqG@67>C7&~9cz&b3wMGZu``I7(J`xJbvRvalh$mp!1+~XVLFQr zX@mlK5+Tr0?j5myUw+7BeESeR;X$?yjntFw69=$?819u^Wg9DR){Oqe3wp1aXiPqq zs8q43iN}(e{`aI$lGrq5K7Ra;m7B|si?d`cRxXso54^;`&f%Z?#I&jN=0E!AeDU(a zB}*4nJ-d`_AM@(YYxT$`~Lny73MHxIn;rqTsH z6++sgoMj$CBp9p+z2d}!doO@nhPumofJ#~&eaIxHi7{IGRG@*;^I*)!IYSkSO(QPDLE-8>HQ=Gz$C?*<6`5=Dr~W_kau_iZjamH zc9d4QQPxgXW5U{uYU<>2Baar2x;b1P;Hwy2kQ?K6tGTXi+Nv;UxyU*b_kOUgZe!EI(3TZ71=(9V6EM- zePjyv2J%cgtJA6Tdy?bg;w7EI?uplCHP$<37LH=60{nj zZw2hSs$v?k8Qs4A>it(~07r52Bbh|SZzJ$&w>MnXD78LjPII(xVb8~vt1H))%=rEH z&M02`wQ{B7dDcnv1ebQ)_{y^{4_Fhou`&Eo^M(yPadxw^sCzGI$oIbl&%n{%X4*3- zcZB^bfQM|J<^$Y=34ua0aA>{BQoP3Kh>1^Zq-&h1<$EVZ@14&OmV7=} zTAI+OB2DMA_Nj1%CrWj+%DBBgzSu2z3$XKXLx9YW%1jJ@~QNnO}&RIbK86X!a-WC?j&v(Rem7^lZrr2nmxg50v{Dn_&|$n z9=kWIiMCl&$<$b%9-GX|$-7*Qt$LKVY|M0^%R~jZId~|qJxtRH85lXa=Kt_uIyEsW zmE}_8Q^U;)dqUG-(n|HnM-?Tw$>KQJ8s7lb{4xVFjQf+Ft98N@LZLqnLt*^-4Z}ls_=hX66>j!O}=3mYCOcQ0qZHrN?7KNp+;W>TJm{?1rs-DnaF(vB5Gk zwa|MW)|t|IQi<9ix6Xw%rsQS3D-9B-PMx!K>AG{@0LbBV&3+cggr|zqRxR3G)NAT~ zX^VN|#$hK*VCuiD%nKg*_~`G5rPxueoZB?6lKC*^5MB+%7Rjf!4i5?_$OOW`gguI1lZ&<03BV!~5Q2xwnp8)%9_c4!vQSADoKQIbsSddy zIQ9n0DEYOA{^+P%{(B|0l@A92#Z8*H9{`HE0kE%HJ^8CefUg6LC4|O;sbMkz!ip9{ z8ibT`DK!Mgf|w6azBn|9;%l{M5!UgUG*$60lEzE+1s@0VYL6YIzDI~tc@29>hz%e< zf}Dp@^{mJirrKOks)`Cz;V;tbewI&b-$ra=^MD&r2O21+a6jwxkR)ZjmH`(mhkO(i zb`nZSBg+V`ou7dwASq3pyGpsfgXNxPzwWS#zr7KBTJsz>O_<24G%aNx;`x$6Zv%lw zSwbSP-;Fk(A5<3qqI^b%+b!u*;^G_ymRXjUEs_Ps3nDs)T9Nn~(Jr~^kTU{=_-e|hj8*%Q4&Rq*jy6xI_PhsEo z&+gE=6Fx|OVBpOgd)`Ytm|UYV?|u(we+Zi(=gK+gr8&t*k}WP%ZjqCbC^_P?tXhYu zyuyJ5Mu&(ZRoVa&iYv5o0@#tnF6PldX9$IFkolEs^H+Y{F=gn?gxx9Ez@vI?v zGuw@-?mBT$(Y?8?XXTGs(PL_P&wEZ5O zNktVjC|Zs&=%fN16ZHRKB;XQZ28f#U7)0XnEo*a78O|@Bscj}5uVve&vI_^4O-Kza zzzr0I5m9YtqDnjzEJU$I+7=45U>`X{?a{5HP#u~Fn@aVJ5YGhtXcv938kWNb9Z+JY zD&@7j?R(I64@jbbngVxC5SdORBYaek`>7+iJj5vBvV$R$(fqbjgT($xNk+7p-yq$? z4h~}nl}^K0F#>ymJuRLUzX>J`m%f%^e^4Rt<}!6SR(Zs>#(@dDS)>HTR@ z@Aswmv1IFj-}k#V9TvotfF*(eDbL362>y|*dto6F!fiDAV~;OCFrCn5_v?SpDAOt1 zm-49>b{3cU?;N>h4cg`YE~=Db7J%-6U~Zk&0`VcrH%SevvkPBSDwNQ6Opk6wD=zI+ z3lPX(+)8|XJH(`k@-cA*?!O*1)hNMuY&7U+!>3UYS8rxzA<#lUo0#ML#y2>-O8##3 zQg`Q_P@owb1zho^b#t)?z$t`|FPMym+46tGDIDd?)}Kop(&R~HKwxX3yKGB4-iCZi zTnapiP#Xs6FWP_<3lLBYMO^A?X80yyXm*uWoA+jstIyUBBx_}gZN+_%2~4m%r39>6 zGtzO*h(32EOV(5_sYk82OEnO2&$z};?4Arn7X!t`UAq>O!AIG-{#Dj%!)vhNELptb zxg|@MD|y$xVu!DwCp#i;PiWr7ZE+C(1vsEdCp)wh?T%~_6y7!19LWyR;m}DbR$UVH z4ITs1PXcF{pVJGFCcg*wHjgYKsd=s2B7IIgF=M~-D0}MN8OlLz>qgItH@9z}C3X!S z+i~~E(QTkhBf=3g-K^OToP%ZouT6?~dr(9nMovnEn_e61O|oDmNzvkrP3=$ZENt>q z1GsryfG(2&-*mb*Y|OH4ySDXS)TCuqhxhIu)TwNMpVcahC0i?b; zQ6FD6+p;usi3#hFjVMggn8*UzCXf*COr^3c2%}4HWJ(fjcAJRkV!f0cE^)?_s4~%8QD-4j&*L z2DK7x&%2*|wngjZk1u@nctKg8?)`e@^}81dDn(Hz0dc_Cv`YQg03FU3HpfC3QiInVd;{BkyF z?wVyo`|o=Cg{{2?6t&;zDC*g(Xhd;`&db_$YS*P@K?lu|srS$A-R!}liHoZy^{8yx za#*+fX9UNz?%K6=es6a|5&J5yX;$YXU&mHW^VEBiFYXQPTDw3Z?O8l(u<%{;BvA!D zY?~D0N!CkI+s1QW$g)WP;oQ3GbAkM-ddu~7LdpnFMBMw$x23tc-4`w~)o+}#BeZdH zhdL#QeVh0EpZ3iw3{d9iYBX0t*<>#7h4p0Hx0)?(X=!&|5{Sh-aR(M2s zOjscNJ8;)SBc|OyZt~=@gNg@~8jOw78)tRvuJ<6YUDKjv$4-GRdaKnUk*4U4jY~{Q z@i%MUx^24-#ib+eA3N)b*hLE;pE0=Kz}}Pkj$`A-4VgUlk$FRA^d8%9$U|ezttg@rHbI=n&UHaY-leMWyq>6>bVRC8$4jt<`^VK4DDsd(!hDo98hH z;Ql-)pGL**accR=rPE6eetfgg@ANY_^m`t?kMEE@yn%HkU3CV8!{Pld^&|pG5U7F_ z^&E*~Ax<)Y}^JgfXxCBAMQVD{P;=f zg3c|A2Xu%p>QUIUxNC8Dt-E$$?VZwVw{lu_X<0sVP*ruiCOgX7=j8Qn)9s;N9h55t z#XUO*dIFV)qyx3abEuA4Nw{vCGaTVyhi{kgG?4-T6hL?)kt5wnn*}YVHN0u ziLDxWjK)}WH&odu~?ZOyMBDhfE$uOqocA;S-|==-O#pKQrz>M zNA=Gcd0#=rU1DaFCgS+R^H*&PZrio%y|X2SGZzzI#g|;8ISBcoO&}i913*;tPS|F> zc9$UF7fjjM8@W=d6&gI9<`O3GJfpomnL+_Qg`g!Ou_VHMF3hy+1Ll{h+A> zGp;Mih^Du*0bk$Q*t199dgYaxdxK}h9H|O>;YZyhiv4wi)(r|Y&orf5TuA^h()c9Q z5HOl7iMp)DE5TyacT1Igk+knA= zIF3jSS+ZJcIj($J=!rAf0z47Hr4)kuG*R_;#k~O(-Vj*Ny@|Ly=B&dkzu`!NrJqEID|7Hi=f z(7_*?8E{Dmbw)b5*{z9>^XW{w{iL46eG=AJX{&HQxXg{10#Fg4S9;t@utSmJ%4)j$ z&UIQgPWkYunT1`_veNR~bnGcF`1oG;%-u8kJrq;yZIa+}+T#+^vwEmni*7dncqMyG)YR5HKJ;4^n?j zbb222@=v)r910G1)P-?g)zHBd5^Qo|!_;{-5dV-smYODNjw4OuZDqIe61xutTKewn z(C#N&%7TYWZ*4q%f^Aao45^Wuu!FXEU} z^&<~UIiTUZ)cA{6XQR$|<-YDkML*fnm(J{5dwTwJ%jeC17S+bHkv{l2(08{|h4G?p zp1D=NojcR3HiiRiL3>aeM|&LW91B}gvW$F;7!#6GO!0BDGr&M~kbNENl&naD4CA!$ z*jloBdufM9 z)$BRoTr}7F%<7TO;HF#3d6rTuZL1xqY(eM+w;!Uik5-mzaRT}TGJLVINH=mMne<8e zlw_YFAOZv`u@_Puk#u1bJQ{0{2sa2vmkU&4DQcK}dErX{z8@WF8lbwIkZU4imv*IE zTfX_o$A_s+c*&`SjzyrEBlC*6ypTt8Fcx zQh@S{o7VLv+^TrzD&F~$zccyP6ZFolpnS5&R1R=Y`(H!gK?3ochAa>?Yi}xyFl~B^30*@EG?S$v{pGrqMe{o znW{MJW`N3Qw?k_{8(hj#?`_c7JrL;Htsu}{xmnPyd*=>4x)UV>l>`P6)!J#yX<*m7 z*VGuaNOdPXp;^gMPIjnI2*cDTA{C@~Bs8a^#dtz1bbXVkXnjp)Y@&RS$2|UB{Twk` zpt5RVCY-$);5rwe5wt?=X=8hKcHj<~w$Aq9}~NI*}Wj@F<9*@LiA;W@64-ws$6SL15W4EU(ck+7>p^eu3*}lo(}y}k6t}|;{1l3CCFVES-Cu8 zAe+tB1UH=Tv6-!59h9ZP8z=t6ov?FW|EL}0@vUFVeif3q$rO+;C{M$uHKoQ>AChkX0O?U-G$kUfsED_Sh!;U5hM=ONQ3M4+5s?r=5YZ4tK@^EG{EV>8`>pDk z*pRWl;)7$%WJx?87PgOlts3^l{{LO$ltTNM!*w!rLtpXnH_Cnl9I$-8tha%!Mj$$1;b;7Xz_~SQX%%h9u8$$jUlCM#zj1S8k zJh-KK3!j%kwk`O+7MV)f(vZ3m#hPOECj0#X)#(jnT5>{GUow_YNlp#~Q7RxEr{vRB zH$ob2us&t?(jW5cw6<`g9AR=k_GM#uwDHw0LYsZOH`M&1q+BYAKdu9Bl z&x{?$6K>-q&ZTD*;EZ(Hr@M#mQjLS}?LGEWeg+C?T`TINN7C~}FL}bdl%7mk6_&%u z?a!ha1hiyCl;D0s$(y81ODG%tv2ma(;BZ)NZfn5hrK)xk&bpGR_+MvW$;oSdmINr% zJ|;RRm?Y|&Z;gNG#;H>{0HdB*|5(qvW-PtKDLyl@91s5H-Y0JMH~(OsCHdl;o||g# zy!*9h9_+onJINjR`Dx1*Xi2ZsAGrf)M&gm+YPMUQ9@Qlh?0%oe<`5RArGG;LBwCjPF3N5*ZGrK)hvxiVZ`5Qj4Xispu+;()Uu{y0dG~q(&MzIc!xv-#ljj*cZPR2XPYOU~^EoXC`NeT}Cbap)-~8 z9HG@;L9zp#Z`+JD@u94x^~ zTHaf5aN*e>gu{3U9Qx*Ww4P_1e|ReK@_4--%*Hjqrl4i2l~91*Hs!uavYh>#`*+{r##=n6~) z^VnI^X03S!q=SJy8lOccz$bHQ0=^0qqqeF0#laJ=kK8xnjT7$~hYlSQbGPc}`{lVu z(4wOQL_YuFv$AyF!Kis*T)V#m?<{cYPuMAEKtqhKYoB1v3?^l1**1?mn1rCT4Z%L> z2^7Fg>EDoT+3Xv|gj8`rJc)b-vUnu@0N%l$4iu(7yF{7ZCcUN%*Xy8po| z6UDJ*%Z#kx@7_hf?zKy2G*6LNUU!EvN|_=SVMZSCI33YT$J{2>RXfxSc*ipBS?HyK zy2KWHVi0P>pR6YLZ9rLm_&v~4TUD(=*mZVGmerb7-(aN^0~AI_c$(*huZo#sdJ$uJ z&6)Y&vge6q%0HW!FXUNJ{hJxad#c~q*?-D_;)RE1=M1V&-yiDSFL$~*afkY$F=NV#38nX*SzJ1Gtn-X>?3A)5 z@ssG>e5csHx;m=o_kxlcuB#rphe&zv_~vQy!{hD)DH}x-=?IdlL!hP1v+hc>&ebH$ z8cs2qbuP`CC!LE~XVR?km6dqbxeCsDCnPGe(@BNtqa;lNN&nZg7QT@3pJ$!xt5(N? zgu9IWhYrcIaYzjqJAOvxgA0pL6eQ88F~1h#%1e`44Eq(ncNIogoap-uC%tZ~>)W-s zLrz_4AIb0VXBL)r=vddQk2ZKvzoaB3vqN!NRaK|{4eqL}Dg=g++i;69im`9c>~RwZWd|uUxvlHa@hm-YStTXnKO6W$+1%xJUu5hH1LkJs(VKFElphN955*Djoa^hEzKT$ zdBvV%RykNqmPDE{OxbT40iXJ>>bjKaH3{A9y^@QIyVON`C1%6-sr9Y*w{t}*DkAj_ z?J6q5y}Dgyk?L^51QD=qwXoZ|dBQL)!a1gCf##H0!B0veJ9L!SF0VB+ZXhvjzmc(| z0$z^jYSQ_;O0B_FP>$5e|Fe} z()v+XH9oQ=+c&J{@||;^S}&dvC99uWI>#)}@tYfa&v|mt()z2fwT!@u^sddkXW}1g z?fJJ&eDZlA0^!1PtYy*bzGUsrB?3zD$twrEz{NYN-B;b5R&!^=z!KWKAtAUILZ{#oK zjZ`+e22eM|AmT*m8c<+4aB+jH=3(!Ate=0{ee~ToKS@$X1pd<2cVgUle$H24e*U#u z|JT1BJOWH<2e}Y-BxNY15~j&0F`R?|rcFvuOTs}>2$iP!*=^!#_6Oye$-i%@Ol zDmf#Po6jy@>TEvXykl|GZxZDa_w8*xCB~lS1&^#;`H1|}io2KJLtIL><6QR8R@SBZ zU5Z83PoQ{YRei6hQqPaM_uTi$*q`+J9k=h2ty>@JnXx@7iU;~3jACzMiYF;( zaRh*zC4l;3lG`-2)g){gD;SYD7O+!*g&y50#xbC;ya=5=G#H0fBFWda>o@7j%gRF~ zWfcKzU2*KX`Ju1+Rc+}j`YgGj!vC_X{<8BY!EL-2`faAwl$*?PE2clAKNf4ZTFF3hv=c4Z*G)p&@o01nW+jj zHI_NXE6`}Wjn_my`f*i?KIe>g-rl+Ojh#E+R!5b2qW zA~5$u#(Z&`m?dV4TZ{$x*Vm}ll!y}$J~YQTGrsw*MGLR|ojm(on(?gux^w3gl1@|) zu~VHOs#jMm4XZ0H&Q41UW@aS?QMwKZv%#!<#CuYU1DQdTm15R+6YJ-o0Zq>TV&bOA zwh{#L!NJvO6_=WKTfsPgM5KvivxxjFP0Rv zM`#j@1RAB!Y+nA@xY19^vs%rT{J2Z4`POot>)^U#B{NU)*-{D>7wU(@T5|c+b|vYV zDYg{Q)?&*mD0CGLK!pU<@Pn1dTL(A|%!?LwM*ew{IZX?cbeM|JOZl9unuLRpXq`pZ zN!93;h3yaJx5?IgW1sO|#*H_nB2n^BNa#s%_3K#O&n*I?!?{80*ZX@{OwN1m*=L{4 z`PI~d_3J>{_l$W(vu2@`xacanh(+OU?b~+?gT}iL8>b3ObB7d)z~R3Lf6>q(MaF5e ziyAN7r=C$aW2QyCuScZLXG_LRvtu(YDb7qwwk4w!jKvnn$;VVtXTj&Y0;&_0IaWe&F=!LyjKRksb*L&zzrf zz}=~1RcC$wzQnE_J9kOkCzqTuKFgo_t2~ka<+ma`ry?A#$}>Lx+}P2%u%NJ@i|8yW zx|Nocly)<}C$^*ZiO50dfynpFy6&}|`t@w*$VT@#cObQ(eW#v%1}9uKtVf3{I!K*7 zon%L+PQ9zU_K|vvRHb*al#!f)b9l*WQLY!ou$|tETzJvb1v^mNwVX_P&IxUaLYvx? z!gN1(=CO0Ybmdjokk5lWc?$ZEP;*sE+d->PbXP^LI6SHFsFq>%uyU67x=bh>blYP; z;&9}L#)(ihSjONLAyv+U7r&yRYk=jAV6^ZU0~E%1!L|JS36t4ge^ z&UczMcgY~*Uk@$l+yxPkc|H1Dr1t5X$FUdi9%F15{3jk4bI1!gZu0=s2Y6uQkRc<% zaXxqe<~r!*0Hina$Pv=O_nl~Gns2k^1OMM;96Mb$>phN z^Bvh+!ZDlp=Z6Eb(IvYi%VK?h=6+TJaQf#)|5RDtgEM;2(v`%ZdySK`Hx3-JX(|-g zUg7)ckvoRK6@ABJ@4h;H{F%`=z54E|`-YT8HgqWI@O*jc5Ozyn%lvqkF`;|c9-Y`L zeWkeR+Ne|dwDG3_V!bhH2ue&cOXhajFd6@C=z_Ik@3dtt_UXman7S%QYH|`b=&k+J zsTtY1;o^jLB{>BJ#k6F_dD(@I)Kqp@CnmRXSYKjs*k{IOW!!OHqnLIH9M^ssrUH#*pD-!I>7n~lp<>9Yq=9bQv)C10OLtx`6kitvu}0`-?94WPv4$cbi;Rk z(Il=vCa&HxX4ePPW1hY0iY1o^eH!2zvuSFAoZzIxlXi4d!uUQ3DbjA#;&y2cX9ALo z_CiI+c2(@lgFg?tS_%8|Yb^XH37@%q{E_9&3pX2|_Y$G^jANIJtSt++h)})p`THXC za#3aM>Mgpio4ZboSvPN;=-kJ6d+pq{#?$L?kW)xo)uqZ7WZJr=%sQtXHS?S(s3oJi zKZ+exw8><}#}A1w6(J}eihGG=u7*kF9mTGMYZ}{kR6idxyJO_q=^bk^=2`Wq@&n>< zsLxa9)f_$tcEqU5w8HWPnBi6p38ZL|Zt6#hZemUmve?lm1K*R}oJ1L$K_L%XGIwU@ z+iqSprFhg04~+9z7D4;mbW>5^E zHBJ-_m9E83^NYHUFvo2*y}EY0^4f-xX@#L2SE|onR9)VF?DWRTmk;efz~=O)<`lNC z?$&F-(2>_pp6;1(eNj%D(wv3rfvhEJF$_Ld|; z3DeaF@hiR;=TQ9Ym;MJj6hJ4#UZAB)A|ELKgZ~x(5&sLD-v8^*Xvns|rp~Z*xqMK> z(m!G6=vlVG(SKMbP98PeDt@qZ>4l#SuuP(Vo-1$jPh`vgr=OmopH^Vpck!$L-rD9_ zbzi%7Mdfc#8vXC@>7rq3<0ug~G~r>?-!RkpH7eXQDrtmKn+m7sI<;>*?ODu%tY4>sub-32wsI zJhLu0yF6QTs=2i!63oo5smaa^MoO$s)rq7ws1T48|D}5Nj`r*|;b{Ejp`>uqFYqja zOf?k>C1m3gjr$-r;VKJxx^O9yV5`(r`)mc_8Z>^iz+01qoq7$zzBqZI_RxFhjjPh{ z+VAU|HLlWom;6Sb-IpD0IybV%TZ4}_si%8>-F>`z%L_g4tr_dfz51tbdLHXDPF=jA z=bECizO0cQ%%|4jcRsnz2+{V19bZ>eNVl%C&82)C@`Hy{L)p#*oX4;w!XuNc3X$T_Qc|-mMTJRfq7-sh*U z%gaCqgcPqcm)qqaxWXa8?iGKDq|!MQ=)pFJCi!%($?QnqM2dq_;YD>;xJ`Yi)Y?s@ z774=KEue=OLajC1kGLJX_oI>zQ*|55* zQRP0to{@MUNj9?){QC|$HnAL<#Uej2&d zOd--ysm5OrW5j0R(9kQCT$(ABq|L{cC^|`;hD8pKn<~_PyX?f0zq^|c8lTJFKkrC5 zXd7|kght25o0r;MYB{yn^EQ+eUB6;d~MDs-QblpPo}jA;Kl;Xh;s(w z;cyNzBWDFW7kD7WCX@ubi2DQ=pMgGP=K_{2&@JA+YJ~+We<63PqeKC^y8|Boh8{;>>Zwx>{MZ zXn`S=e_4u7omy-7xO(H#^LsfYPLcs^@58FPVSA3Qiy-UJ7YJHa)D!R^OO-}Y|jrj3n#z zUV7&u_162s!Rwbz>9)}SNUteIS8KNi*BgIE zve=ss-!*BCUwQq>ExGT%Y`>@R_J)_X{t-44@q7uW<3jD?Ohlp0dKD-dq@Y{{xZRF} zm|hJX7N|y1ln!m!g){NM+!R}+C~q|)-X&#MSHXzBPg!JWVwmy#sRtjF zk16*VCtfkSig#W?VP?ElGveZ4)d$_^5p8 zs+XI9MCTc+a$!nId=CgN!x?EDX2py_A2j~*Qw2ZzMw#L)59&7dJ7s3`qG`A87KKkN z`SF>?+b&cI}j4PmW3pm>6)CKwEQ+yM`qhMqPjvsxsh4Tf=S5Y~tzi=B-}mS^2_{q!4eUh>on zwVh7M5Z~claMnHbe+;eT2en&Xe(6o8F;X4+j`4*P^@!2^+xRQtCK=OhOR3rW8XD1wc!_PwX>SX z=L?@VKpbBJeFXploo%}%iHCmrYVoDpB^~AOR;**hMG1mujEQZ zN{Fr^>p}McZwtyi%NDN}Wo3NsL_OfhNkAfWLhLK`-|;q!%(ucB6AgFasAvbsErghL`|d?6f29sbSJ;uZg0` z?BL<+W2N7*i0_Eoer&l7z*Tzw710AIng5d ztoeDBg2XTx$ z@r-6|5`%^JnM%O7sF15;o3n5}j!I7xgdebctfj>$Bp%0Yn$P7=e3vL0W3b*6a?Qd^!rV=5Y? zgK-+zaF!|TKt^Ha{C1qiMsEXw#4igxF}jBu98-@2vA>Ck!V&WL<8&9G$k@S^ermj>8Y9CEZFQ>ab}NhFxnVVtS7`Jji;!& zLW`oFow)2Rk-6&jvrmrv&A_I`YhF42S!4Z~<_+JeRZ2$UfNOesvM(u+jK&SgZWUd*)mEWb zGxf67M+lV(xD)xs78TPCa|n8^TYt6Z&fi?uIQ!Q(uUcP}c^c*Hm9>?f9zS_Y_m_+% z9Y5^+`b#gpsTm{8{uV~AcDr$&_7(FkJa0LTD0wk_a?|TNS32`cqz?Hwac%P^=UY0~ zROXarE6&2i!m|DiQlY01Sx1G1i2>%Y#JT`>py;xTw7}Tu4bG4Gpv{6KrLK(!f#T=n z%0Z|X6F}Pp9VFNl38ZWO~YaAby9NdvIKIa9| z|CqR0+!55bXEg6OE*M`rhKhvyzy4?Q_YXYz*!exB<3oC^Al1~`NRLQzG59^p2%jPzWj}r3MIJ%UIcWQ0# zS#w42`dN|_OBdd8cco|A^N&8fe%$cFnmSliXP+LQyL8Me&7Pro zcM0WLq!dIlUk$wZ;l}OuJGcJswKp~_*wM+8xY0+J;5=A@`^XZ6FODri89O%IZ-ga? z(l)r?J8B8u$ChA*Fo0OaUlORth>w+~1k zj`)V;*H4`I&KRopH-@qjR=?V}57Jd)Ea2`d{00SQJ|!zYIVe}1BX|?1xoxO~9_z&L zvp0|z2g1YepoT05j(lOPRNg>&sC2T0qkUOm0ldN0DZB8jsA}>6)_tf;iiTCHT~GwW z1>FZH4QjNyWe73ZOfd_R)9YwIjWj9 zH)hDCm>d4%u6iEyqA!pXoWqA1Eu-v!)sf&vE|3jJBjEXQIu#uGa0nDdh3yzMUE3N& z^hLpk9>Rt%J6u1k=y3=F+nF&qBBdh7y~@~g#@K_uKqnMb$dbI+voN&Mfe-COZPfGy5l%D`))Ih^RZ<)(x{p;%*#m#gFqW1(2w{JGIYn+~!D zAaPbyQpNg!PFNkui7plpItv=aC@o@#+sMdkX)$V2szvtVD}!${Nguw^6;|grC(f-j z=BQOhZ+Yo=aVb3arFs%?h9t5@z;BilP?-kJo}~nr1zTIUBL{@S(dtCERZf6F@@|%r z1>o2q*!Ink%9s(v?}t}qi#UDi(9!cfjL(!|kj`v;zu0vO3B|kb0#{Idz$B?(U4ber z@YW}~gewU#PMiy|CORC5u{s=Ss8? z^-PX*LXg!KyVtAqXm6qeM?P=cod|0LzG&T{2<6YYzF89D0=1}6swZezEc61`X|W{D zqYcq!YPV`guyrU}Qj*sfkeo1{QKE^Z@f+nHC}a9%bU>mv3Ey5`u>>x zoW?-LlBH|wB5t40>r6;WN=7i#o2;a!Bq#f1cS2Tzi~}JqG?UZ(LDcBhQ2Sr@d8}^W z-)ce8n-8cmrnRwJmTZSav9;mz%EvWnf#c`~a^-MR>T_>@vuVM&nWs+O)UZH|mtS}W zGI-qvkz||=TxK?c>Kiy4waB^WI``hy95OnC`y41-n<)D%X761@xiuee^pT9jAO4H_ zPx*d?>8g$QeTNOmtC8Y&UqYqEw3)NA+cyuxO2I1U z?hQJ1zCs0R_!x9M&eJFfc9#nd4i^edk0YPoYP=7bq|W%EK=VePH^j zQ?Kscv|X%xCR}UeqlZq>oR^+5Cc;L_!s*$SupBd_Jow|<=cIMO{%i z6B3bySLg7hg+eeBLm_K0h?JKgii0EZC6@OP&$NY=7|l(OGZWE*s=ZfJXTXYwfpF8aOa^tHX zCn`nTw{)*QJVjh1di*%LZ^zDKMSIcLSY#~j{n__w{ih#(@)2f6l_RoX{n5;()YazL zLZ|@fPYc>y{vgdPIV)LCRFXq=C@&QXQ3Iw>dI;@iLLoGv$*gZsJUX^Qdd%Q6rx>^N zeqok^I~xVK&}}sxjn74?TjYkD6Q&H`P-TIrFA>uF$AoA`K1}uG^^=FcJmcTS5tnf& zdt-2-Y`7iUbhtiO<;HZ|eIL!`P zi!@hsSNTgcBr00+B!vq!Tui_UCNCH-N=aoSQdo}q*KcAHW{FWEGe*L{5slyY{=`I+ zlv*wl;nHrt*(78;F)&IvC#TJjGp*H5j`oAJgcr7$m&N07?+}1B*o%a3&U=E zmK_we=hi8%KyGdT6wOV~1x3-x-jkK%$wtJ=laYiIh8Z9#&H%K``ahGECysUuaXOm) zt6HesGHv%%8&Dxw!v;=lKRf|6rXZ6w@==#iGidgW1KJ}(hQ|Or1#Ef24=;Zvm zMED|4UOeuG@4nlNs#V_Rr`;ck;%Aoqw06XjE1K?p=H&~L+%Kc~0Q6wDqvCk;&=tlP zAM7#yvf7tPd+KY%09L7y8jvQ}Gf z{{F&vZME@c{ll@9=++yF&Zdq8=0P;`{q>)hFPk>wx|{Dd){mHU@+5k3+Kuvm3QPAF zE=Wr{e$e@iP2yJ>2D;`NR`HV&l#R~_KRe_PojDN6fagk)(Y3}R+5D1l`KiTn)Kc+d zqvTf-;L?aUu#PicJkDZjNHg{xl4WbyOgN{8xE4*QPZ|Gs{ySsr;A@}1r*Dti>iR3j z^;CwN7Tn3^TaC!eO3JR3-^)W#AB3IeG zzlToa6BhSrTCsM0)Xg{7IBaYRq#h{$Omv6Ck8|lR)#V2!9wfzj zJT7md8;xwOh_OcfI5A_c4JIOnMokMEIq-6S-H0ZJT^4W;n8);c%G3|?|LXYU6^b%Y%hFJ$#`n+v zlKYcZWPxQ4?|*=W-A3L|ht>3d+7f}q|J4D?TEVpbIlCg}6FkN2a%m?h+y7Ck7M8Xm z2jBsAJ0;l(lh*3M4!|`31)Ki@ha&~_Qd>)#?JwA}te6N1eB_8fq6T)ffCmh3^~}K& zds|!o#&mh2nA^ViotMafyGJBG?#;L{nZ-ZRa`v2h5x7u3&XuE}G*CMN>KPh;|wiY~-j5@7l9=GmB z4TWR{0idAbvdeUyQgbDucb*({C|peqPk_czvgv>05h=Z?B~v zeS2X^^0!wS&fi|y!wtRg8{FBRzP(gq9aX`r5zs-6lXy=se26gu^#tP)q-jz=j6nS$ z^LYq54aH+{PcR-snuhvk^h6gfjfN*K82G~DiwT?H4z>yK8`drG+gWMnfDvFBAPh}- z7Dn+*G;IWD3{SHb3*lLB;)%cy@J#1dz@oehHuGj!lwRbXL0borK9l5@QD-16)tv+n zJ*o$?-LG=4($B2_xRxZ_z=FdR6_h6+g-|gK$&Csf3-kx&WL7~h+;#*XoVZC*u)AyNQbeNpthLKR`- z%&B9>1^Kk)nU!z8cGVx&&AL0mkZx5QjlUTGf=6eMNI0?R*=L7t59gilc=w%4@5Acz z+7XTAW3>99@%AW<%i}cW84!)-ztj3l(@^V%Xxu(VHWc+|Y={@A3ti{(J$QdvM9AL&W#pLp6{;AJLihzymczu)gW6@l4~6!vRu|((VJsIiUR<&G3~|MO z!Y>H?tSVbP2yftg3ow+##^yEfW?lB3Q0_L)J^#bnF$c#y^O7-jo;WPtdi_bGgTMKs z2anAgu&-U&+U25@WO6$sf2H*>=)m=n#6W46DU<$~OhR_mcPzK#39f%61`cgywZ}$a zO7aMx_TDHZ&8CDzZF3Cb2p&V4Ho~N2UYxJ^v@dI*NR%Jm<53j3G|mrv&XzS0P#}JQ zb|CI-bs7`;;Q;glRY&>%&kXbN=C(&8|8Hl8LAf|x?l*a)EY2fNP&b8n^-UTDyjqS?u!D@( z^5Tw@#H(iiQ8Dmc=2f#+7iPmFFdjStc(p2uN4q$enPY%g%`v2D@0)lOx5a~NikWy^ zDLow>rPbMCL^S$wRWT%+3#+)Y#2lqX1G2A_ae)l71|0jdQRtaQUK7&USd$EMl)|_M zgw3UvLIdJVK^-a?PBl5++0VOOxvqKfmtVr^ zxA)u$%5^d=BL(}(pN-2+S|tQQ`n2?7XV=Un#$7M(F|y$`R)=me174=Ku-5aecbc=t z@i@}^s?s9o&=!zl(iXJMrY{w?v*t5#8k8HoD3=pos>kp%n{unPm2C{o=tWtVxWAh3 zH%U0NjrXcXFH1M9Qvs?U^Yh9qzMq0|p2R#0q-)IQ8TZ;iDIGML9w& zu^`YwG@adrz1X)DAVQz|b;dqrj69B#48 z8PY@lWYNDj{97r8x2nk^?s%TQ3fQpw9rlI$K&uH6bJ5_Vs9#hE2#!2<%M zW9Lj`F&h+sZ4)7(Fe@c3BODGSK~j8p*_%&M^RSi54N+^Y>MFVWmtUh;Ua;wm`u01g z|Gt0rA4(=)|N3vgnKsw^w?7{~DGxpO>Z^YfuN%3qeRyU4qw@3fZ~gk(E3tx@iFG}4 z!Kf$7P*fxfW+di1oX*4|1^!W`w4EaZ<&Pzl=C|Syz15S7b9EAmai&Uekwi*b`wI~? zX~lcsNE37Oh+h)7o{HCuq*8E%zcma4ldIa}M{=((e?0cy{^?H7sWDR}N$jGfvy%ze@AB=@> zzCpZNfmy9Uoj5vAUTpPdhYC}WmKsb6Sxbtuv-8~nfhyGf5l<;b4OtYOQS*^ili%7- zix!muHHajw&E#l76IjSNFjF0hkWoa1P;h952muv2;mx<2*bTkGz6JCt_dNfkInbb=7LsdgfDedz!{%5rCK;p;y34|HclFK(ipM#n5;aw?7^mom+yb}nZDO< zo4@Ug_ogjW)J-NGj9E`VGWi;_>Pm6`>N`-L#Xo1#dZGqmnITXk2eHh;B&6+k4pBQ|IBj7h`-PJ>${q_L6D!y5&?PTAa-@b}qucGtp%8RmNO9qF?DA11f#ev2 zlUvhdjJB+Ok$hI^Asbwr5LMGf?DeU~uWf9+_SC0;I&{=nno-_++4p>eviZSso;TtPK%Nz`Bfov;(Y{oT{$BsT}j5>J4__DQ6cE4CSbz+QX zcfBiTwQXqQdCPhwkZ*g?B zQ5xo#*pjWZc8#_u3(Fy6xY~R>vN7kK89A}>np2&w|{5)D)*PDOn)%PKYEW*_{;d*m0sEx{Uu3JHZ~xHVYcAGF_G8 z`)|ff9COV{W6XiWvXOWS9)Hx_Yc6S7#P{EsNX}fsj%@dxko7d2cgac>J{ycF7Zp84 zpcEhL1a|tXD&lTxj2q)BDsIl9wU{RacLW_2&o)a{aN1loTocM5d2aI})Q-LL1#!h! z!oF|#?p}!NWjM}!DB%*?4siMErAp4)q$Ht$N|zBa{3N%%35_*NM0+KBBl5rC^)cB z^bvV~f2n`Jmj}MKb;J6HpEBN&rwzsrPT(`>nhl>l8Av*-+e6_rm1!BF`TAuJKiimGF%zMW7ZZAAf-$5S(WA;)ID4$DaOt z-=WWN^yG45h-jKNZuUI$8?$?-a=n>#hP62k68h==i1Okfqg_XE1XZQ14vW>&hsp?| zkQ9CQ`K!;7uht(&(@cpb*AOP=r%>sB;Ha@$*=(#H)A;7e1ODAR<#Wfjh zUbFjRoH#M-E|ksDb{KpxItmI_-16<}Ro~CLVfi+3M*({E3GneZM4Z_z<;6zSi*Ouw2a z?1{QR1zN}}he9aS7YZS<1Kk!7Od&6BeDN-cH_C%#2mGN3Cyqw3q@(#}sRCj$#lFTk zAbh*tSoyE-FGvfP?*HeXK7OhGw`)${w^CmD!um&t@9h8Fs;P^!6RLOL{@CC@)Gr;- z2iB?``;afeTLl70)4oN8Eg!wFgXTCp&-a@Ycv*2@LY7bK8vc_lD4~V>BjNv7IVTd& zp;rH7^-1%2_TG%5i^==?h+kC&-U$lN;477y({Z(~Uy!iJ9JGsgO39G`jWiW1hzm$%?U zG~ue_SYs(HGfm)+=r5TuZzY?Di&2Ta07NA`sjkDCTSfm9wBkw)4;fo2yDyH}0z_3! z%#zz;X5AjgY(ad6;ICKlLiLsC zI8py>d|qSYZAAf@O_w~s5DP$ zCIxmFL4DCilF3*=>bCNF%EC;uAgQAmW>dEp$dw4Bbv#pukEiP8AUU8ZFIlO?lVjAk5b zW4a^Hg{Z0=;gMSCjuJ1jhv|-A-EOVTjh)O(8Zk&=l4s(`?&pgYbOX9PTIm;Yp-Y?<9oMnzPKR!-%8_rtDoMnzP zKaNk!H;8G%oP}{Da2C;obv{WBbh)X}qMWsmISZrFlPbFFkj{59XBD(saqAiyQNET& zl5T|OjYg7NMuHtWn?{ny(g@OxbC_mv-ozTU8KI{%=f8~56Ao*^_CmQT18 zNL`|IF~7AOX<>SeGVfb{LKXqrjp`drFFeoGFl7v9FAJm+wk$ciLiECK@)JwVS;pyw ze_{;!*76uF-&(!R82qiJF)&LQa{)dhx7>@3~Tg4JzV{MMWE}(UMaD^ z(QAB=dicT*)?}%LbOb%@a(|a$LevC zKNHm=;Vnlo9$#yU7#;HZUfv_UusCs&ee%%!{=Mr`={jNZO>^c?xaPLG&vp8H&o$Pf zv`~6chsn35=cJc(xNd>5>GFmv2B!SssjP>))w0~>?(Xgx z?nQ2kdmHK{(<@Qd6SFI!>0QhV!Pc)gI?S<-(P}#kDa!L*-Z1HbR#;dUG-eb{bYx~! zSV!7>8A(xOqS$q~W}%Ac!+?Xql^^sK;244E?sy8#(H5>Cir@l6zrO@xZ8~_+Y=wAF1z_ zGjB@o%c{%r%THF%>d~?9u+niic<*(WLh(s{co6rZ1E7Xb{&$ny&`vhj>wIccx$_557%+HN^x$K72zEO;2{59WBPh8d+wC3Q(Q ze~K(8`csj9u4@Au^a7DGsDXx!P0396q&go}q8rKxlf%>u&~QTqOHxSH&X)O=8UaxmT^3F#A2Bee!Q5dari2ewC2|}nB7qtuiqA?F@dJLh zViOjhWpIPl;qxg-2hU@Ei-z`FMTRLo6~~9nW4_#q9KQ0JTx4RXGj@L8e676UNtF+QG*qngB2_SF6rnJneA3m{jr|pl0FdbaGYrZ zA%h;Pb6^9i(Z$FaT|IWyGZKOVpi;}SQN47tML8-B%KbhS!Z?Bk4|feXH1dgc#*3Zq zDxBI;{;~N`D0hznt!HvT>2U}@z&%Y@aR&`o~-BjX{f4ts12q^7&&Jw(`H2m;%F zSh=pi)(V~rwCW3<$Ej?Ca54!fawMVU;3X8g*&-aN6+N2m%0HX8W0dbdeCDUm@dnBU ztmQYPk&Ok8dQzdIeuw*CA5czI}ORUb~Wl!ong=%Jf>iNm5a}a$9wkmWj^qO8a(sQjsVs zP74Ggr3J+bayal`ISPf2j^MxYou>M0$>9bQP+md>e?DVh00>V(m}-Wb&TA5Rs&Nnu z3MH3|uc6Nqg0?leid=rr{KbQ2HO}>hhh5P-=k^(suP-Sc6lveJ>Z&hdF- z{&?U))w)gDICfV4qVnM>q4fN`n)=Fy>&s?(lZx^S%5y448Q;oTbBz)5{^qacU~{=x z)6{&7_H7xk+HqbV7Ih7%Y?I~-bKej~*X1)7vemCP?@Ku7Ncj+Wei%IZ3D7M4>cW~Y z*`=nZhkQ!7FyzV1%ViM(G|vL_g{p=ubyBRC|{+O3a{JSHPXc_EsZ9m{jD20RuB zYOM5eQbi5N-=k-6@|hLq)*6|;-W&eFGSi!g8PJ|k!CsJj0I*N7cdlsJW6;m- z@t+UEyj$m?O<;s(n9ioRu<@d=)wtlqfi@xqIEW(V!v%x7?B_g!<8Sf2QW zb9iDtWdcT@7-;;}e8L*t-Cg(?PdsWH8GmAs@fY(6HMaj70Go>HF7OzVRa{X;6vG_F zA8iBTzc*M)F@G<<3fqk-Y8pjw=-uGrQh65belK99aj?*3_CIGg8i!nc`_RTdtX=z*oR>~!+sau!JQ!tuV6To z?_bH+!}$6tz8=nS1jF0-U5gnmVYrmxZy4Ur@CknJ(>%g6{PwjBf6H(k!)F<;XZRdH zxq;#D7(UPN_Y5~Pe3{`Z3}0oqh2iTA|H!z#!SGFnTN%F1_`Jh!*}>O4`TAYH-o@AN z@d$eu?q#@-;eLh(7#?JJh~Z&|M;IPu_!+!HI3cjx7>uScTBg0M%yD+R{*n?p&hW!{0U^s{&>m`LXk}{m{j9@sD z;V6b<7&0{#rlvBHXsR?aoWgJ#!|NDc&u|8D1+tF`&Stm*+@i5Y)mWoytWhg6-NTX`-eG?>E(g6-NUk-BG^!?% zM%5(JsG39?Rg*}gY7%KwjWwz!NTX_kG%7k<({Hgx)dXo&O^`;_1Zh-FkVe%6X;e*+ zM%4sqRE;&NCP<@df;6foNTX_kG^!>@qiTXQDhe;~^Q2KV)~K2wjjFLm)mWoytWh=A zs2XcjO^`;_1Zh-FkVe%6X;e*+M%7rOYJxPXCP<@df;6foNTX_kG^!>@qiTXQswPOI zYJxPXCP<@df;6foNTX_kG^!>@qiTXQswPOIYJ#cE8dVddQ8mG|V2!E?(x{r?m1m8r ziLdz%X;e*+M%4sqR85dZ)dXo&O^`;_SfgsJQ8m`68f#RIHLAuMRg!5LHJQ1THL50)M%84}sG3X~Rb!2+$)r&=nKY^< zlSb8K(x{qD8dZ}?qiQl~R81z0s>wePWQ~fmfP76FRZ~c#Y6@vojWw#KkVe%M(x{q3 z8dXzBqiPCiR81j`sp$ z!w(sL%J6Rt|IY9Wf+CTjhoP6DpJ5(hD+(AE)A*tt!!m~L8AcdZG9*g51yRZ^cwV9p zkJAV`y2W&cvv{-{_?g-K(>Z*76T_uE&g1;d6a3S4e7%LQ|H$wSzO$7_+kRmbMkf92 z7N77>kMTI>ynf>A^9&7wvc!zipb`4+yum7lqd;S#>{8-{l< zyp!SG44buKFuaE0XokFc3a_3rf!0u&#BeghsSJO`a5}>ojL$5Fvl*@cJ|3wCbo7Wk zhNMG0Viv>48PXTuBi>-RgCS``k06cbk)NYGSb4gBnXg~r>o@s&D_vvOcm}hkYxJrJO4oqeNl5FZMn>x#;&a$bqZ0ZuprY@0e>JrJOE|F~N63M16k!l1*JA+0-SHOVjlb$BF@4mQ7udZ0anVx**xq1<9r^NH%prvZ)J_O`T;^XW7(QHg!R=sk3bASa}+g zWK$O;o4O#`)CI|=E=V?YL9(d}l1*KZZ0dq!Qx_zgIw(bVNH%pr{H(KV>MWbOAlcMG zJ9?62Qx_zgx*+b=SvGZN3fu&a$b?B%8WSvZ>1?o4U-iW7*VMHg%Rwly{+LST=Q*O`T;^S4cL| z>6#(Qrmm1|>I%uGu8?f%3dyFfkZkG-$)>K5Z0ZWhrmm1|>MWZ&%cjnr+A7UI|zh8n{HJedcnAy_J~bAas7HE~xS%T6AoW+SdU zF{CeA9;AkT`XIxH7(UGK5r!)nu3|{ikq7CZ=ig`e0mBa&lFgF`=^#ipPadQL5Yj== z!_dpn&yb`ekEJ6IoDZy+^YfVV^T7G^TR-vr^9&7w%z=5bjeb`qdnpfmh$lf2g8dl| zWH^}N6%4OrcooB|88$GyhT&+2<~X#@dA!bfyv}*N&iRrXZ_k%>hIx2CAM5!JU@dIO ze5@zI&V0WMUw36lR&+l0Qv{bVBni#Oeu^Mj)cMdk^t*5K^$v#b5`^}^_*fr;)$|P3 zhakU8bmnV*i|EeRJ^8nuk63b3ZSd$4sl%pbTvWZ zx&r8Gg2ZnH%x?wI#&k{mRsd~Gkoc{D`K^HYt$_KhfcdQe+895DHYP|Mgg3O9AAUAaP3p}>!q{cgHE~6lxgyM55oWFkV{c3Mi7Ud)6=CLzFmpwi zxgyM55oWFk3w{f8MHqWS`Yqy$Frt_aJ-6=CLzFmpv1y9v5O zToJ}Tf*^547<&hT#1&!e7YGtpgt12;NL&$y*1}tuE5ghbVMx;jsW^E#CCI+XJ|l=C{2^E#CCI+XJ|l*9U>5mqyNoFTFk zapwshhvdDSSE-y=shn4-oL8xwSE-y=shn4-oL8xwSE-y=shn4-9Fl@@ASnckX?$2; z1j`t_|93nh27{D2LP#JkQV|2&utO@eRU?;TuGdv_Uy+A&k!yDQAk5 zGeydoBIQhxa;8W*Q>2_JQqB}9XNr_FMaoTzz&4=KCNP}Da5BTG41dKCc`JBk2H^uK zBRHGk3g8oA?S#J4(Do6QtO#qT2y3SZYo`cnrwD7O2y3SZOJ9VgFT&CnVd;yo^hH?u zBCMSvEQ1l2!3fJ>gtb$IwNr$(Q-rlsgtb$IwNr$(Q-rlsgk?6u+9|@?DZ<(*!rCdq z+9|@?DZ<(*!V(=}iH@*DM_8gGEYT5`=m<-6ge5w{5*=ZQj<7^WSfV2=(Gk{85!Ox- z)=m-DP8E{dI4f01I>S8JX%)Om6}&zbSRcBxm?2rV6<8mFWZza`eF(nIa0kP83G&=4 zc{hh409RgGYm5Q^%LE1CM0O#MoxekD`ClBr+G)URafS2Fc0nff(Yx25p5dmuG6SUtL? zZ&MA{a26oxlN#2IHLM$JSU1+-9zD|w+MovBczUuA!+M7O7!CnlY9!ht)W920&(Kbx z2HtqOru{+A!#cSJ{(O4=8ODDt!{0Jo$M9K(>lxC1tp@&lg1=+nZZ+`d6MU877KX1g{C`L~`}nx7`poOj?Y3-zR28tPI_#%xNhUX7979{l9?LZ! z)DV}ng2YU+L@9~0te3DgsT{(p3#C-jXb_tM8}t^%(qus|M)v6AWaZ$>Bgv76(Nrjk zBJ5TC9*B`$aJyalrk4)d=lSNJ=kxoVx%ZxPp5Hmo{hf2qoa1q5t>*KMlb}a)wH4FU z&a?Wpn$u$Gj~;k|K4ptUk8l-I#A2kfm(eXa9-~3wSoJ4ZQ%Z1 z8@RvM>g#~f@95f~&MhSPUGRgTzY)~x8-ZBWHv*&IZngSS;B?Q*)&?7-l#Q{N?}~-s zFMy7$YKg3BHPf!V)E{-PX4>^M-hj25Z+FTg{#E@{wq~dGt9q;LcVT;Wx>mE(PWS9| zt$MC8L5gRmYr_cpcI@|Hdv>}u+=A`d=~~TB`w4eoZ^M2+_6M*%J6)^UXIiV4}rf2dK6h3(p!0h>-=WYJw~Vv8?Zf6sO4>58`6t;r`Lw`V&3evn#XqT9y`=( zHrqCRIeY+{z8pS??a@T7=C^%~qlj9~a@&4`!%xBFe(=-aXF$(|)@qj9_$S=uneFY; zu4Un`g10C(*e*Rcwt{V78f*tM;0#y*i$*E4P}-}f$>T;ZehKJZ)Q z@@;Ss90G^I5%4hh9dHyp0v-i(;5c|3^c?99DW~xSI02p{$2>R*PJuI&`83yf4t9sW zg!hlD9i~9p=`B(wNJHwS-0Z(_e2`&Q7g#12I)zB0nT9osW_I~2V*eGB&cu(x90f$iDj z9g1gsjptQ%D5|mj+t?nw z{w2lpbLd}EJlpgyDV}XulH%F^1a~=l*`d*mb8+;tLt`AGFm;7T6bZz zdL&VgBX8hr9?8J!kwiU`s7Dg@ zNTMD|)FX*{BvFqf>XAe}lBh=#^+=)~Nz@~WdL&VgBQI90*k<@!ucPU;{nf11{ZS_bhUUG`nBZ+z>HR`c#^+=)~Nz@~$5s=fZ9!bSZ zwyhpX)FX*{BvFqf>XB5uQI90*kwiU`s7Dg@NTMD|#Y=vI)gy^|BvFqf>XB5u!@`dwXTyk_9^|tpjQIaNgIuRBh;~etWMf^TK2u9d;M6Qw9(gi{aBr}aZKp-V|5iS zNu3nZIktjrpjX$_Ng<71V^as)b+BCr+jX#A2itY9T?gBBQb_0ZZEz4A0*Ap7@G$rt z&|mrMq>#p=U=ADykAwcISSN)v`rBxo6w>IGW_7GItCK?7_DZulDWuDMnrjN!-@`6q z&tjLT`(Ix6(Hg!@+qgScb zNg<71rB)|}G}6re7o-=PC_(oEmwF=m}K)3)Q%I%%eDD?^<$(>A?QnrYi(%sOeN?Ke2| z+SEE}rqL^@>ZF-QucWGzW}dFtCH1%=bY!(l>S6qC&~eT#;+$Q?IlG8+b`j_7BF@=G zoU@DgVHc6ZE@FmVL<_rk`|sktzl%5iF5dOKc$@FyJ-$orQ@N;R8XcwY;_bPMx6dx# zJG*$}?BZRsi+9Z~-ZHy*zwF}8vWs`hF5V`)c#rJj4f4CJ2m3vJ0lA@_uYTDW`z7$r z!aGU7lk_{8k-L)_xjUJWyOSBYJEeQR((_k$2DMz8e*L$bApF?_q9d zPvG45koz8T-$U-duiU>-@%zeMsN9Wj7T!(nca!_w+;um1H4sZTRQUbXp!bE*k#hqv za|1DL1MzAD@oEF{Y6J0V1MzAD@oEF{Y6J0V1MzAD@oEF{Y6H<`gJ$;pWJj0{#Fh=j zmJP&~4aAlW#Fh=jmJP&~4aAlW(mLHGl{0$$*dS#yQf8vB2BMt?qMZh!od%+v2BMt? zqMZh!od)$;-AjbiKy1?xQfu`}r+Wm{K=jf;+|oeA(m<@zK$P+^`1}}rehfZ82A}tk zeh=yQkbV#8_mZxELCKr<;{AK^{=InrUc7%V-oF>`-;4L}#ryZ-{d@8Ly?Fm#ynipx zzxR#j?N1I8_@6fHkR%TLkrQ?&dPEk8xePto#IwEPq;|9NlT_e70#CMJOt`Xlg;=4wC*NE>L@m(XnYs7br_^uJ(HR8KQeD@%1KM31e zdn^96Vh;4o?SruWAZ$Mf+YiF_CwZ&3NL!jJTBI#Tk3m`#MHsz4t)=1v*lvw26<*uf zQsMP!Efrp$)>7g1X)TNtS{Ny`Fj8n?q|m}hp@oq`3nPUVeV6q0j>B6RowYDJYhiTO z!sx7p__>AASqr1H7DXDmo_M$=a3tKKNW<+zQXF@Z1W|t?=9m&#my> z3eT3eT3eT3eT3eT3eT;fd2WU0Hh6A>=Qen5gXcDQZiDAGcy5E|Hh6A>=Qen5gXcDQZiDAGcy5E| zHh6A>=Qen5gXcDQZiDAGcy5E|Hh6A>=Qen5gXcDQZiDAGcy5E|Hh6A>=Qen5gXcDQ zZiDAGcy5E|Hh6A>=Qen5gXcDQZiDAGcy5E|Hh6A>=Qen5gXcDQZiDAGcy5E|Hh6A> z=Qen5gJ=EMP<==L_5iILX?RYd$3)9{>z=QKR0;W-V@ zX?RYz=QKR0;W-V@X?RY@SK6?3_NGxIRnobc+S9c2A(tUoPp;IJZIoJ1J4Af#(c7 zXW%&l&lz~mz;gzkGw_^&=L|e&;5h@&8F@SK6?3_NGxIRnobc+S9c2A(tU zoPp;IJZIoJ1J4Af#(c7XW%&l&l!0B3M)%HV7LQ@JK(khZad(x0}eaj zumcV|;IIP@JK(Sb_Bvp%1NJ&#uLJfvV6OxAI$*B@_Bvp%1NJ&#uLFKMsCx%>@1X7- z)V+hccTo2Z>fS-!JE(gHb?>0=9n`&px_^~A{txg;@GrrqDjb_VRpHp|Db4yW3%wfo zDYc~=!X&tpbk7ewRj~_fA*B^;1JhtTm;tj~IfGpQi$=8#Jzs6ZSmSHdHjL!Oim#_w z@%2=&oAi3_@@nL#)MkwT3jW-vHe+v(e!kj_@o~_rkvrk76W%)EtrOll;jI(iIxEaur+VTIp?T}nEVon4 zTPG{!I$0^#sabBPn72;#L|PI&8tw@!HLgttz3>x8#X&7JBA ztd#47w@!HLRA1Bc;jI(iI^nGo-a6r}6W%&mDc1>ao$%Hfnzv3?%5{e3t&^29H5*7lyiV`4p7bk z$~ize2Po$N(DbB@fB(h@0=rs~qF=O-^iL970c5r1U*adcjJzy``2YQV}w!&*9 zvieG5^csn*zLFTdMk1@PBu1~1$ZCGu=rs~q)<|SEzir!VB(j>{HhPUjmNgPt)<|So zBavl|M3yxYS=LBoStF5^A6;gzk;uxMw!KCoE1%l-8i_2Us;p+nZF`MGR`cYxy+$Id z*>c-nBazjdxoxkJ$ZF2q=rs~q&6yj$Mk1>@bEDTtWGlQzBFh?yETglmzPUK%N8sz= zRnTiBvh3cI4ZKDo%NmJn;58Ci#&OxeYb3Ia=CXm;NMsq)WdpB~$TG6a23{kP4ZKDo z8+eUGHt-sWENdjPtdYpFMj{({jYKx^8i{P+H4<6YNMuK8_@k;tld*!CKUY|OLGS$!k0?eF_p^&0)k8i}m>j%}}z z$f^g~_8N(-`jKs~k;v*Rl2g1!A{%;*L{@#uw%15x)w67SjYL-c%eL1@WYx=TdyPa^ zea*JlNMzOHYBFQClRixPFzF+tkB~k>`UvTxq>qw5%D3rJzD`8GYux9L&7O^@oa-3X_lgn{(IZiIe$>lh?94D9K+(HtJX7n}rkPK0)pi z)Nz8`C&+z*+$YF=g4`#_eS+L4$bEv`C&+z*+$YF=g4`#_eVQ-D(|jqOR+KeXF|8=e z=qPKNFU8Y(e<_78#nXC=ja8hYY^NyODav+=vYn!ArzqPg%65vfouX`~DBCH@c8ao{ zqHL!q+bPO+in5)eY%fx_7b)9|lm7u=AGf4JHy*{ zhWG3YZ`c{$tuwq;XF`9!o(cW^dPZYLqxZ4V?wINq+Oy4w?@r^p0{j=?zX1OQ_%FbJ z0saf{Ux5Dt{1@QA0RIK}FTj5R{tNJ5fd2yg7vR4D{{{Fjz<&Y$3-Din{{s9M;J*O> z1^6$(e*yjr@Lz!c0{j=?zX1OQ_%FbJ0saf{Ux5Dt{1@QA0RIK}FTj5R{tNJ5fd2yg z7vR4D{{{Fjz<&Y$3-Din{{s9M;J*O>1^E9S{C^MrzX$){ga0D@7vaAM|3&yO!haF| zi|}8B|04Vs;lBv~Mffkme-ZwR@Lz=gBK#NOzX<(U+ zFT#Hj{)_Nmg#RM^7vaAM|3&yO!haF|i|}8B|04Vs;lBv~Mffkme-ZwR@Lz=gBK#NO zzX<(U+pN0Qf_@9OUS@ zV50;ZCDqjq!DZjRc`QM);6H%IN}sNEd3 zo1=Df)NYR2%~88KYBxvi=BV8qwVR`MbJT8*+RahBIchgY?dGW69JQOHc5~Ejj@r#p zyE$q%NA2dQ-5j->r*`wyZl2oBQ@eR;H&5;6sogxao2Pd3)NY>I%~QL1YBx{q=BeF0 zwVS7Q^VDvh+RanDd1^OL?dGZ7JhhvrcJtJ3p4!b*yLoCiPwnQZ-8{9Mr*`wyZl2oB zQ@eR;w?OR{sNDj!TcCCe)NX;=El|4!YPUe`7O33*Qf!Zxly9H{uK6MYZ7zr*i5?l=YEp<^NLEq(Xsf*10E;9GK82Fpu zqIAsYSZk3;W-;b(sf!vX8vQMGQR778yFq_TT@3wAa8cuZqrV9*YK(96x70y7>< zxF{Xd^QB`(e@k6t?)Md9|a%g*K62+ zqm}2c5Rbh=B({VvmhiUVhLX?;fp1Fv4k&{@Wm3oSi%=e_+klPEa8hKe6fTt zmhid zKjfv|<<%0j&oSsR&N6u|lh-nNEtA(Wc`cLIGI=eN*D`r6lh-nNEtA(Wc`cLItK@Z# zyv~u=IqG$eyv~u=Ir2J3UgyZ`9C@81uXE&ej=av1*E#Y!M_%X1>l}HVC$9_Sb%DGt zkkc?ye^T~CGxsNUYE%0 z5_w%BuS?{0iM%e6*Cq10L|&K3>k@fgBCkv2b&0$#k=HeHxkfJ6`1KmUuA=IzsQN0Z zzKW`^qUx)t`YNivimI=o>Z_>wDyqJUs;{EztEl=as=kVZ_>wDyqJUs;{EztEl=as=kVqQ1^5~(z}Hv-zE*L8l3X$d{(`m^_zT)v@HWu@TUlcT z_!=v~*H{6*#tQJYFzH`I|L1Ov72s>E0AJH=s#E;Gl{Hp?uZ0cR)H?h)w*R-X#tQJY z(Eqnx3;jR+HCBMHu>yP@-qzu59p2ViIlm5X>+rS?Z|m^34sYx5whnLW@U{+b>+rS? zZ|m^34sYx5whnLW@U{+b>+rS?Z|m^34sYx5whnLW73OUn-qzu59p2Uh^R^Ce>+rS? zZ|m^34sYx5whnLW@U{+b>+rS?Z|m^39-6mxcw1-X{5rg?!`nK%t;5?oyltqLJy@}! zUS>?_-VJ)z20d$op0%NOnbZBQ-_RS)w!OKbciCy7zX5H~?>6Xn8}z#k`rQWoZi9Ze z!LE86?5ek+J&pae0noeZZO|(>=#?Av$_;wu2EB5FUb#W9+@M!(&?`6Sl^gWR4SMB< z-i#`b-i*fg`1$Orw-Ic`_O5yx+SAzRe+X{q?ddDMtKNp*o<{e+4ZS6e{|f%xsJEnk zl@^IBX_3)04;$>Nw}Ap|pa2^vzy=DifdXux02?U41`4o&0&JiF8z{gA3a}CGbE()> zZzKHA*#8B56#TE?0q`-GM{iZ*w2V*7 z__T~q%lNd6Ps{kUj8Dt>w2V*7__T~q%Yl7b#;0X`TE?ekd|Jk*Wqex3r)7LvR^+3y z;nOlcE#uQNJ}u+ZGCnQi(=t9S!n5a%i8H6)A}~d|Jk*WkpKM6`S~U6Q6G4(@lK3iBC82=_Wqi#HXA1bQ7O$ z;?qrhx`|IW@#!W$-NdJx_;eGWZsOBTe7cEGIb~dBuunJf=_Wqi#HXA1bQ7O$;?qrh zx`|IW@#!W$-NdJx_;eGWZsOBTe7cEGH}UBvKHbEpoA`7SpKjvQO?_lj;A4LjB)RsF8^9H$ja=WNRcM)JR0Ak%&+u z5urvRLXAX(e`DJt5uyHn7X)r6Lg~3s8YtAinS>tz_5T{#(sQBoTqr#kO3#JTbD{KH zsBij0ebX1}o4!!r^o9DSFYE)K;R%O8>ABLS=R&m;q58g1-_V8ndM?y=bD_S23$;st zP~X0VSB-8bLhZsWtODN-O3#%-UEEG&Zvmy}veoy6(sQBoTqr#kO3#JTbD{KHC_NWS z&xPvyLEv^Gl%5Nv=R)bZPzoFbZYRRKLH+Yx_D8{cz`bA!)Yn`6s?mf{Uu=c?Rx9Lb zZYQ$;6DU2Gt-dc*-xsRy3)T09>ia_Jxlnp8bUO+0X^2lld>Z1@5TAzb`?|(H4e@D+ zPeXhf;?oeHhWIqZry)KK@o9)pLwp*#@9R1CY3RN$v`<5P8sgIspN9A}#HS%X4e@D+ zPeXhf;?oeHhWIpe-w#6feW86C;?oeHhVJ`Hu}?#M8sgIspN9A}#HS%X4e@D+PeXhf z;?oeHhWIqZry)KK@o9)pL-+k4#HXSAzHIw6bl(@+ry)KK@o9)pLwp+I(-5DA?)$pZ zJ`M3{h)+X&8sgIspN9A}#HVkPPj3Wol23&ytx;dAgPSV!O-iV5QbMzIlRSG`s97DM zW?F=r)e&k|N2pmHp=Nc2n$;1uftuBk-413zt@KukW_5%GuxOMo^nCfks97DMmEk7w zY}^TwOQ2aDrD#@1s97E1I{2@kW_5y_#J^FqIzoLr6KYl`xXCjKLe1(3HLD}ktd3AK z3Bubz&FaY3td3B#I>I|Z&FaY3td3B#Izr9r2sNuC{JKhB32&9~RtaxD6U6D}trFfU z;jI$hD&egX-YVg(65c931EcHBTcu}UgyyXh-YVg((laoDPaDzm;jI$hD&egX-YVg( z(lao+#=KR+TP3_z!ds=oyj8(l6}(l! zTNS)j!CMu)Rl!>oyj8(l6}(l!TNS)j!CMu)Rl!>oyj8(l6}(l!TNS)j!CMu)Rl!>o zyj8(l6}(l!TNS)j!CMu)Rl!>oyj8(l6}(l!TNS)j!CMu)Rl!>oyj8(l6}(l!+uJ=8 z65Pxi{AS+ZH+#nbrFK)=EX5zEa)EH`_{fZ%42e1n_4V}S5o;BSHnFajOP+#GHJ zw}RRwOev0SZq^Dequ>5Fd+aQ9RCBY(&O)tT6MhJ!JmE*M{{YmSgMP(FAwKfhSt-`8 zo5Ke{%{j>aB!4TT})t!4TT})tFSBLg~wO02T?fq)+7a_Fw ztMPs{-mk{{)p)-e?^omfYP?^K_p3c~qPy() zm@DrBwa2wmw5zjFd$0@d0kwOx?7i69y;*h&TYIp}*1Afe_4AerYt${Cffu^1-l7?J zmrZ-H3$+KkunkOu?O+D%;QCIm3+x7az+SKq)E?}5j`m;|Y7cgy_Fxxk4|bvUU>9l+ zcA@rQ7mk8QK<&Y<6z#z-)E?|Y?ZGb89_+&Jg4%;!w)S8bY7cf{9@HM}vb6`haGH{6 z4|dtwgI!p_)*kG#i`d$OU3Q5pwFkTGIqdIa&tq#3cBL<1YY%qW+JjxFJ=lfXgI%}` zY7chV+JjxFJ=ldF!``C4VEZ*}?ZGblN7&kfUG`P%A7ih(_%f6YrszI%qR*Ke03$+KkP-k8XwR%>l)w4pao)v2KtWc|G zg}(#V@=Wc)t`zOTF4P|ELhZpWquHR|Zc%@C$|L?&ahh!Pef_Fv&9?Sn7itf7q4r=GY7chdt)TW` zmwg+y_F$K-J=lfXgI)MuZ0*4=TYInzwFkRUd$0?&2fI*vunV;ZyHI1jU;iq77Klo|zGvFVCp9TMf zyR-*;aI4;2M(yMl+$uFTYNsQ$9&1_xO-rC@2{bK%rg2V|e)U^8fu<$Uv;>-#K+_Uv zT0(EYCSBt;lR(oFXj%eIOXzLrbZc5d??l_yv_yq9ErF&b(6j`amO#@IXj%eIOQ2~9 zG%bOqB{cf*bF66zjXsRlG*0glTGKeaOK45w^e&+_EulBEueYWp(6j`amO#@IXj%eI zOQ2~9G%cYwvhT8{CD614nwCJ*5@=ciO-tyF>}#xP2{bK%rX_r?gi@?&2{bLCv68Q` zrX|p{gx=k@t!W9p!EIa95_*q2#hRAT+uXJ_EunY1ZEIRWZ+6?(v;>-#K+_UvT0(Dj zr(4q!Xj%eIOQ30-S*CPr8YhROAGJ(0ErF&b(6j`amO#@IXj;NwnRTT# zErF&b(6j`amO#@IXd36N=^EN6nwCJ*5`i@>fu<$Uv_#CBmWWx?5@=ciO-rC@2{bK% zrX|p{1e%sW(-LS}0!>SxX$dqffu<$Uv;>-#P@E&rqG<_5JGQN92{bK%rX>{lINh3- zK+_UvS^`Z=plJy-ErF&b(6j`amO#@IXj%eIOQ2~9G%bOqC72mYplO^sr(CRQ2{bLC z7|FIZjT7jE^kOtEfu?a9ozkso2{bLC2+FqOlLVT^`E;_aX`E6gw5BD{v;>-#K+_VT zH7yZZ(-QhWi_w~v2(4*}(3+MAt!W9Lm>k@Orrn07-G-*!hNeYmT7;%WXj+7(MQBR(;_r2B2J6YvfhhG=Dnc) z{ViMnQWxr9>O%edJJ>=ww@}V4lyeK^+(J3GNX>kW%eh5rW^_5XNEwVS=N8Jjg>r78 zoLea87RtGWa&DoVTh!iky;_>l<=mn+W^_5XP|huCQMO&qEtGQ$<=jd+w^GinlyfWP z+)6pOQqHZEb1UWCN;$Vu&aISlE9KluIk!^It(0>s<=jd+w^GinlyfWP+)6pOQqHZE zb1UWCN;$Vu&aISlE9KlqIk!>HZIp8x<=jR&w^7b*lye*9+(tRKQO<3Ya~tK{Mme`p z&TW))8|BHZIp8x<=jR&w^7b*lye*9+(tRKQO<3Ya~tLS0OkAu<@D)|Hv*r` zXmtDZ$&5z(-6t~|?RTHaXtdvbCZmvY`V__Gz^5o0-9CMaqS5Wsrzjfjcb}qYwBLP- zqS5Wsrzjfjcb}qYbo=x;Iemtp(dG2%fkv0prvVBn zr_cM-(nmk`#{ff*D%jn!#rmV^PDxz zbJj4=S;IVM4fC8e%yZT-&soDfXASe5HOzC?Fwa@TJZBB_oHfjI)-camqX@*g=fO#E z3e>4FO7|Rijr?faGvPJzrftuM*C_Vzy`B}XQS4#cbK^CNJ#2f1yhgEy?U%7%0X}ml-4NraJuKoYZQCx6nohAOnZ%D58Iw^uTkt_yBc)MtWoS?bla;@ykT_Ps|nopY7}o6e+R5L zGtAl6FlSq%xWd2Et`t|uR{K}`RQosHPl`^Bk?lCYMv;TB@eFy5A_v*(9r~5o-5T`~ z+wbzP>M6E8&tIedVq2%i2t9XNqh4b>!q%xVvOV)qqaI{?3${*;k-ZiB4s3rBs8OGC zy60VM)U#~=HnzVF)hKc>CP9B2s!`-%{18Z=Qsm&0e}t5~vHt-353w7tKZ;HNQsm$# z(7zNp*rtCmlU$?7!B6wIq#8vIwmn;0qsYOwXKQN|IoS5sr5Z&Jw&75bgY8d&`$3%= zqm<8pIyFZ2XN9#I0cm&j3a=*e387;`uOi@V(4dxC_geW*Da^h5oW!xf=kaOxPhDxW z=4_Yd*tQq8GcwvP&9Q9`w@Y)hc`cs+=p41vh)_F?2({CQP&`S(CPD2qB3nC+2tNc; zcSbSWrA1EnZ1Z-FVr+Z1dAmk2wm*t}4@kdb6ti7gvHE&tAwaBOD8O@JR%`;kyk`-)*_#sXS5di>^!5j$Y^4WPtYmv{+Gg^y$ zcAn8%lp3z$5v-6DBBA=aSv=;g7JfpS9XXhEMMLs*vXf5*Dc}8oI&(1Si zi+pyT(OTrQ^NiLapPi>?qD4MC&$hM5XXn|r7WwQv+twnVooBQb`RqKSwa91Z8LdUh zz*^+9^NiM_q~=@v9BWY$E%Ir4;tDPDX?lLX<87a&XWLqoM2mcyo~}fTl4y}n)6+F* zkx$dJ?SACb^mHX!}o^5N9Pt&t)E%Ir4PO%mx(ITIwXWLrj)AVdxi+q}% zZEKNF)3a?Y@@aautwlaf&$hM5r|B83MLtc>Xf5(-dPZxJPt!C0zH5yZ`7}M-)*_## zXWLrj)AVdxi;^Mz4lVL&dj8c~}o^5N9Pt&t)ElQ$AK26WIwaBOG*@i>3 zD5m7?Kt;J=-P4a zmC&{0+$*7L$GKNR*N$_qgsvUuUI|@0&b<=4cAR?^aPC#WxmQBhj&rYst{vxI30*tR zy%M^1oO>m7?Kt;J=-TbZce|V4Z=!ml;(Fdh^}LDdc@x$1CaTwJOkZ!EuSenQ(e`>&y&jdWN1y9a=6W=_9@VW! zZ|lW|?iCwGuX3pm5}d}pQ@#*WW74@h@J^E0OGSr8U`T1cJsGVD6e_gq7Zkq6y z)pCAMxf|asypuJYcM+f5MSOCX;*I6tF0p-D=#|5FiEZOf(!JvPu8Lh?3n{H&8<+;$ z!3>z?${FkeSTu?~Jzwk@z2f>Vv1cSNR>0oH3fQ}X-K5uZ*R$B`pjQsxC02!E)##Dk zUBpp$>Aj;|^nNk^2Iv*ncj;|nycN6+yd8Wm_&)Fs@crO#fsgt5V%7LK=#|6w(R%Nr z_1+ik*Om7L2f!wAeqV4<{NEQmPRbK1+kHW^Q}F(Mc>liG$Cc6u|Bdk97~H4p8w0nB z#^4dqBj3j0QS3j#Zc^@zdcM;?NBR@k&EQvzu+az`jmqUl;8TIpLXUGFR4&Gcz(+ur z|3T&Abl2iRmHf2u^S(FuQ@wp24F0=n@nG-;(!U7)8TciB{R?c*p*J;>;<1Dy$|~tBaw#BFj8q_p4<7Oph;!^BRKgZ@vIbT{Ym*~ zIryY}Boy<;Hwz!acMsvahw$A))cPSkrzv;{-#vuy9t!Nchw$A)`0gQm_Yl5&7~egN z?;gf?597Os@!i9C?O}ZMFdlgrkL<%2`}iii50C8Ay$=Tabg%Id(C_qpdV*69U_UM% z_Q@ko|5KH7pFHA}FMwZEIrjyBhW#ae{jzGhFR)+s1udkvfu7IY7i6$Iz^`)UliX$R z>`t!iBBdMb1)t{EKI~_VF|Ul;7xT)feSC4-hu8MuwSDrMN)_9y zr#*r%9>Eun;EPA_#UuFQ5q$9ozIX&*Jc2JC!55F<`?t_T!`dfqT||<*2)8Mf>sEe&y(Nx2XMrd)9vZxF0|6r;UA@GJl#f zf0}$h9sH%P{B-a?g^yCZN2%STT=^(hK1%H#rFM@}yGNT-a(9H1@-sLKKBa)7!Vpe~Pjhs@wH?~oZh zrd;}j4}p(>X6!NL;&dy|V|tFzdtD0OB5a~Y)jcQ%j8@%)V!&wCJxJXTs_wR}x(8Kv|7z7es9M{$ z>K;_BjaJ=*s$eq`sdV^9#?DhHSSrD>-l<)o^SlP(mw}3pM#mt!OZ9AS)Ze4Jps2*!0i*teJprF zxf>q=tp-mhcc)kro}m0sQ2x)WB+J3)=^dY^M|__4-^??cd1f>IYQ|s9_^X-nG~=&k zO4UrMn(LN;X8hHRznbw^GyZDEU(NWd8Gkk7uV(z!jK7-kS2O-< z#$V0&s~LYa`0G!DuV{Yz3sR&TLPvvNkj@w#4SrGSW5QoH z!t)p5`HQ+nDY|AX_!3X}vRE1mzATo6`0mTfOSbYF3tH9p`+`=nu`K)&_!r=l;9r7Y z2fqRSPw<=I)5ciLPf-6d{({hFy4?`E%x#ppjWVZIlI0++k_c4><6DG2Giyxfy0lZ5 zcIwhjU3{w4SdgKF8A_ND=gUfQsWM{Q=<;O5>ayzmZ`4D-qNfRU*A3y9K&#MKP?)di z2~KzIzM|*Y{s!pUeML`m%F{-bLC;Yc(!p0@@~bfURhaxLOnwz6pQP4LQtKyCyeG-) zNf>w%2EN8MU*npuan0Ab=4)K@HLm%Fa=8(FL%9g`eB)b$-{jtJa_={}_nX}NP44|B z_xj|W(?O?vx-9%v+wj&2Z=Gt-N{78p*z1J7PT1>&y-s;k*T|d3UjRL?<#TXO2R$mo zvd|G)kMcD-LVKFBJx$r3rfg4Bwx=oE)0C}W*Ng@Ix<(lEi_iXG7(A>e^aox!-yck3 zzliPGzy9DNDVIRc#q|eQ!GAXD`Ffh3Z~QFyMc*6yGPaerKh^_21CD^-@snetJmEOk zzkuyo%Kq31?7zaEz@Fs#DeP&|PhnHem`69?hh-mZ+7nCujxvk2#^-~e;hs+Kz5LIdN8Q#2Lk_pVIUa8cD)7y z*JU6$3Ff6I1HqK<4d(gPGo=H;0?+aK+ks$_D_;SZ`1J>%Yc~*_<;wqq?HSa8;8pHA zhkYLO8r=bT&AD6xFOzbGXTHWYKLmdSz7AgH${%B|fY-SGI`-d)hk@WHJm&@}e~bNh zl;>yQKal=U;6L-Uf5Bces#U8z!~g@t06q;t?5R~7KjWvx{wr7hvGa}j{XP(DBIO{z zdW1d@dxDhz2L37N7=9pTZ^Y8;PukId*c^-ZsR>J;1chQz&3#7jc zSDtkrh|zvxXR&EBF|Xwwh|x}B{(s6q>@{$O=UfMWVvoo0b?ooB_y3aq_gwk^uz!aA z57_^RZA}=6tx^}y=M2O=pED5qxt|bLfPPyIgum!3L%)Lt!hh>~L(gjsgr4Ua2;TzU z#Fc(O4up=H2Er=WD||clJGl4XapkW$m+;rIA}G2HyBu@2T|!k z^><(6+6|)8gMmFVh)NHl(u1h?Js7h}55}z0gQ)ai%xX5M z7VD>d7u(7<7_&+b#;nqVF{|`o%nT34tkQ#UH5j9uFgA!v52`i#8msi6T8q&tJs7h} z55}z0gK9ZOtMnio4x-Y7sPrHzJ%~yVqSAw*ReBJW_FnyCf%obc!r>4c4#D9N91g+Z z5F8G{;Sd}S!Ql`b4#D9N9D2`xJq-?r;BW{Ihv0As4u{}y2o8tfa0m{E;BW{Ihv0As z4u^Qt4Z-0M91g+Z5F8G{;Sd}S!Ql`b4#D9N91g+Z5F8G{;Sd}S!Ql`b4#D9N91g+Z z5F8G{;Sd}S!Ql`b4#A<%H5dzgu7MB^hv9G-4u|1z7!HTwa2O7U;cyrZhv9G-4u|1z z7!G|tf}RP7!*DnZhr@6<42Q#TI1Gowa5xNy!*DnZhr@6<42Q#TI1Gowa5xNy!*DnZ zhr@6<42Q#TI1Gowa5xNy!*DnZhr@6<42Q#TI1Gowa5xNy!*DnZhr@6<42Q#TID-C+ zpg$w%&j|W6BF2`35%?KFg+|1KQqZCiv}gn^8bOOj(4rBvXap@9L5oIIJKtqR8d2?x z)};~YQlHT8h!NG)DeiG2sM84QG=e&fs9sLDMvb6RBWTnJiZp^Eji6B@VYOo5!^A&_ ziF^*Lc1j`gIZWhpn8@dFV68Z;TKiY8wL7d@pBDZ#_JX{BICxn(9#%YK`&H}<;APMX zc3AO-@uwC0g@23vcRb-|-1U!6CyF>s6meKlgsvB#$}#4c;c)D6Uny3d^5^{8hMmT4 z$If7TOnq4KfS>SHY>!Y5D-v)@FL@mXpCkQw(*HO1IJUiT82%6QUO22bwQ4OdIK71J zxAWoH%aqCJIveju-=}w{q{Vp zx2J8tF%RpFDF)<0)g}CQr2jhTx8&jQo%+=$k~9hZ{vB0M?-M$z8C4&5iuHVyK0c~G z?(~bK*hi!EZl6D*E7h-!pLII@dX#=WO1~aezjpdF;0X8~KaGAps($Tz{eBr$zfKGP z3Y_E`%0OQprL~XJmq%fHl-52#ZlIt#&c{#|@A9IXHa`eg^ znvY+`tJs!yguYewp25F7S9H7kE693p^glNePV} zkK_W6M{;UczS857T;TCYF1W_^9*^V#k4JLS2S3L#YEJrK+vAa3;PFT<@OUH_{1fQ$ zNG|vnY>!8Bj7M^eM{ae|M{>M7axsrba=bxuF^@-bj7M_neZI@% zk(}P7Mvq5wdXw7rcqFGDXS5FF=yy4(oS)!#O-?Fj+vAa3jJCvhBqzl)S00b#7?0%C zLv7P$(7+rTm_q||j7M@Yk4JJbk4JJbk4JKhM{9Ydpzp`6Fy_86=lgU@5c3CGaSW5fx^h!c)ci(_xp0tSu|Cp?FyJ%^?}ho(J; zragzIJ%^?}ho(Izoxc%0ho(J;rj5hKIBbl=#yD(@!^SvljKjt_Y>dOkIBbl=#yD(@ z!^SvljKjt_Y>dOkIBbl=#yD(@!^SvljKjt_Y>dOkIBbl=#yD(@!^SvljKjt_Y>dOk zIBbl=#tGOs0UIauhP@G-kUlR9hp|1fJ0Yz$j)BKOM;a%j+fMg7y%WUSCjv)(Ct%}* z-pIaY7W6ut6Vhbk&x|mC0_IOhwRD$M%jy3ebj*1IkDS0GCt_Jr{ujS~2R!b4@ze=C zbt2}utP_f{{TxaHhbLllq%VLk^Q$Az6YAYYM|UUGyNy2vuW`*kfgTB-Aoe~%)O`Ym zPlSH|o(TQ6JwXdOK?^yd-shAm->dhvF;2=mWl!)`Zi26J6XH1?Oo-b);TX2Loe--| zcljsuzVokEqzUmRc_NTJ5lEg0B(J_{P8@;ci9qs1AbGWUr#k}46M^K_ zXXQ;IkUSAco(LpQ1d=BL$rFL(i9qu7mpl7@FpfA#o%Qa$vv(Bt<>_02J%$M2Ks zeYQP*pHwe1UIsn#npE#Fdi*}A-eKG0_eu2*-{tZ9ByE0@Hb2SueNwGm*U-Wz)xve9 zTC!9A+)q&JwVlTH_a{$g{eO@%yBF>bo3OPBMONHw9jfzgApVKJkG>SKk z)=d*HP1Dk*iJGQqZ`0`5GzvCN_*c&e74&X3y6+eC_B49@RbbY)z^re9S>J-#)4ggZ%0=zO=x@XYW_=6H`WBe= zEigM&h&gg7=sui5EHLX^ApR^c>st`pzTW+`z^rdUZAmF&?6lC|hzsJ)w!c0Um^JbVgJXeD7!<-` z5e|!RScJnO92ViQ2!};DEW%+C4vTPDgu@~n`usjU6Ap`TScJnO92ViQ2!};DEW%+C z4vTPDgu@~n7WJN8*3-;k5e|#$gK633un31mI4r_p5e|!RScJnO92ViQ2!};DEW%+C z4vTPDgu@~n7U8f6hebFn!eJ2(i*PuLrp=;hv*PeZFpH+mib>mUjk9RlESffprp-#z z{Hrx>7EPOl=UFsumR>w7wtbC9OtX5I89ic}McHOiwpo;I7G;}7*=89r&C=^<(YIOj zZ5Dl-jd{d0E4Gc+w^=c4+hf~VMhdgy*0x6+v-JI0v~Cuyn?>tp>HD)N-YkkYi{j0q zc(YPGKfxoWS(u-N^I6!Q70-Gyx;KmN&7ym==-w>4H;eAgGGdxV_h!+(5^R@Xy9C=M z*e=0#3ARhHU4rcrY?olW1luLpF2QyQwo9;Gg6$G)mteaD+a=g8!FCC@OR!yn?GkL4 zV7mm{CD<;(b_upiuw8=f5^R@Xy9C=M*e=0#3ARhHU4rcrY?olW1luLpF2QyQwo9;G zg6$G)mteaD+a=g8!FCC@OR!yn?GkL4V7mm{CD<;(_MG(LMldIR5UO7ry`pSB_#4d& zy(C}s2`lBzm*f%I;_bB1Z^M_wp6yq$J(K*BA}-@kz`q55=4)6-^b+fcUSb{5OJZA3 z6Whkm_)4+uEB_oj4Q9X&(CczvQlw-Y2VdrT|HtPg#WqIIGrXjDMyMFZ_!h9rS1Mw0 z%CCd(RLTN%U!d*_)O~@vzfAheq`yr1%cL(7XD$+9E)rob5@9Z)kc&i^i^P_TM30L^ ziHpRCi$sQt#Dt5)fr~_ai^O}2DBB{Mwiqjl?ZsFL^xI*PC~lGXZIQ@rk(g}}9a|(? zTO>|fBr01ZDtiSFo}tWVDDxT0e1Lz&M|<};M}3}rq;na@z>GnDxZWj;fhUxoQsVg6Od+OO(O zbR&3GZzAIrvGJ-(Zu=_u&qjRoDn5FZG2p9u%Q*c7(DTNx>OJC=Q{W8fnc-JeTBmz< z_f@?+Z2Mm-uj+ka{JD|Q(5sAwUe%kzDV5-_3C~mJ^OX5KWj;@t&r{~}l=(bmK2Mp? z>m91QDD!#Be4a9&r_ARm^ZA&|e4a9&r_ATYv+r`5&r{~}l=(bmK2Mp?Q|9xO`8;Jl zPnpkC=JS;KyxwRxf{XO)i}dS@^y`cC>x=a3i}dS@^y`aiGrC@F#^`>1QLV-3etnUC zeUW~Bk$!!VetnUCeUW~Bk$!!Vetl8xO82T=8Qrfhs$Ch~uP@TCFG>&nWcTZf^y`cC z>x=a3i}dS@^y`b#G+jx*zDU2mC`~&ZT;dIKi8sh4)oVGpq#7AL>bZo@Uqa_EsccU1 z`0F#H+}zXorw!Q1PkzfSt=q`yx3Ri&qct4bH* zk*o4ZpX^KW_*Fb|RW%)xeU-7ZV0kLs4=GmvK%syRZPU$M1x++iUY4Viu z1ouvW?ul3BHK(8Q^TmVFDt#3muHwO~V#DcHlB=4ZF|P6i|112e{Am2SufdO3@#9tb zQBRg1jlU*bp{6U;bcLF(P}3D^x7RdO;@Pt3N>A!rYqER zg_^EV(-msEqIla+a7|aJ=?XPnp{6U;bcLF(P}3D^x^mE7X)zG6PP@46aerYpUrD*;e~&)byHaYTIgmjb6ringQo&3jNLT8olfq zz3dvbxJEC#rdsGOdf7EfevMvsjgnuZmtCWmU89#>qnBNy%-1OMHG0`Kdf7F4*>&3I zb=v23%6y$NU#HC1Df4y8e4R31r_9%B$=7Mg*D3RL%6y$NU#HC1Df4y8e4R31r_9$W z^L5I6oibmi%-1RNb;^95GGC|6*D3RL%6y$N|AaFCgfjnxlKg~{{FL;clKxZDfBHtc zp0FJJR8LqAZt$kK!JFa+Z;BhdDQ@tlxWSu3??dr?gEz&Ez;B8hyeV$*ruhFPy?=CE zXMOHFv&Yuf+8&w8ag16AKZ)g}7Ml5{(pF40$(q+7?HFDlVjmgp->^pz$0$`XBLiN3N# zUs%m5Ridvf(N~t}D@(dAmD5+2=qpR~l_mPh zRq~lt@|jignN{+cRq~lt@|jignN{+cRq~lt@|jignX>kx_r=O-&u*2Obu2UMSmwT1nfqd8?u(VVFILu>ct2j5Q$|r`?u(VvzAskhzF0Z! zIj*wK)?0dIPC4y+9Az=@e_bN>%AB%l!6jaqQN-jDB#l~t#Xy)vgP_KaScQ|7){S(^9Wd|#~0 zeX%n4#md|lD|270EVlJ8v2DE5d*i-XnVHx!ZKTY7u`+iJ%Bm4>IpBSAU#!f1u`>6? z%FNl8r7rKsnMs+JRSxzM`$>T^bGc=y&haqieo~+uj1WHzdS!T7YIM0*=9IZFR_4A~ znHE~+zF0Z%%A7Ly#mZ{4x?b*!l>=%&@XDMrv&3bo+I#al^Rl$<*iQ?pmdkAEl{sZ*u*+(F zjy*G6mfQIJy)vgPw=sHUPMP~+W$ufWah@{HQ|4YtS#4H(;9f~tE!VL#x-yPb=DtZ; zEm7CSeX%n0;bpaMZ|RjeWwmj~zK2p)Yu%r&(C1d@b1U?@75dx?eQt$5x1tubn6A+0 zR@71)dvsQj!i^rCRp@go^tl!K+zNeeg+8}JpIf2Nt%1v+J#~!uICuh_06jm<_q&C@^TqeO zgH`Ay;r#BP1-sf)zlBKG_<-vk$Wg#+IN7rN)-o8UsPpW&O}Lf>IoPg#5GsecDO zW?xS^V_(;sSd4yC=z7Z8`?}tdW%TUIdb$qu^Nj212GH{=d|_PZ*%iJsF5E)gDd8_JF0-JZ@#DgIIVBKgI=p#B`>Pt zB>KL&%gKoJm2+aRUXJmc7|)5>GRAXaJSWC;Vmv3-JBt>zz4?h#)<%ry#3^ed*4z2~ zt34-9nUgqWPU4g~iBskzPMMQ9WzUII_MA9n&x!Gz7|)4Q_MA9n&x!Gzn72a3cut(M z=fu1fD%RVO9NTkZ-U=0`>^U)>6XQ8?%AOOa>^X7Do)f3+IkDc$XSC=E$b7DLvPT6x}JSR@sb7DLvPT6zflszX-*>hq%Cr;UO z;*>onPT6zflszZLbK;aeCr;UOV%|<1<2kY3%ja@?PMn$r?KyGE_uOMVC&qJPJSR@s zb7DLv#&cpkC&qJPJSWC;Vmv42?Zh#j6Q}JtaoTIwV>~BLHxk=(;m zGN}?jAMplG@&=ys2A=Z;IrU4uHrnX^@sXZYfXiE3$bv9ZM4Qrv7Tua z>Mg`V&1nc<;cUN2e1TYRAy)ZCVm*JPSob1@TA44@^G8Ch9v5nsL#SB}q2|PdTCp$G zihZGGCWX59E&M5{SxUv1K|N8Z_zHLx)Lob$CFe2fZ7o8*g;=OreW6x#2sO7a)QS$_ z7UCx2t;9DG>n+6kRc|2{>Mg`Vy@gn)w-5{U7GhyH*aP;09|G0;>(~DTDhE)kw-5`_ zo4m-!)mUDL-sDBvv-GTOq-5hKydQay<4<~fd6Bl47dh5jh=Y{8NWc0m#6rD=Solt2 zy@gouyNLA`V#Rt3vG8U}^cG^p?;-9W)?0{GqPGwW-$$&s5G#H^aX0Y?h==ck&{~f6A7h zAnqgnB=POUe@6T%Vp^rV$kzymehabUUva26eJTD7_+LT2g;*te3$ajdAr8{^BB91y zLgha~X;D{SI;s%bmfg^6fLprvf*C~fI+Ry8hL;6?`f%`zsNULNB)Qq&^ z$2jg6*~2(TKL#EL&3T<%+V~`>_jo8i1%3(qGWZnu&!C=%(l*nep1)T774TWmE?uYm z&}f&g!=>xw(mtOVj`AY$OT?OaR{6`s-((N3g5Lr)=d54<75pBkyA>*#1uubf;7`DR z=ZN#*0(cd)>(=4Ab+~RFu3IO+)!yW^#wPG4(C%7?yVl8F9qYZCLVXQcs4s^K?X-0` zZ5>WqryS2EcG^0>?_GE+Tkdcz=neEneFs^H66CaEULNbCqk*)(ajEz(z&pVI2L2se z-Y1>c=?!?sK}z(NLd7{s^whB8ec%Dm{disa5L^CFwscFZOaCMIzraVqW1NHTH0f78 z`zEB8)9x$lG{5a~>O%9|j{l8qU|#dv-u~y{FTh`NEY0Mrd>sa2Ffpn>6c6+ub?QO1 zjd~EBmHH0thrXjOxRZDnzwQPfs4eQ(J(N3RsSBK|)M+N%`1jx$5S8klh0AsSOQ^RP z34i2k@f`}G-K@^{DTMC9>ojNX?cHnF1$MbQ&7ZqO_o0M0jJ~HJ)G8ODp0yFWH>}fr z1mhM;-c0=Kpq|lF`P(Sh*Qgc0!&j=_(D6Ho^)+h6?;_UMs1>(?H&fD1{2t;C;`b7F z62FhQi}?M--NYXt?jimlaWC;L#J6%*J3zfvTSwFzzlFaA{xks%*Nz(EsG)LW$9B|EBW@qXjv8vjZM36?8gU!#s3DFTYQ*g=Pl0ySP zjv8vjZFE};anw+GuVXuEs1di(jvC^qA&wg2s3DFT;;3QDjv6ZO^>OW}A&weqtnEG6 zQA3Tdjc&yujv6Yzb!1dn!?YbW#8Jbv9W~T@ zM2&XTFl|Q-({|JlM-9_<)G%#F4byhi(D&|zcGM6@4RO>EM-6e*5JwGh)KGT}y`>#B z#8Jbv9W~TFaUaW$8sey-W>wV+G>;|3Q9~Rx#8E>WHN;Uv95uvI!@!Oj26ogiu%m`J zY8cp2LmV~4Q9~Rx)V)QQqf#6-#8E>WHN;Uv95uvILmV~4Q9~Rx#8E>WHN;Uv95uvI zLmV~4Q9~Rx#8E>WHN;Uv-J{ew=pLofjvC^qp~e@w3LG`WQ9~Rx)Le(l?Wm#VIvm?k zLya$7Vn+=%zHn?u4K>%{*p3=%eBs!R8ftvu*p3=%uEVh%HPl>(V>@c7xemv6)KGIB zMmuVVqlP$YsJRZ8*il1`ER1&4P%|4wdEM-4SP@RoMe5JwGh)DTAv zanuk;4RO>EM-6e*5JwF&cGS?{ehunV9%t33JgTZsd8|~g*#@J&1R>NcvG6x_tooF% zr9S1}pW%O9{?nQp7rr0VJvhalOQ}zLE~Q>yL(o;ET}So)mW0qV zD)s5ls0Qox&S9h8Q7_!Zuei{Kml%GK$a7j5I!7eZ&<^>R$UP!*kBHnOBKL^MJtA_CNONvJ2j?CUxkp6q5s`aD zoO@(b&ONfa3*c>>dt^29Z*=aFCHKf`_TI5`k8H|)be7yBOYV^+_sFK5 zdt^1Es4r5Gdt}Kyvg96Fa*u4Mo@Aka6yj%{ceSW}JIuGtND-n&CG(_sC|Pdt}Kyvg96F&EdPmxkr}VBTMd)%{ceS zW}JIuGtND-8Rs6^jB}4{#<@o}wnPh$GM0%JN?$Q{oMH&$LI~u{qQ~GLvP~Qs( zJ|6h~(Z@BPKNH-h^8G^3MBS!-$M_fE9pGoQx7*bFxZKCRO&Zg`(toXe-lqO&RCu4V z*4zAj4dMOZ1E6!x+vuBaQ{Uum^gR^e5UB5=DAxB-gs%77)HfOb0sKes|K->JMf^Ep zeGf(390nhye3W?1sO!>s>bi_tHyHHkseyZiTFoo;-O@gJh*96O6FSfDlam-dis_Sw zObT~`9>4T)PqR-R;%$6Sv(MkN6Z)QJpFG6qdzyWCMIUzz`{Wfa@m<0`?hp2Hzpsxw zeSO^H>yuaLS9yieckcS+6-M8!>%%Mh@QOb9fX)gZ=)(v4xXad;)~aTeYgMx_G14CU zg3#9zc&4$B`)hsNpX!r7wP)$m=(|yU(x=h)q58N3)hB&A_Fbnw>C@;tO?}d*(W>i1 zb$zI=57m9rPiF+56wg8(-KgiygWIL9Nulp6-7a;_3ca7(mDL!vN=ImI-=6*~@x7|Y z+fncB>3+%wD7TVtPY)Ya%i5c2*=TM5W$M4^{?uQlJ^_9*^%=#tgMS8o3VgwsZu2(j zcJMbSse*49gIio4dsD?}`6Wc!!So8Q~{DAMp;3ct^@dyd&i!-jVVV z@6ZvA?Vyi%ht@V4eZ)I-MB|6RPlJDMrhJcqa_s3Bz~7@SQMx7YyG8!*|K& z7lXT$#mx%!77L+P3<^(yli+Fa8GfB2_C1%o($5jU0DcX8k!@ZEwW3ek`~X}rQVVxc z3wH&(yuC6sm){58Psv{59QYU|PY~-Z7TR*k$Mt&^gnEmG@EqGbN6eY{y$ULKYr0Fh zoKf#65PqLnYX}w3fj|2(>a$ z_*P2ZrkHPj39aY9Qa(H@`~kRPgcH8rrFb_b-!W=$#N0Lf7xz>LraY zunor&livOfqx!p1;hVs1-jaKi_voDW2lwclg?=VT=y{2I(m&Cj@A0!dLOrD`be?dJ zpE3*X(K%~-owLz>$31=)M(EkmdxD3-$3f3C+(XZPPw*A~`z&~#U){6cv)ld1EsnR?K(3ir^b-$OtCSwBA&d{)_! z(Q5px@*?BBQCW>~5Znh2fy3YkcnEw3JPUpm{5tp&_%dkad{!BVaTzRviBY2r<0jC3 z#AkJ$#+!t@R3rBa-LLJEibjPeK+hxX;+%I$OD=yAw3c>p6}wbNid8$>Qnh2eo09vz zrSh~%q5JDyf%~{!!5BCJdNs~2@_yKq(GzD*yZ zKPA2n+IedN!&pDM>X%=Q2L0%&A6@mMtA2FVueV6) zxNPJ`o=&B!G^~>vg zEbFQtUG>ZN?p17E^`onP+FC!l>PJ@tFf#x%1L$f1T@9eC0sL?PT@9eC0dzHht_IN6 z0J<8$8wX%%0G0;O)d0F0Kvx6kY5-jgpsN9NHGr-LG}kd34B(#w=xP964WO$5bTxpN z4xp<6bTuH}M)fc2Y5-jg;GzTQY5-jgX!gT5`;}d2du12i<`U&|;7^QlW25`u`;{SROZxQtl^ZyA&;EcEvM6*8`~bb=15$tE~hb7!D9EATt_#aezR|(nUpjy4-C$;B6vd2NO>i9J1>~T;G zyTsY!Alc)f-^!)~YX<y zLiV7LJt$-k3fY4~_MnhGYQ@?Th3r8gdr-(86tV|}_{);}1AkdksO)G_cuY>RSE{&I zI7vJOeuZE4Jfq6J!gg=^o5XsXt75mTz0!bV_sDy3&b_$hUR||I-2d+N+gye2h4*R> z*?U{zUwWHs;O|=MOr#v6d*r>!%CwDCr1O!Aw0~u2F4@Dc`-t5y@70Wx%iTNg)x48q zd+FX_g!mBXo_ep}<|@?NT!mKqUfgxBW}+Os@7_!AvzLBnulgOA=xwgTmx*5?_B`QU zsm^ER3}-L1(0ipipY2aTyY61)f!?#dcdxQR$M&nenw4^FAKpu!wU_zly?F0l=AZZC zzq>=9ID8niX5uQp^98!RpjVZbEqPR zDsreIhbnTYBBwb?Z)sKJP(=<^}a;PGQDsreIhbnTYB8Mt+s3M0da;PGQDsreIhbnTYB8Mt+ zs3M0da;V}VRPhk1cnDQIgeo3F6%V0`hfu{ssNx}1@erzb2vzK35Bu1|KK8JWJ?vu- z``E)i_OOpV>|+o6*uy^d;IGF{2L5`ikUi{Y5Bu4J?)|!)Jt%usjqGO+``N>O_AtaA zhS|%5A$qhSdbA;Ww4uN~+7Lb35Ix!u zJ=zdG+7Lb35Ix!uJ=%~|q_Y(R-v9TB-J=cBqYcrc4bh_w(W4E~qYcrc4bh_w(W4D1 zAJ)I<(T3>JhUn3T=+TDg(T2pZjzW(%M2|Kkw)Gw#db9)dXb0%g4$z|=phr7Ek9L3_ z?EpR60eZ9p^k@g@(GJj~9iT@$K#z8S9_;`<+5vjB1N3MI=+O?Sz38~~Xb0%g4$z|= zphr7Ek9L3_?EpR60eZ9p^k@g@(S}jTFbWw)A;TzS7=;X@kYN-uj6#M{$S?{SMj^u} zWEh1EqmW?~GK@loQOGa~8Ac()C}bFg45N@?6f%rLhEd2c3K>Qr!zg4Jg$$#RVH7fq zLWWVuFbWw)A;TzS7=;X@kYN-uj6#M{$S?{SCg&MOA;TzS7=;X@kYN-uj6#M{$S?{S zMj^u}WEh1EqmW?~GK@loQOGa~8Ac()DC8gtIfz0IqL70qBmBPe79g^Zw(5fn0lLPk)?2nrcNAtNYc1ci*C zkP#FzfBmBPe79g^Zw(5fn0lLPk)?2nrcNAtNYc1ci*C zkP#FzfBmBPe79g^Zw(hiQ)w(;gqj^B)!`v%$l7{=>AIhiNqr=iOHwi!IH=+lh^Bd8F&++T$`1SL& zkq);Vi?owM<;yr00cYKNKq zILutfVSM1Q&RqY}IU7A!d|2}vMvsFI>zrNgx#GjBJELdM4lD06dQ5a!HRy7Wnhysa zaU7OQcn_X8J1mzldan2|E^!!_IIQ~8o>gB)&zL>xZvY7!jq->6LZ92C@&v~oDL*PV zaO~0Oqtdp2{Q-4t zQT%xne;&o3$K)8J!IE@?+_1;OlJpAH+ZBzyBZSxk$+`DDfKaF}bDpQzX8@ zHYMUUuwo1X?=A3L`dF|5toOgzKw?-h(}MOk*p@cG@wGtsL8L$27KbY}Xybb;mTea*6NkkI6Yy3wq0$<1c`o z6B`S@2zr)pOm8_eKFO9R!7o$ddB3sXG-xLu)9B25wx5q_bmmy^IuqI}#)9XFzshxe z9ek1hdMrOC-|*f%mLHRQIJSF?>CI-2J$fCZC64LMW-dVw(zaPb18Sk>%`5ZA)IyCv zQV1B^B&x%jA^XrJ-cTa(^${3`?uNT+I>2<3|{Y zA7KoBgmL!~M%hOgUmp?Y-rjR2M;I3$VMKg{vG5VbzegDP9?{ilOGdj#80{XBRTOqKJzGj>rwTsj@`E&C6_oV4^%AoQ@PyF=pObcJ?v3>*rV!U zU4Du!J*GQK4|`NStp8g8pQGG8>``T9-osak-OnB+>o`hpdsK?@Htutel4BetvpTBU z)Sk(&j;c-_Zv)*6e}QZK0@wHj&h`tO?HAC%7tjD-t`8m~C*k|`ik&<8`}H$IU$wtt zKPmK8^DTSf|499B!UyExeAiy+_Re?hg>K_~*IwwH>M?lW>-LJ>5+8$&$J9GGc2Dgu z-5X!>ap|ugQ@eBQUi&dI;9uQ3`0BmTEy7>DS2cqMsm*a}a~yugsm*a} z^BA>xjM_X#Z61@uEC$EOOpZ~T$EeL?)aEg2^O*cZ+fbXwPaPvG+t@IL|n6YxI){}b>(!8uRB{{;L`!2bmNPr&~K{7=CD z1pH6H{{;L`!2bkiJ^}v|oc{#;Pr&~K{7-Nd6YxI){}b>(0sj+R#RU9M!2bmNPr&~K z{7=9?-?9(*ioMW1?33{SB-g@M>{Vj^`9i(W{ppkN|0MkL-FcOm|0m)9N&3?#xeC51 zukvs3t6ld=&YUmBE51&N??*fd|4(w}d=Wn2Tkt}!C3q74Ps0C6_&*8%C*l7j{Ga5U zPs0C6_&*8%C*l7j{GWvXlkk5M{!haHN%%hr|0g-~lkk5M{!haHN%%hr|0lVMlkk5M z{!haHN%%j>Rh)$Xlkk5M{!haHN%%hr|EJLZDfE8|{!hXGDX!%d`acE#r_lc?_&){z zr{Mn-`acE#r{Mn-{PV5(fUnF8&HpL%&-djOJI^@<|EJLZDfs6r^T8?fe+vDdg8x(S z|0Q~XFEP*XC9dd8T+x>q>wTHA-j^A{eVGxQzwka9_zUl|LXW4OVm!rn-W7X1^%UbN zf9-w0Vvnc%wRhuJ{4Z*mue~dF{_qszDSz|bv2$jB^WA&)c#3bn3q78CD(&%^;ydp`kEi^dccaHs{=&P_hYAn?QR^T#N#Qx=PvYkito7#J)Yuw z?m~~J_@2Aa8JEB0?h=ouo?<-Z@3}knc#7}23q79l_uO6Ly!R=_Q%?mRPx-6vE|~;9 zp5m+SLXW5Ts=LtRDZc71^myti##4O5U9rbg{)W5%>+zJo;qKVuDSyM=vBy*XhPz{r zr~D0f|I6bkf5Y8~5*SZC#dyl!a5sA%Px%|}{+Gv7e8XKxJu;r+>+LG>c#5yL3q79V z>+M31r}%oi(Bmn8t6fKAJjJ)#71w*ujHmpqc5Tmi%HL{t>|D;@YBzd3iwg`Niw2I##xi(MY@OP|4Kzh=S7p!jL~_~q-xgaan__5 zcI;eel3Zv~yeTFNnj{OFWSljrD|NZE*-6G(Ps?pS6+A7s5vGsoe4b{U^>o@R6`$5P z>vx4;Q$0Sdah6MdEM}g@QJ+puOy zW2yFaEM?%1e~s9y5T91QIvJeSwcjiB`pnb1u2G>^IGomXDb{tVT-Rm%E0+hJ?L5tF z=V@j;PwTq8rROb%paafd#3A*uH7Y`KRm(#HiUZefwjIPwNM_Xrf zrA9l(8C|1exB4^8AD&_U@C@^ZXLRlQmHCh}wBIx0!6jbxbVfWZ24~4n&eC(8rRO?J zesY#NI*V7I#evU~lbj_dIZIA*mYn1)PJ5P|@|5~zm+1Qr z!k@FBMM{1_{7cSf1uRlt0$17F8ga!aKh*x^hsF({R}D?c4~=(vZ|ax5rTgV6+TfIW zXP0;#(UjcMTMkh2H{joa4}k8Sr{tyH(k*w2mOF)7rsS?JAENvK@i6g0;t}G9LHE~F z@?LNMdG_q55vSBs8z1La_taDBsa;~{oWk*@)JHp}_BH3}*mIs!@^J6XGc8kca>t(Y zoWdKY3?!=3S0v)NA`+=tRA?V}0L2==M9sEa;T(!l=g8cl%$z1U+J%QorLZJr_Eq-p8?L zex}q1Ird!WlpMh4?;yMR{B(j|=4)7vvcc z9_7RZa4QN_;p@^T)RJKxKvo&V>>mCK#~=gI%` z;>{(_|MTSkd2#5H*Fb0fdHIZw?#w?==AW0tICkcrC+E-0TV@sioPRm<&y)G*#lQFV zOZMQ*KTqbLC-cvf`RB>}^JM;c)yV!JkDugKBif!kKaZc}$@BB%`FZmEJb8YeJU>sK zpI4r*GohEss~)`v&!gs5n~v=sdDW?7yGLF%>)7s*r}xRLmR;gJKTn>YC(qB5=jX}o z^W^q^)ER zo~OO%)e8JC&w%CC792Z!&y&4>MJ-}7_=;MDP`BHdUZa6=+ih+Ejry zRiI5hOPhL@HuWrR>RH;e|10ba{@E+Bxd<9Q>by`Ezi74z|z1hEMvwQ;OP@xMv(D?> zj2`=+CtEmAws4+o;k?dJ<>U(-1-5^I?O$N~7uf!*Z2wiZ|0>&mmF;I#J`>EST*%mVCVfII&1i06ztHzm zXBgq?d%~3aNt_wD(pOt4S#^o_sXb_)M&HlXDt_V|=oM2l)VQ)#@0q$*|E3;6?hAUw z)C{#hquFWi!FkQ-88O<>GS93d~QMO_jn9*3_gco(~qrr>1b|F{yqQ+mdihW%#YLqS1b?H}Km(hxSku!fW@Hp{BjRK5T?29@d z<2o1{b@WN0$DS{8#FxbCZ156u1urpI@RHbYiJ#AUNjwO3=EgS(zd@~igIfCrwe}5a z?Pd1!GW&U%{k+V6US>Zpv!9pQ&&%xR754KA`+0@^yuyAi(9$o^#xKyuFQ|>r1{b)? za6z@KnAUxPy9^g-*B5Bl7iiZPXxA5L*B5Bl7iiHJXwetA%Wy&U=>2>R^nB3;Mn)GH z6J6jg!v)o;%ROefKwG{*TfU$=bxC4mqH(Y;395(5gsnmHZQ`)MOxxTuKgnOT^Chf+9$JK z7gcMHw+p|;b$yGYe2e{mi#>dc|9%@c`!;U&ZEF16)cAMM^LNnmchK{9(DQfM{=01d zUAF%&+kcPkzsL69WBc#1{SVpxhiv~tw*Mj9&$9h2+v}a9;$)WXFRA?A;F8LPa?4Sn z=Myfe)?DJYb4j)463+l!!c{JDjhAqhOWK>Z)ZUDDdwbQLwp86s3UlBil#hWEpyz2X z;Xjwu(*0lem6ue5`-Ogg;3ds2dK=C`b?4ZMy`;KxY~5a>-Cd&HT~d9y-0kiX&-Py8 z+1^X4JC|Fxmw2}Kl4?*#gr7^QLC5yeOY%}}iL?C(#(o52KZ3Cz!Pp#(&B53ljLpH= z9E{Du*c^<_!Pp#(&B53ljLpH=9E{Du*c^<_!Pp#(&G9t!98W{f1!ioHne90kn}e}A z7@LE!IT)LRu{ju$ z1T-u3^QZIaCyCv2&1*DdJPrD3o%yugU|w}GBXs{e&pO+A{C{3G;%#0AJvy6DyXT!J zlbk1$oF|i<*O)^8C7+yUrTskp#XLRKJU!GrYjNj;C%gyMj?pvZ^YmHs^jY(PS5M8W zUi|9|#O^ibgA3rdL5~6F={4q+$@^FP{JgSvqgU|Gv(kQ^mG<+jw4Z0C{X8q}=T%?Y zhE=}vtn!`5qvmm^d1c-H)nm+g)tB+Dlz6;(ncBHb?ObN=_p%hLa%B!i&)HsvC}aVJETE7D6taLq7Es87#>=z80t#6`Aq#0MWC4XNppXR= zvVcMsP{;xbSwJBRj5QWe$N~ykKp_h#WC4XNppXR=vVcMsP{;xbSwJBRC}aVJETE7D z6taLq7Es6n3RyrQ3*;3GC}csSKV1bQngtZHfI=2f$N~ykKp_h#WC4XNppXR=vVcMs zP{;xbSwJBRC}aVJETE7D6taLq7Es6nqo*q<y^6bDrM|A}TD(u^fmg``uaXB|rADseu~*3huaXB| z#bdAHu2;zeuaXB|BM-br9(avB@LKvc?eiMfa*aIj8hPL~^1y54f!D|buaO5{(D?Jn$N4evLfv8hPL~jq+4Z z9{4&f^mSV3>$IBJX*I9YI$o!ByiO~4omTKVYJ43v{s(Ipe}?LQhU$KXmVSnoeg;23 zgP$divcyrA@PQ?KUg2bS=GC468BA6SBcB^X%32bS=GCDgTq zu9onDC468BA6P-fNReBe4ha2+4Gjt^YN2d?7-*YSbt_`r31;5t5V9Ur)k4_wCwuHysO@quL&vW!BO zQOGh1SwjmN1CBl8x0d!ua4qdjZ%tQi{5k0N;jEGGt?}lQHEG8G@|#cA zq#T`zlw-Wp+bh@A5v3xXk5r^BmGQd7vxRHHK4Q-qt||LBYr&9eA(iRWp{ z+OzR(!V0RWpo$8rsGy1ps;Hofiu_?TsA!zBD6}dnsG@=@Dmw0@O1$R^s;Hof3aY4} ziVCWzpo$9b!>OQ(3aY4}iVCWzpo$8rsGy1ps;Hof3aY4}iVCWzpo$73hzhExpo$8r zsGy1ps;Hof3aY4}iVCWzpo$8rsGy1ps;Hof3aY4}iVCWzpo$8rsGy1ps;Hof3aY4} ziVCWzpo$8rsGy1ps;Hof3aY4}iVCWzpo$8rsGy1ps;Hof3aY4}iVCWzpo$8rsGy2< zRI!dK)=|Yes#r%A>!@NKRji|mbyTsAD%Md&6;)JGMHN+4QAHJ1R8d70Ra8+$6;)JG zMHN+4QAHJ1R8d70Ra8+$6;)JGMHN+4QAHJ1R8d70Ra8+$6;)JGMHN+4QAHJ1R8d70 zRa8+$6;)JGMHN+4QAHJ1R8d70Ra8+$6;)JGMHN+4QAHJ1R8d70Ra8+$6;)JGMHN+4 zQAHJ1R8d70Ra8+$6;)JGMHN+4QAHJ1R8d70Ra8+$6;)JGMHN+4QAHJ1R8d70Ra8+$ z6;)JGMHN+4QAHJ1R8d8YDq>U-qly?+#Hb=h6)~!aQALa@VpI{M3V-)`e^6spr@#KJ zm>G;3+Nhz88rrC#jT$o>HECm3Tl$IhniMiAyeL1Zv8uDCGx2`Bsc+j~`K zE$vl#wY2BVYdTwR=~bPzv{&fWq$vN(t2%312V%4v*VGsLC|=cBlhRz`8NyoHD|Tv9 zozbg0Ypm+5sgL%SUe#GkdsSyG{W{xwRc9^jRh>1d)cf&DznWC)*sD5gV$bMRoi(it zF?v;JP3uD(dsSzRRh>0fb=Fwb=`UsLU+B3eJ!@~Q>Z~!_Q)5+Uja8jB6kbz}c>4kN z_BWtcb=Gv>-#F;AmGZrx2ZZ}D` z)mhUT5~Ejj*2q|DJbzIOoH^83)mc*xqwCdr5|=oOs0CitSyK!0-n^=_rWWMbt2%3} z>Z~c}@xQ#Pv!?rBM$gCA0u-WF<~?{-XD#qOof>miHMKSG!K*rJYHN-?TU%pQXN`7O zlWxtGS9R933dQ&X5Y5mMYqZ1~EwQGS=>2%6x5lc@8ml^Mtm>?>szdlN_CUL?sa-qX z%$8o&S)+~D)Dm@Ftm>>W=T=io_m*DOSyOv=?A)NH*1A9AZ?BIEbs3*UKKj*(%|EX9{3<>q*m++UwT2-jHNUSHn z6qktgNVjmbEsPOmIIXN$uGrv z@=K^Ezl3rjp`QE_%6Wu(@=GY^5$ee=p;m+n_2idO&LfoP2=(NbP%A=(dXt7wPkssY z1V8d1esBPx{t2=(NbQ2ry-lV3uuDi_LagnE;P zP;MiX+X%I4RH#vaP@@2$Mgc;N0)%oKA=;4JcyC$>EYy=SLumKdh)ZnrIt0ab zgN?YsMtoqS@&}h_RkrYoW7@(-ueDSBfLv%JYTt;?H=^*3XnP~7-iWFb+=J{ z!EDCgtzHz`+v`*pMtggmuE=PIuTzZ(aql{OyAI#>H>O=~->wt$M*DUhzFnu5;#l`d zg}Os3w1@l4(MEf?zZ`AU{jZF_9Bs6d*KxLWoNXO`UWcED)I~@wgw#T)TA0m*o_!K( zJ|Pprf9TmH#rByH=0lhdVLpWU5avTT58*uY43f6j7+=Ufb^eZDlAc5762k9OqOr4L zvmL^A2-~4&id2#q)v}D6K)0rlD+=L1^j)w_J^a_he?9!y!@s|V>0ix%J^a_he?9!y z!+$;e*Ta83{MW;OJ^a_he?9!y!+$;e*Ta83{MW;OJ^a_he?9#BOO&%2e}mHK{z%@E!z)Ei)gFMwYIUu64#(VjP{?f6&s zZkwpPO=>|Z(cG8zuemSdE=vB|+o(?ct5z)vwQ5oL7--Mmq!~h;iQ19NwE{<|HB`bp zSOE34XqDK{H)+n$+q*a4qIPfOTB|5ebZ}Nuuml8@SR2uC#$`Y~UIj&`d*M%`~8y1~k)vW*X2;13WaK znFiQsKr;<+(tu_fG{dZ;2i8mjEH$8+2DoZKGYv4-fMy!ttpUw6z+MBIX@J89G}C}) z8q~jgpVmwR+%}+@1~k)vW*X2;15VO_W*XqR0nIePb_1GeKr;})Gn=`h&0Nc7u41#!U+=#|Gn+Z*H__X^$*cY{Z{q6S#C83eu4OUvYq}Pp z&d{h8R+&bwv5{+RL}QI;tPzbhqOnFa)`-R$(O4rIYeZv>Xsi)_8sVoAW*T9p5oQ|U zq!CUU(O4rIYeZv>Xsi*9HKMUbcxyysjj-2<#v0+U5sfvXu|_o32&;`~tPyS-(O4r4 zH=?mdcy2^vjj-K_#v0+g5sfvXu|_o3h{hVJi$*loh{hVxSR)#1q(&OiSR?h)h{hVJ zokld)NG&v?u}12m5sfucUt8dR3;b_^!!2;Q1&wWi$t^Is1tzzku`Teq1wOaH)fQOV z0zX?|V+%ZNfq^Yt`xdTx3)j1a>)L|GwxF>sXlx5tw1sQg!c}ZRV_VSJ7S6eeb8h0C zo6t-XnrT8aO=zYG%`~BzCN$H8W}47U6Pjt_dYic3Ca$!JD{bORo4Cd%uCWQtG@+R$ zG}DA;n$S!WnrVWECN$Fo8%=1Y2~L{OOcR=ELNiUU)P!c5;HnADG{IOCnrVW!CN$Fo zdrfGj2@adkOcR=ELNiThrU`DF&`cAWX+kqiXr>8d1JB5@+K#sYZ-f zT`snbq43RO&*<^Xo5kLu&|AJ)ycxBoG4p0|rC-IB@o`GdgRg?uz%r=yirPl&6*F%Z z1IBvL*~puzyKOq+q~7u2apE?$7d@w;_G0wNWg9$f6Avyi58KGex2cV|tw8@({W_i^_Lyj!T7gmP;f3aHoAmE3pC{(%QohU0=QgR` zsFkQfk2kl8RijzmCOr$`b{pJoL%rM3?KUY^dsgkwX11f)?I?CTirtQ4x1-qYD0VxF z-Hu|nquA{zb~}pQj$*f?*zG8GJBrGTlnu=>1W?cKl@f%>szVox9Lh3GjG$C3U&TQ z_p@(T`MpBTKniabCvQ)^7u1(V6@QTU7EoUrRf)bdD%=TvSaTY0_m@V6{{(&x{5+@? z^(sFMj)M9su}VC)eS6CF`1aIA@Y~>P;7`HJpw;#Ev=#eye`!>>1>6eitHdg~8NAi! z<1dX0cY+^b8_mS3L^H8MkDA}^FO3TIM1W9tU4?()E&ZiY;qQTe0R9p9G4SKypMakL zKMDRB_-XK0`?<&a&)f@Y-d^!P=qT@i|98OuJK+Bv@ZSvo&G6q0|IP5<>@U4$n&H3M zUwTz+{+r>y8UCA7=D!*Ko8iAXW&WG}rB|W(Z-)P7f9X}R`EQ2*X83Q0|K^nWZ% z=9KwwPMQDal=*Ll|7Q4ahW}=N=~dy8UCB$zZw3UGv>e9UwRdq|K^POZ_b$i=8XAo&Y1sZf9X|d{+l!Azd2+6o8iCN zUwTz+{@)4z?}Yz%!v8zrzXkqV;J*d_Tj0M1{#)R`1^!#$zXkqV;J*d_Tj0M1{#)R` z1^!#$zXkqV;J*d_Tj0M1{#)R`1^!#$zXkqV;J*d_Tj0M1{#)R`1^!#$zXkqV;J*d_ zTj0M1{#)R`1^!#$zXkqV;J*d_Tj0M1{#)R`1^!#$zXkqV;J*d_Tj0M1{#)R`1^!#$ zzXkqV;J*d_Tj2j)@c%COe;53}3;tW-zZL#l;lCCBTj9SI{#)U{75-b{zZL#l;lCCB zTj9SI{#)U{75-b{zZL#l;lCCBTj9SI{#)U{75-b{zZL#l;lCCBTj9SI{#)U{75-b{ zzZL#l;lCCBTj9SI{#)U{75-b{zZL#l;lCCBTj9SI{#)U{75-b{zZL#l;lCCBTj9SI z{#)U{75-b{zZL#l;lCCB-wprohW~fN|GVM84gTBUzYYG|;J*$2+u*+q{@dWc4gTBU zzYYG|;J*$2+u*+q{@dWc4gTBUzYYG|;J*$2+u*+q{@dWc4gTBUzYYG|;J*$2+u*+q z{@dWc4gTBUzYYG|;J*$2+u*+q{@dWc4gTBUzYYG|;J*$2+u*+q{@dWc4gTBUzYYG| z;J*$2+u*+q{@dWc4gTBUzYYG|;Qwa$zZw2-hX0%4za9SD;lCaJ+u^?*{@dZd9sb+l zza9SD;lCaJ+u^?*{@dZd9sb+lza9SD;lCaJ+u^?*{@dZd9sb+lza9SD;lCaJ+u^?* z{@dZd9sb+lza9SD;lCaJ+u^?*{@dZd9sb+lza9SD;lCaJ+u^?*{@dZd9sb+lza9SD z;lCaJ+u^?*{@dZd9sb+lza9SD;lCaJ+u{E`@c$n8e-He>2mU+YzXSd|;J*X@JK(v_{C@!cd*HtZ{(IoR2mX8DzX$$%;J*j{d*HtZ{(IoR2mX8DzX$$%;J*j{d*HtZ z{(IoR2mX8DzX$$%;J*j{d*HtZ{(IoR2mX8DzX$$%;J*j{d*HtZ{(IoR2mX8DzX$$% z;J*j{d*HtZ{(IoR2mX8DzX$$%;J*j{d*HtZ{(IoR2mX8DzX$$%;J*j{d*HtZ{(IoR z2mU_@{~v_^55oTk;lCIDd*Qzq{(IrS7yf(UzZd>{;lCIDd*Qzq{(IrS7yf(UzZd>{ z;lCIDd*Qzq{(IrS7yf(UzZd>{;lCIDd*Qzq{(IrS7yf(UzZd>{;lCIDd*Qzq{(IrS z7yf(UzZd>{;lCIDd*Qzq{(IrS7yf(UzZd>{;lCIDd*Qzq{(IrS7yf(UzZd>{;lCID zd*Qzq{(Is77Wlsf{%?W*Tj2jgsjk%j$lS`WxAN<)DUYmgP2CQ9e0^)`Q{bmHUvz8A zb8)w(e*^rmOVa-d{4KCbx#!<*k!KtXW{?z;nu3%JfG-q8^mm2tsw8+F{S z3yR~6Ixe`5>+h@gRCl7za-aJ=_m3ZW`06`L)m!KNs@`*|PIdPzV3h%@3|M8rDg#y- zu*!f{2COn*l>w^^SY^N}16CQZ%79e{tTJGg0qZzm%?8$NV9f^BY+%g>)@)$S2G(p~ z%?8$NV9f^BY+%g>)@)$S2G(p~%?8%-z?uWBIl!6&tU17%1FSi~nggskz?uWBIl!6& ztU17%1FSi~nggskz?uWBa$r>es{&XRz^VXN1+XfBRROFDU{wIC0$3HmssL66uquF6 z0jvsORRF6JSXIEP0#+5Us(@7mtSVqt0jmmFRluqORu!&oDqvLss|r|Ez^c{c z`-NIfzF(--CQ)0hB^`T&Y$>(jTGBCTXJNl=;kDXvuyW44R-<*iWY2^>3w9&yCRq9u z4;_6N{$5zQf~b~siOMHklD0^mL%Jj_u-Gj4Kw-zjuS72SHlddEN?Q5WpqBKCEa{cB z@(oBW-hkBdrSg0+4)zGx39v`PPKKQVdkpL}*cq@hVLh<JXheM5hkXsY7(?5S=B9?_{sbm}!3oqA11r(ToMsi%95JYPnqUX#(O z*JO0+5uJKOrykL%M|A2Doq9y4p2_IcBRcg=MyH<1=+q-R^@vVAqEnCP)FV3eh)zAC zQ;+D>3mKhyA)`|-WOV925-}h)zAC zQ;+C0AUX|*P6MLTfao+JIt_?U1ESM_=rkZY4Tw$yqSJurG$1++h)x5d(}3tSAUa+| z$BXEA5gjk0<3)75h>jQ0@gh22M8}Khco7{hqT@w$yoin$(eWZWUPQ->=y(wwFQVf` zbi9a;7t!$|I$lJ_i|BX}9WSEeMRdG~ju+AKB063~$BXEA5gjk0<3)75h>jQ0@gh22 zM8}Khco7{hqT@w$yoin$(eWZWUPQ->=y(wwFQVfEZ$9wm18+X?<^yj&@a6+=KJexP zZ$9wm18+X?<^yj&@a6+=KJexPZ$9wm18+X?<^yj&@a6+=KJexPZ$9wm18+X?<^yj& z@a6+=KJexPZ$9wm18+X?<^yj&@a6+=KJexPZ$9wm18+X?<^yj&@a6+=KJexPZ$9wm z18+X?)(GAj!CNDEYXonN;H?q7HG;QB@YV?48o^s5cxwc2jo_^jyfuQiM)1}M-WtJM zBY0~BZ;jxs5xg~mw?^>R2;LgOTO)XD1aFPttr5I6g11KS)(GAj!CNDEYXonN;H?q7 zHG;QB@YV?48o^s5cxwc2jo_^jyfuQiM)1}M-WtJMBY0~BZ+`IR2XB7x<_B+n@a6|^ ze(>f8Z+`IR2XB7x<_B+n@a6|^e(>f8Z+`IR2XB7x<_B+n@a6|^e(>f8Z+`IR2XB7x z<_B+n@a6|^e(>f8Z+`IR2XB7x<_B+n@a6|^e(>f8Z+`IR2XB7x<_B+n@a6|^e(>f8 zZ+`IR2XB7x<_B*9@D>1X0q_<8ZvpTY0B-^C765Mn@D>1X0q_<8ZvpTY0B-^C765Mn z@D>1X0q_<8ZvpTY0B-^C765Mn@D>1X0q_<8ZvpTY0B-^C765Mn@D>1X0q_<8ZvpTY z0B-^C765Mn@D>1X0q_<8ZvpTY0B-^C765Mn@D>1X0q_<8Z%egWZJ}7IErC5j>ma`g z_C(lb*gev+$?_aF1-2M_zJ>i>T3#Uc^Fr8Vur1PxUU^iU4}S~UCLlHeu}PDNO+akY zBw~{$5t}rL*aXBTAT}|H*u*4a6O)KdKx_hH6PJihTp~6Bu?dJxLLxQ;u^EWXKx_tL zGZ34B*bKyGAT|TB8Hmk5YzAU85SxM648&$2HUqI4h|NH30b&afTY%UC#1y# zEkJAmVha#kfY<`W79h3&u?2`NKx_eG3lLj?*b2l}AhrUr6^N}sYz1N~5Lz)T02=>RhwV5WnZp`*l%w6eW*fSC?3(?QJ89%4q?Ww0&Mf|(9t zM*3UGb^);qh+T+97ZAIE*agHcAa((<3y57n>;hsJ5W9fb1;j2Oc2O*-d?0oKu?vXZ zK8;IRN>;_^t5W9ic4a9CBb_1~+h}}T!24Xi5BS4G*F#^O0 z5FlUqBS4G*F#^OW5Tihh0x=52C=jDSi~=zV z#3&G>K#T%03dAT7qd<%TF$%;e5Tihh0@0)vewHw)g-bh8qxUh?&ZU18wNevvYbIvZ zOw6j8S{1FnGqoDnxv=wK>u~-88jG1)BkV%#_rqTVKLCF*jSWq0DSWvS!=yeX5jVh| z340doM%YcTa@CNDSvwQ6b|z-+Ow8Jun6)!8YiDZL1M3D@`s69)x)GMX1(f`oVQ+z@ zZ|tN!J7I5yrO&0(p4(yXf!zgrFYJH8{ucIrSh+IX)a05sQ7O9$!%vds@K*TC z^Srf7gKS3Q|xK76_M$;8~RDbVjQ18fTP zJIn){VlmE?tD#J>6uz9fHANGAIh$&VX87opq6I!U6yQ)e9JYhW4%jZ(ZrBKHlx(k- zLeC_$ysQj082YLNvkvS|K6=8{@uL5nQ9 zze`_gkwy1+X{8ofc!OX;i!5l71ue3mMHaNkf)-iOB1@B6WNA{1ENGFXNiDLVMV2PD z$kL=1Sm7Fp0D3-35AXpx0C9Tv36!ut*jT4X_sENGDhEwZ3R7PQEM7Fp0D z3tD7Bi!4oQkp(TX@UFyy7Fp0D3tD91y@{nsEwVJJMHaNkVp5ANXpx1tDi*ZJf)-iO zA`4n%L5nQBXR)9~7L!_JL5nOVwa9`NSxjn?#iSNlOlpzEq!w9BYLUgH7Fjg!L^Yv# zCuyY?S@iryyg`dBXpsdivYQq%XC|qA`*5r50Hd$c7f#&>|aJWJ8N=Xps#qvY|ybw8(}Q+0Y^zT4Y0u zY-o`UEwZ6SHnhlw7TM4u8(L&Ti)?6-4K1>vMK-j^h8Ee-A{$y{LyK%^kqs@fp+z>d z$c7f#&>|aJWJ8N=Xps#qvY|ybw8(}Q+0Y^zT4Y0uY-o`UEwZ6SHnhlw7TM4u8(L&T zi)?6-4K1>vMK-j^h8Ee-A{$y{LyK%^kqs@fp+z>d$c7f#&>|aJWJ8N=Xps#qvY|yb zw8(}Q+0Y^zT4Y0uY-o`UEwZ6SHnhlw7TM4u8(L&Ti)?6-4K1>vMK-j^h8Ee-A{$y{ zLyK%^kqs@fp+z>d$c7f#&>|aJWJ8N=Xps#qvY|ybw8(}Q+0Y^zT4Y0uY-o`UEwZ6S zHnhlw7TM4u8(L&Ti)?6-4K1>vMK-j^h8Ed)F0!FTHnhlw7TM4u8(L&Ti)?6-4K1>v zMK-j^h8Ee-A{$y{LyK%^kqs@fp+z>d$c7f#&>|aJWJ8N=Xps#qvY|ybw8(}Q+0Y^z zT4Y0uY-o`UEwZ6SHnhlw7TM4u8(L&Ti)?6-4K1>vMK-j^h8Ee-A{$y{LyK%^kqs@f zp+z>d$c7f#&>|aJWJ8N=Xps#qibIRy(4siBC=M-(Lt*03qByiD4lRm9i_WK9C)1cM zLs~jV+Dx+j(5QZme!GNxIfCm)IsK$m7Wr}n*AJ!Yhf?)Jsrt2I8s+tqUNw`g!I^Vm z=fT#&E+Dn;~8~ zVd-0jXwODi`j#Q`<@l~2I@S*z>xYi@L&y4|WBt&ve$p{{{tc-AcGw$XZ-TuU_7>P3 zICCfLt+2Pj-VRIOFGS_Y&x!Ywj!FApu)l@9ANF^+x(8tCw;Sl32VwW1wh!Z+M}V~# z{vY7e_YTpSkHMFtyna$Mxkrxj`bo{CFGqR(q-N5Wqr84nGwDAE`#kK6urI;V_XpBZ z`o=1<^!O#1S(GySAy(wC#Weo`~(k4COBu<{wEpVUm+NwQtBqhP1u=nUAIupZca*g{yj zCZwPAjamrlo3wLaD}jRcN%}^u6#CXr`Xc&+M`6zt_(#J( z2L4p|)8J2sKLdU){F(3#_#XIq@blppz%PPd0(&fM8SEU`3fL;xT6yiHezLZ5RM=1I zCw)08>?ie;z8n?yL;dNnbvR^^^KZUp|TTllnuu)jKs;8e?;xRP$lmeR}Eoqvxnc6X$ z{C7B8tTA|+RzRuaGcBFA9G`1x+HuMk+F@F?@^$SHtyTFcT9y`5zDpafou+&mdusj4 zPt!(d`<0)m9j<+${46b(4Of0P`Nu1Nh&Gk=X!KQAdOFpsi(RgKrcGi$DxYgZ_>syN zS`qgsUmtW%igqaPRQp}pM1H#RQ?>1UoAT4NqeZpyGqnC2QqOglvXwep8+!}Le0!kyuGcx|ZN-5!hw-EC&?npn8AEAHOm&NDoo>F&9v*%=AB zE6rH184Je4W;EB=8;ZL9!Km#I^@J+PUR+TPWHdiVePku6Vrn*qJj|ty+~EREOK>`f}UMo|*sdSbR-ys6Awd zJEL?Bxn1#|NJE%Pw+X)w81b%5B*Ii ze=eP4($NUzc59X7$0(1qvXn4+Q7u>V(Y_FQZp}~oqnZsbr1j7l6?9I7P#4k}omwCH zLCWo+Tpq%iMYf!BRg#w|B~iu<+W*rs7Snc&N_TMG$x{Av&cqpmYZyj7B@=O6Pdm_L z?N-n}Q|lo6)9aVlCOPb(Ygj|+a?0VR^W~Mv(&DI}!*dvXv|*3r+u80W1|;7$l@q22 zBsjE*k8;{8&zBhTI{y{lGE#A3{8()!{jI`ZE+PChw~VfgRW9P(LudYP^Tp{}Wqf6= zB=?V*o33-YAwA9Wi^Ox=6=WUG?m^*igA3LZi{F8rTC*w>o zoux1rOJ!*+on^30mc_E!5H^$zW5d}YEQgI?BiSf6njOl=so@>u~ZWVFJSm9SEFESts3*l}z&JD$y9 z<*b5LvMN^1YS>&hkJYj|R?ixkm(6EBwtzLVh0Mf1lmawJl1lGh(WX)_DYhfp` zRu*K-SsQC-A=be@;>d zJA)8f&COeC5WSiL8>>Re4oy*Q+=d%k~Kik4CWEZiE*(K~!b{V^zUBRwoSFx+v zHSAh;9s3pA%C@oV*$r$vyOG_*Zf3Wz9c(ANmEFc}XLqnW*^JOgb`RUd?q&3Q z*z7)bKl>effbC`vvOVng>>>6rqhF?Ee_)TY$JpcS3AT?t$^OWmVo$SY*t6_8_9yl{ zdx5>k{>)xtFSA$JtBihKjJ?j@U~jUw*najldxsrh@3OzJ_Za<(3VWY@z&>PuXCJYT z*(Z#CnSy=BK4)LBFWFb@YxWQJ4f~dT$G&Gjupha`8Rwk7w~(iB7fv%nH;9fqT`}hLh$QN=yU&I4^F<-)$@)LLyKataWcizHJ;;lT$m-9B>&O^L|ck(VC z=G}Y+kMJHI{7ilp-^e%d zv-vrEGe4J~$Is^%@P599U&t@w7xPQ_rTj8}IlqEm$*rQi@8kE=@4i03ck>7N z9{zj&5Pz6{>vJ#tYUZQ-G5$Dzf_^3PN&3~or})$S8U8GPj{k{2&tKp#@;}qB_q|NN zX!k1pD%^kb*ZCX#P5SM${q&n!@9+ckD?@+b@A1F#zw!6^2mC|+cm5Ion18}Qrkz$gVERGUW#L?myF;z?x z)5Q#tD`pBqctoDa7X_kF6p3O{B1*-vVwNZq$BEhEcrizmiwaRGszkM@5p%^nQ7h_b zb!3C^iuuAP7Klc%Q250n5fF>T5?VoW0;mL`3w6D7~xcr5Vncuti+-iIrlNSS{9wwc=!Pia1rACQcV;h;?GU*dWdnXNiqs zlQ>(PBQ}e3#d+d!ivJS7759nz#qY!eVz+ou z>=C~g4~d7xBVw=kgLqUtCLR}0h<)No@kjBLcv?Ioo)yoDKZ)nX3*trbXYrDFS-c`% z6|af^7O#sp#GB$Rv0uC`-Vq1HyW%h6J@HrZH}SssKzu0vEFIigo~dW)+4>NDs6I>|t{Q0>&NI*^=bNaeTJT^ z&(sawqvz@QdVyZ37wN@%iC(H7tIyKQ^yBo|`tkZ4yhttky-u&! z8+5NeU-#(?^hSN5?$;OT0e!K)L|>|(pf~9!>dpExy+uDsZ`FhPa=lG&*F$=T-l=!# zVZB>lp-1!{J*t~}uWsov-PYrJpT1IGrLWf4=xgFVOq-E&7G}Mf%11CHkfMW%}j%75bI>Rr=NXHTt#sb^5RL zt@<|odi@4{yMCj7lYX;)i@rnOso$EK8#UwYp$G{vSz z-jFM_x-AmyNwfOQc&L4OBqQ3_vs{h{I-{<3GZG2LQhP%&dZ>=42Ybk~>2W_3C)-p~ zB$VD8jD@0+P)9ri9tJCEK{*Nt+bi_mNS~cTkMTW0SJ#@}u29rPWrWT46gv{MyY#i8 zm?_L?NW@o}DetiglvpWoM0YIB2;_y%Ygg3F35^U>>hj>q)Y(GKbthZ~3(=y~$$Pr{}Td1At5X_|J zk;s)rRqP=)`sfNnLy~oLSfcZ&8N?`aD!E<3NQVQdcG_8qb|J}fl_O5Ba?~TU+=*jH zB(&O94yMz~6AY!4$B0i}UY%B{s^qG6GFLm9s|PZtS0{31)Z!f3+%jr$o^*%S4xB5u zvuhLQ%PmnI?{dutyvyf6_#6n|KsJ}psh=;AGp(mD5)b!A*0_9VrLKUJHQ;0o3}j6Y zB=WdUz`>M7U1ltr(HV;MP`6$lv0XA0D?_fJlQ%e!*F{qe)Bw|ii6T;hpd}beYfI2V z(U+M+PUg@+=5z|B)7)HP=bW%}j_N;>_w;b$91$WKq7DtFbGqrAZVnXbGM)OEiCnJs z@XBy|$YnYt^f?*(oQ!<~8PofcIo9AH=?;;Qz9z9dwY(?T7Bi!%K__*UQ;(CJAW1DZ zJE?iCNDVrvs}hB{+8m(D0ievb0bj3dH{*I68CPXnkP3ITIZ2h1v?sP=W-#t*C-`7I zwOZAKCR}8FT-8oJLP#>IsjwhXAB|^(l5T3Xs$EFcuG%R$gd}tBK#ejx2YlCDr{qo~ z`dnGpPBK|@q1+BiR_CCN%y|R3GrIvu)O0dyo$HXhQp1j) zQ42`tEV!AqPR*UO9Dhh{@&e`VG}@A~A9mH&$!#9)&a4}#LuU7YpH)Ao(pf8hvLU4^ z8liR{ZgVv_L5v{DY8ZT8WYC7I!J#vPL~oEpMaZ}soJJRMlKD<)QKz)|g9^xs4%%?d zcS?&o!HEWYO*gmxojkv{sB5O>6Rz&ce1~x`Bk@1qZvCW zwaf2hw~=Hm8U&CPAGG0GAl>`v*(4my zs_wPJbYa+?RvmYaXV;P#VVCTXSw4C?BgMjwtiYfQ8NQxSr*q=)FlG4(UJCH^icmb5 zGB-$9h=+~*(t=clsW;Ifx=9AmMYc>pgM?+3}l9z9_$E*J%*8&pYRGjNiQ$y4IC}VRyhg_C9}z`BDs}3zc}fY zB)!svS7ao;Bvw%Z%TrL8IO<83;z^d`NtTkAEF~{lN?xKABd;J)N?x+OyrSg3WXXBS zlJk-!=O;_fPnMjYEIB{PMSc<^KZ%i_#K=!#xmlNbd_jDjRaK@y`NiBXWm7~rKK ziBXWmC`e)yBr%GTwJJ*HC`#riO6Dj^<|t0qsyJDf;$&TllXWRhmRy`Hxj0#JakAv% zWXUDTl1q};Tav^mNn(^FF-npcB}t5uBt}URqa=w@n#3qgVw5H^N|P9+NsQ7YMrjhG zG>K6>P)Y)WdWvd89wTwoVfh@Fg!*A!($|_!(${dJV}g!Iu|DP z8KotzCC+2EMqjLwD(Oc^W>+M#Uc2t8KE=w%&^%$&&wnaMds4QGg?Z`8x1}k# z?WN0Ui5{AwXiujR1m-llvM?%kd^=N4dni8(GarcqG)RtzgOT=dM@LE(?ial=v%Rk^ zo^JQiJw(S^I<2aV+8YsiVqaakmjZXz*rHKt0^TL5pyj)eum`Drl!L1s5CFTjb26**KK&XNIZvk55t4UpofyoLH_VTeoWpPLs@dx zCqZwPobMUfAOaE_nKb{C@Uy{2atpL1wzA}eMPftNG|w;$m7?afou{_*Ra&6ZLX{S& zv{?v;gl+zQgxlB3a?b*l`6bag;%QZN)=wI!YfsH$%dYtPo^f=dF=mEZ`+Ucj1;y9%^PHEye>POqCAEl@trKlgJ zs2`=MAEl@trKlgJs2`=^hf>s!Qq<2=?etSh6~5C?XTj4wXl(rSV z(@$wz;XD15wiUk9Pib4>SAri;wbMr_RoCzIQQB75@AOgHR@YxyEc+U5mn8Zc`K4-K z`JjEO9!_7Sb5uPl6%UoF9!@{?R6G5YQdJM9pVGFfhtp4KTh+tqr?jo&;Pg}4R&j9p zDQ&AbIQ^8i6~5C?J=IP>rBubi>8G@<;^6dC+E#IJ`YCOzI5_>3wpARQeoEWw`kj7C z+v@tAeoEWw`kj92sdoA)rRsW}eo5QvdYyhr+v<9qewk;e`$E1^lQS@Vg+T~CEG{3k z55o?*?~sA>d45AwOa^vX0ya#H0}E>e2HmB;DXRvyP=t#t52 zD^HLQvy}3V4tYDu^W+(6ixLy9apk0R$|gH>&|M?*eX5$8&ls4F=e2d|a>fi3Lb~*_q)7}P)qvM1 zObld=LbME{!0E}9CVIANA(iDCt>BfbhBJPo-=)TC-Yi-$Hj4gpxg~ax)oF`-Wix2C zagoL%!FZJN4b!;S*WlJhE%bTav{G23a_HY+o6Hww2Y!+7XymIvj&xd?o2F&b`9o-3 z@(69THWvFcs0J=t<(x&e7)mRdM{0-C+GdH7L93-x$!1e+hiN%f?=e(|aglImP`eBE zUf2gB)M&JaVIPNmI%2j(v=?AsHRaK_VE+pHiEL!r*RVfG%XC|YGXwSz*s->4c-TbP zsjzuu^VqSlb6{)8=CcOag|JKGva}Z14%jI8k?W@AO6~!h3V*Oo!yajA2^Vqo%QO)y zCt}jdm4GsK|I>6J&I2)*`xr`bEGO1oD06U{LF|v$j-rK+McQnwhL$ZZ)>>4q1u9*u z(w!=ORHYxO^m8X=!&Ev-rFl*pWb^1chG{7S>vL#3MXRGfO?#967_D00Py61XKcT%# ze>!dDQd^p?T|lebw`dn??`t1wA8DUx2er>>RbeNs58TGCrxjQ)(`ux-bT*?kKRa-B zW3`Nbwn|8zLv4-PI(g1HKVL_5CLIxUP7a+jlFnqb-e^5VSN1gWDLNNX%*xw7w4 zE##*FMiA0O?P&T23_(jxee``8GHswwRB^4Az9WOvz5=oh5}l67f6{Z>gEq2-wnt#E zHgd7Ce&j+|`qYi{Hhz`OQu)^PBP(gw@tiSFrjhPSnKnf5u_>AnbY)C)(bCiP#hmF| z{YIlPebAo6uOENL;aVB~e6&j0#v1Gptr`wdqoO}!!l1(R5wp?*rwmy=_vGi#x%}CG zT=dOH9e2;#vvvLOWyX53)>zM%ZxwQ_5Viahk3EB`f(&ZgT-k*6Rpzp%8hw8?1xAA%Mbc@F5b z{{$*)N=yA`xaZ~>>wY!(B3X(i)}5~z>(1fp)@gfp9b7o_fwMQZ9y6-$#F_OMuGn

YE=h9c6s`zZi@B7|3|JKJY7qo+jyw@ z#DLjm_vX^%WtiTyMCHd6j4WbgTn=MD>fF$be7SXmKHZpV9KH3Zt&=uRR2kc1k)Pz7 z8Mo~jZNXgHZ;X&t!9)4r&ueb4SH?5zMwPEDC;*9k}rr*^xI=JiQ zlpoH1?b8b{ynFH3IX8W9(Ss$Wcl8y;kG;Zop!ohP&)Iir#kjlfdu;3ZOWykC#df`- za6Wr3|N7C7dv{KG?BM>54ZOs=VfCZm`QQ5BE!U>kw_kQ$OV$-{-}vC3^=CcOy8q4F zkAC^F8|&L&eeAFkci&c;_F~DzZTaWU+zUqt*wmtI% zzh}fViyj+w!x_#0STlQB?9{VIUpKw-`hEVVPd)C-smK1-cZqgmPsWC2|7h`le(2px zhW0-4?H9LSx^>9tH};M?qxFfQ)1n*oPe1s4^_1sQ{_s)3i7ofl<{iwZ-nWzSAB+5R)ijCJP@>IqHdo{>h5q&O`nYYENahGJ27Ww1Bo8DShE zccEGBWe2ts{a1C{eCnw*U6<&#ax*{CZU0ZSVm+HUm=)Pw*R!FTv7Tjc*`jvr`_1-0 zKIOhM{;g*k=PW(#yw_H|UUc2iJjU$rV?w%eiH)`)QAzy=2Bys|)fkJ><$m?t7za z=FY#o^YG^Lrap4+giRg0H!NLZ_U$R#dDNz5`-Y7y`_-B6FM22=y7z}a)V+RR>hQ}a zp7Pr4DbI~x{o$`XPkj29iDO>dd-vSRtHz$Rb^MkCEnj?e%BQE^x}5cY;mv&G*@=s9 zx%8Woo&NQQ3 z?mI$1)+jNGwiay7+nD%>(l2zwX)A-9N@Y1zM7Gp%lmDHBFc)bWB!pV#_A$ojMEe#w zStKFU&`M@_W)$WRj=vNV(&@St|9F4t!&QfS&RKKiw9EFazm5I*@P?=E+PpOSX4)|~ zv^>7=;+*&Nh1nm^oibA^x$D3a7tg=yg^9~Yesz5D1YfV`j8D%k*>v|`|9ZLh!!v=) z=1=<5jw$ok-tk|-^3SF|{oWI=w7mYiX=lyeb?vTK_AmMI!F&F2+857cUH8f5KTLam z*22RME1B}u@pZ;}{X6;}QvEoz@TmR2$vt%c2}6%L>$ZvSHUF%}#z}*^@xQx^78`{` z2=&n1N?Mj`yYt-(`j*pc4)=l>y|9U``Du@Jm-opfWAt(bchpj&FppmDCAy~Eq<7-Z z9d+Hk|HB$65y;FLHE>If_1SUv{16Q#V=Fwfj8dnHd5dVZo-IFr*Jp>^!MI!AS#0&` zxxu%jnX%rW`{=e~j8dvyuFNcQrX)*GTxg})PEQMT7n2VQ^robAMxK0B_)p#c!On5_ zwC<$U5{pNl((y#g#_ShAz3pae!v*J_^EEAA9_hM&#+ef?J@DK$3mU%t)5P7c9{f$= ztnvMiq<{NePHxklb51#K*5vVDezx@FYd&YY9?kge8BaerB_8aY;_ZI-!*#)>Yi@XJ z^sqxlPPuEpx8U??bKO<WQ*?2mmprlYU>zS^#5O4elWG;Voq zdh5LFUfMZ=?bz^A$%RH~&Sm1*Q|2tX_x87D9=74XZyCODHoyC&Y2Qz{_vYpshGy=# zY1o1x1-agvpMIic@(brZ@LBYfV;*43zVmEqdhxuoI+vb3X6v59Pu`z)!-V&?e7WJ> zTmIgbl@mU8y8n9i8Zq?}ZUaB>%Du9Sx%IHoX@p#vtsCdD zjbB%@)X~CNY#g1qyK^?`@P8SC~z_Lo++W9rW~igpsNqhV>Es?>;|v<89|(u;P(t&ggz&-l5Y^9+PWK z9(AO8dZBf|=1(7AR@&GnOOkgn5}r}Uhy*S@t*A#SA^w*l>5+vVq0?iOL61>eCvHS@ zr`G-pLF{b{=0gDG12H`wO*Guw#~X)x#u|sx4r=?u(d6?hlLA-hRCx$}q+rD5&#t)T zsNTo79e>FYX*2c~UcG(W_=7)F6RCgair>F}$;;)}2g7%byk+%c#-m%xPOJE8(!B>Z z*rRD3|FCPez5UI)nIHUqU)6iDw-($R80Ov(z3id`S2cFuQ|$Tg8)tlQp7z){-+SJ? z`_KA%{)69i211{7Ke%>Zd&$^g!&XRI47&mJ>&!_R7L{C_JyG*ThaD$Xk% z&{bMzV3Z_v_1T~5s%&%=v@_1%WAwGy5jJRv7+zG9m;r7ZEWwzN7cl*h#qK`hf7Y8F@ z`lvQN$+=hNc@D)>yq-B?=ptD*eV*F+jJBOX7XJeI-wuy1soHvJ_>@5Qv#*UhKd*3e zL;kHT?rjY(P2E)T(iJz(`D9FO=EU)S-@}zR?K^kJ;*X>AT(_i*EFIrAYtkWG?z`fd zeQAZK#@?B`kpp%@l$;d zeHB{JKJnV!r#^7|Z|ncKw0em5xf2?^3ANimYIiyfcd3KrV4U-lp-Ji)MwL8tgnpbs zx2vtiTMIYlC&oQ?TRsg<4}zcO(UJs739ol<@(oumT^N%^E#4*paYe{w~km~n*Uup1M?Dx>3Bxe=rQqUeH_EP`G1+X>CMjak)z-K(?_QbdHUfi|J=6wlU*0T+Z|iJ z|BFABm3(x|acL*rKX={wlTNI!{d}DJo1qt{KRa&B;;PZtpZ(dl=U;orSJ{Pclx5vk zbxCXW)T@8E+H9Eh>w?bSVHedogc=dWF{YgN_mtlK|d zHhKCxPi;14*Nbb`?7M0H9hndRaZ+mLLzk@oa@eQ$Z@KsCt6pv{%lY(u?mBdex9l7< zfAjMj-}u|o{J!HpxH$ZFl{sIFJoDmNuP(mns+*2~vSC8kmV>SL@Bgc7S?PqFyuW+a zi%ycoHqMx_?#cgeWseX0g`f}2Q*G@vh7D>FSspphFeW)`lrB73gAVJYa|6vM(=&u7 zCV5X7)e2{nT|Uw|@HNw4CVWhg7Zk-3zjBqCjVp7 Date: Wed, 22 Jun 2022 13:51:37 -0700 Subject: [PATCH 120/302] DM: track RHD predictions (#24947) * driverview * auto choose * useless * remove * modeld not use toggle * remove from params * Revert "remove from params" This reverts commit a08df0b4921e03deac24f4da2c0f1e9e9255a717. * Revert "modeld not use toggle" This reverts commit 2730bf8f57c8b057db2e4a76541e92880506cedd. * Revert "remove" This reverts commit 21f7cfaaee5452e53ee719762078cb153b3cc766. * Revert "driverview" This reverts commit 222d129711e6aa34c0468294b94f60ebbd1bb126. * semi revert --- selfdrive/modeld/models/dmonitoring.cc | 1 - selfdrive/modeld/models/dmonitoring.h | 1 - selfdrive/monitoring/driver_monitor.py | 21 +++++++++++---------- 3 files changed, 11 insertions(+), 12 deletions(-) diff --git a/selfdrive/modeld/models/dmonitoring.cc b/selfdrive/modeld/models/dmonitoring.cc index 8c7e14edb2..e7e6d46612 100644 --- a/selfdrive/modeld/models/dmonitoring.cc +++ b/selfdrive/modeld/models/dmonitoring.cc @@ -20,7 +20,6 @@ static inline T *get_buffer(std::vector &buf, const size_t size) { } void dmonitoring_init(DMonitoringModelState* s) { - s->is_rhd = Params().getBool("IsRHD"); #ifdef USE_ONNX_MODEL s->m = new ONNXModel("models/dmonitoring_model.onnx", &s->output[0], OUTPUT_SIZE, USE_DSP_RUNTIME, false, true); diff --git a/selfdrive/modeld/models/dmonitoring.h b/selfdrive/modeld/models/dmonitoring.h index 874722cd93..ae2bf05394 100644 --- a/selfdrive/modeld/models/dmonitoring.h +++ b/selfdrive/modeld/models/dmonitoring.h @@ -38,7 +38,6 @@ typedef struct DMonitoringModelResult { typedef struct DMonitoringModelState { RunModel *m; - bool is_rhd; float output[OUTPUT_SIZE]; std::vector net_input_buf; float calib[CALIB_LEN]; diff --git a/selfdrive/monitoring/driver_monitor.py b/selfdrive/monitoring/driver_monitor.py index f2d0524422..48d4303aa5 100644 --- a/selfdrive/monitoring/driver_monitor.py +++ b/selfdrive/monitoring/driver_monitor.py @@ -120,7 +120,7 @@ class DriverStatus(): self.settings = settings # init driver status - # self.wheelpos_learner = RunningStatFilter() + self.wheelpos_learner = RunningStatFilter() self.pose = DriverPose(self.settings._POSE_OFFSET_MAX_COUNT) self.pose_calibrated = False self.blink = DriverBlink() @@ -137,7 +137,8 @@ class DriverStatus(): self.distracted_types = [] self.driver_distracted = False self.driver_distraction_filter = FirstOrderFilter(0., self.settings._DISTRACTED_FILTER_TS, self.settings._DT_DMON) - self.wheel_on_right = rhd + self.wheel_on_right = False + self.rhd_toggled = rhd self.face_detected = False self.terminal_alert_cnt = 0 self.terminal_time = 0 @@ -225,14 +226,14 @@ class DriverStatus(): self.settings._POSE_YAW_THRESHOLD_STRICT]) / self.settings._POSE_YAW_THRESHOLD def update_states(self, driver_state, cal_rpy, car_speed, op_engaged): - # rhd_pred = driver_state.wheelOnRightProb - # if car_speed > 0.01: - # self.wheelpos_learner.push_and_update(rhd_pred) - # if self.wheelpos_learner.filtered_stat.n > self.settings._WHEELPOS_FILTER_MIN_COUNT: - # self.wheel_on_right = self.wheelpos_learner.filtered_stat.M > self.settings._WHEELPOS_THRESHOLD - # else: - # self.wheel_on_right = rhd_pred > self.settings._WHEELPOS_THRESHOLD - driver_data = driver_state.rightDriverData if self.wheel_on_right else driver_state.leftDriverData + rhd_pred = driver_state.wheelOnRightProb + if car_speed > 0.01: + self.wheelpos_learner.push_and_update(rhd_pred) + if self.wheelpos_learner.filtered_stat.n > self.settings._WHEELPOS_FILTER_MIN_COUNT: + self.wheel_on_right = self.wheelpos_learner.filtered_stat.M > self.settings._WHEELPOS_THRESHOLD + else: + self.wheel_on_right = rhd_pred > self.settings._WHEELPOS_THRESHOLD + driver_data = driver_state.rightDriverData if self.rhd_toggled else driver_state.leftDriverData if not all(len(x) > 0 for x in (driver_data.faceOrientation, driver_data.facePosition, driver_data.faceOrientationStd, driver_data.facePositionStd, driver_data.readyProb, driver_data.notReadyProb)): From fb949779ae151d9597cd70b5435f87edbffb1f53 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 22 Jun 2022 15:13:09 -0700 Subject: [PATCH 121/302] Chrysler: fill cruiseState.available (#24907) * Update some signals to unified names and definitions Co-authored-by: Jonathan * steering looks good * Fix cp signals * Do steering signal changes separately * bump opendbc to master * fix fix * check available is true if enabled is true * fix * already added * bump opendbc, better cruise status names * bump opendbc * bump opendbc to master * bump panda Co-authored-by: Jonathan --- opendbc | 2 +- panda | 2 +- selfdrive/car/chrysler/carstate.py | 31 +++++++++++++++--------------- 3 files changed, 18 insertions(+), 17 deletions(-) diff --git a/opendbc b/opendbc index 5e2a820268..e7cd3ebc89 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 5e2a82026842a7082e5e81e5823dab6b6616dbf4 +Subproject commit e7cd3ebc893047bf6eb947c60d8e3196b506e8d3 diff --git a/panda b/panda index e1b2f1253c..4bc85ad40a 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit e1b2f1253cb7f05f39d4afa21500565bb8b955d2 +Subproject commit 4bc85ad40ad032672008eb75567892ba45e0b932 diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index e3ee4753cc..f71a300263 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -18,10 +18,10 @@ class CarState(CarStateBase): self.frame = int(cp.vl["EPS_STATUS"]["COUNTER"]) - ret.doorOpen = any([cp.vl["DOORS"]["DOOR_OPEN_FL"], - cp.vl["DOORS"]["DOOR_OPEN_FR"], - cp.vl["DOORS"]["DOOR_OPEN_RL"], - cp.vl["DOORS"]["DOOR_OPEN_RR"]]) + ret.doorOpen = any([cp.vl["BCM_1"]["DOOR_OPEN_FL"], + cp.vl["BCM_1"]["DOOR_OPEN_FR"], + cp.vl["BCM_1"]["DOOR_OPEN_RL"], + cp.vl["BCM_1"]["DOOR_OPEN_RR"]]) ret.seatbeltUnlatched = cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_UNLATCHED"] == 1 # brake pedal @@ -51,12 +51,12 @@ class CarState(CarStateBase): ret.steeringRateDeg = cp.vl["STEERING"]["STEERING_RATE"] ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["GEAR"]["PRNDL"], None)) - ret.cruiseState.enabled = cp.vl["ACC_2"]["ACC_STATUS_2"] == 7 # ACC is green. - ret.cruiseState.available = ret.cruiseState.enabled # FIXME: for now same as enabled + ret.cruiseState.available = cp.vl["DAS_3"]["ACC_AVAILABLE"] == 1 # ACC is white + ret.cruiseState.enabled = cp.vl["DAS_3"]["ACC_ACTIVE"] == 1 # ACC is green ret.cruiseState.speed = cp.vl["DASHBOARD"]["ACC_SPEED_CONFIG_KPH"] * CV.KPH_TO_MS # CRUISE_STATE is a three bit msg, 0 is off, 1 and 2 are Non-ACC mode, 3 and 4 are ACC mode, find if there are other states too ret.cruiseState.nonAdaptive = cp.vl["DASHBOARD"]["CRUISE_STATE"] in (1, 2) - ret.accFaulted = cp.vl["ACC_2"]["ACC_FAULTED"] != 0 + ret.accFaulted = cp.vl["DAS_3"]["ACC_FAULTED"] != 0 ret.steeringTorque = cp.vl["EPS_STATUS"]["TORQUE_DRIVER"] ret.steeringTorqueEps = cp.vl["EPS_STATUS"]["TORQUE_MOTOR"] @@ -82,10 +82,10 @@ class CarState(CarStateBase): signals = [ # sig_name, sig_address ("PRNDL", "GEAR"), - ("DOOR_OPEN_FL", "DOORS"), - ("DOOR_OPEN_FR", "DOORS"), - ("DOOR_OPEN_RL", "DOORS"), - ("DOOR_OPEN_RR", "DOORS"), + ("DOOR_OPEN_FL", "BCM_1"), + ("DOOR_OPEN_FR", "BCM_1"), + ("DOOR_OPEN_RL", "BCM_1"), + ("DOOR_OPEN_RR", "BCM_1"), ("Brake_Pedal_State", "ESP_1"), ("Accelerator_Position", "ECM_5"), ("SPEED_LEFT", "SPEED_1"), @@ -97,8 +97,9 @@ class CarState(CarStateBase): ("STEER_ANGLE", "STEERING"), ("STEERING_RATE", "STEERING"), ("TURN_SIGNALS", "STEERING_LEVERS"), - ("ACC_STATUS_2", "ACC_2"), - ("ACC_FAULTED", "ACC_2"), + ("ACC_AVAILABLE", "DAS_3"), + ("ACC_ACTIVE", "DAS_3"), + ("ACC_FAULTED", "DAS_3"), ("HIGH_BEAM_FLASH", "STEERING_LEVERS"), ("ACC_SPEED_CONFIG_KPH", "DASHBOARD"), ("CRUISE_STATE", "DASHBOARD"), @@ -118,14 +119,14 @@ class CarState(CarStateBase): ("SPEED_1", 100), ("WHEEL_SPEEDS", 50), ("STEERING", 100), - ("ACC_2", 50), + ("DAS_3", 50), ("GEAR", 50), ("ECM_5", 50), ("WHEEL_BUTTONS", 50), ("DASHBOARD", 15), ("STEERING_LEVERS", 10), ("SEATBELT_STATUS", 2), - ("DOORS", 1), + ("BCM_1", 1), ("TRACTION_BUTTON", 1), ] From 569a39ff768ff1704bbf478719253b365070c98f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 22 Jun 2022 15:38:38 -0700 Subject: [PATCH 122/302] CANParser: invalid until valid (#24945) * CANParser: invalid until valid * bump opendbc * bump opendbc * fix counter in sim --- opendbc | 2 +- tools/sim/lib/can.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/opendbc b/opendbc index e7cd3ebc89..82be71072c 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit e7cd3ebc893047bf6eb947c60d8e3196b506e8d3 +Subproject commit 82be71072c52fc78cf0e1eabc396af26c18ddc11 diff --git a/tools/sim/lib/can.py b/tools/sim/lib/can.py index 2b1048fef2..939d081a80 100755 --- a/tools/sim/lib/can.py +++ b/tools/sim/lib/can.py @@ -63,7 +63,7 @@ def can_function(pm, speed, angle, idx, cruise_button, is_engaged): msg.append(packer.make_can_msg("SCM_FEEDBACK", 0, {"MAIN_ON": 1}, idx)) msg.append(packer.make_can_msg("POWERTRAIN_DATA", 0, {"ACC_STATUS": int(is_engaged)}, idx)) msg.append(packer.make_can_msg("HUD_SETTING", 0, {})) - msg.append(packer.make_can_msg("CAR_SPEED", 0, {})) + msg.append(packer.make_can_msg("CAR_SPEED", 0, {}, idx)) # *** cam bus *** msg.append(packer.make_can_msg("STEERING_CONTROL", 2, {}, idx)) From 2deaf69789fee9a048256a832ffddbda95242815 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Wed, 22 Jun 2022 15:58:06 -0700 Subject: [PATCH 123/302] Refactor torque stuff (#24921) * Refactor torque stuff * Add to release * Add substitute and override * Maxlataccel is required * Add to asserts * add ideal car * Need china too * yamls already linted * Fixed some bugs * Fixup * Unreliable data * Add cehck * Better comment * ref commit update --- .pre-commit-config.yaml | 2 +- docs/CARS.md | 70 ++++++++-------- release/files_common | 4 +- selfdrive/car/interfaces.py | 26 +++++- selfdrive/car/tests/test_car_interfaces.py | 1 + selfdrive/car/torque_data.json | 1 - selfdrive/car/torque_data/override.yaml | 29 +++++++ selfdrive/car/torque_data/params.yaml | 96 ++++++++++++++++++++++ selfdrive/car/torque_data/substitute.yaml | 75 +++++++++++++++++ selfdrive/test/process_replay/ref_commit | 2 +- 10 files changed, 263 insertions(+), 43 deletions(-) delete mode 100644 selfdrive/car/torque_data.json create mode 100644 selfdrive/car/torque_data/override.yaml create mode 100644 selfdrive/car/torque_data/params.yaml create mode 100644 selfdrive/car/torque_data/substitute.yaml diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 81ce927f65..b901e07721 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -20,7 +20,7 @@ repos: hooks: - id: mypy exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)/' - additional_dependencies: ['lxml', 'numpy', 'types-atomicwrites', 'types-pycurl', 'types-requests', 'types-certifi'] + additional_dependencies: ['types-PyYAML', 'lxml', 'numpy', 'types-atomicwrites', 'types-pycurl', 'types-requests', 'types-certifi'] args: - --warn-redundant-casts - --warn-return-any diff --git a/docs/CARS.md b/docs/CARS.md index de7dbacf28..fb163b44e0 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -35,7 +35,7 @@ How We Rate The Cars **All supported cars can move between the tiers as support changes.** -# Gold - 33 cars +# Gold - 31 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -55,8 +55,6 @@ How We Rate The Cars |Lexus|NX Hybrid 2020|All|||||| |Lexus|RX 2020-22|All|||||| |Lexus|UX Hybrid 2019-21|All|||||| -|Toyota|Alphard 2019-20|All|||||| -|Toyota|Alphard Hybrid 2021|All|||||| |Toyota|Avalon 2022|All|||||| |Toyota|Avalon Hybrid 2022|All|||||| |Toyota|Camry 2021-22|All||[4](#footnotes)|||| @@ -73,13 +71,12 @@ How We Rate The Cars |Toyota|RAV4 2019-21|All|||||| |Toyota|RAV4 Hybrid 2019-21|All|||||| -# Silver - 76 cars +# Silver - 67 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| |Audi|A3 2014-19|ACC + Lane Assist|||||| |Audi|A3 Sportback e-tron 2017-18|ACC + Lane Assist|||||| -|Audi|Q2 2018|ACC + Lane Assist|||||| |Audi|RS3 2018|ACC + Lane Assist|||||| |Audi|S3 2015-17|ACC + Lane Assist|||||| |Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise|||||| @@ -113,22 +110,18 @@ How We Rate The Cars |Lexus|NX 2018-19|All|[3](#footnotes)||||| |Lexus|NX Hybrid 2018-19|All|[3](#footnotes)||||| |Lexus|RX Hybrid 2020-21|All|||||| -|Mazda|CX-5 2022|All|||||| +|Nissan|Altima 2019-20|ProPILOT|||||| +|Nissan|Leaf 2018-22|ProPILOT|||||| +|Nissan|Rogue 2018-20|ProPILOT|||||| +|Nissan|X-Trail 2017|ProPILOT|||||| |SEAT|Ateca 2018|Driver Assistance|||||| |SEAT|Leon 2014-20|Driver Assistance|||||| |Subaru|Ascent 2019-20|All|||||| |Subaru|Crosstrek 2020-21|EyeSight|||||| |Subaru|Forester 2019-21|All|||||| |Subaru|Impreza 2020-21|EyeSight|||||| -|Škoda|Kamiq 2021[5](#footnotes)|Driver Assistance|||||| -|Škoda|Karoq 2019|Driver Assistance|||||| -|Škoda|Kodiaq 2018-19|Driver Assistance|||||| -|Škoda|Octavia 2015, 2018-19|Driver Assistance|||||| -|Škoda|Octavia RS 2016|Driver Assistance|||||| -|Škoda|Scala 2020|Driver Assistance|||||| -|Škoda|Superb 2015-18|Driver Assistance|||||| -|Toyota|Avalon 2019-21|TSS-P|[3](#footnotes)||||| -|Toyota|Avalon Hybrid 2019-21|TSS-P|[3](#footnotes)||||| +|Toyota|Alphard 2019-20|All|||||| +|Toyota|Alphard Hybrid 2021|All|||||| |Toyota|Camry 2018-20|All||[4](#footnotes)|||| |Toyota|Camry Hybrid 2018-20|All||[4](#footnotes)|||| |Toyota|Highlander 2017-19|All|[3](#footnotes)||||| @@ -138,7 +131,6 @@ How We Rate The Cars |Toyota|RAV4 2022|All|||||| |Toyota|RAV4 Hybrid 2016-18|TSS-P|[3](#footnotes)||||| |Toyota|RAV4 Hybrid 2022|All|||||| -|Toyota|Sienna 2018-20|All|[3](#footnotes)||||| |Volkswagen|Atlas 2018-19, 2022[7](#footnotes)|Driver Assistance|||||| |Volkswagen|e-Golf 2014, 2018-20|Driver Assistance|||||| |Volkswagen|Golf 2015-20|Driver Assistance|||||| @@ -148,23 +140,21 @@ How We Rate The Cars |Volkswagen|Golf R 2016-19|Driver Assistance|||||| |Volkswagen|Golf SportsVan 2016|Driver Assistance|||||| |Volkswagen|Golf SportWagen 2015|Driver Assistance|||||| +|Volkswagen|Passat 2015-19[6](#footnotes)|Driver Assistance|||||| |Volkswagen|Polo 2020|Driver Assistance|||||| -|Volkswagen|T-Cross 2021[7](#footnotes)|Driver Assistance|||||| -|Volkswagen|T-Roc 2021[7](#footnotes)|Driver Assistance|||||| -|Volkswagen|Taos 2022[7](#footnotes)|Driver Assistance|||||| -|Volkswagen|Touran 2017|Driver Assistance|||||| -# Bronze - 67 cars +# Bronze - 78 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| |Acura|ILX 2016-19|AcuraWatch Plus|||||| |Acura|RDX 2016-18|AcuraWatch Plus|||||| |Acura|RDX 2019-21|All|||||| +|Audi|Q2 2018|ACC + Lane Assist|||||| |Audi|Q3 2020-21|ACC + Lane Assist|||||| -|Cadillac|Escalade ESV 2016[1](#footnotes)|ACC + LKAS|||||| +|Cadillac|Escalade ESV 2016[1](#footnotes)|ACC + LKAS|||||| |Chrysler|Pacifica 2017-18|Adaptive Cruise|||||| -|Chrysler|Pacifica 2020|Adaptive Cruise|||||| +|Chrysler|Pacifica 2020|Adaptive Cruise|||||| |Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise|||||| |Chrysler|Pacifica Hybrid 2019-22|Adaptive Cruise|||||| |Genesis|G90 2018|All|||||| @@ -189,14 +179,14 @@ How We Rate The Cars |Honda|Passport 2019-21|All|||||| |Honda|Pilot 2016-21|Honda Sensing|||||| |Honda|Ridgeline 2017-22|Honda Sensing|||||| -|Hyundai|Elantra 2017-19|SCC + LKAS|||||| +|Hyundai|Elantra 2017-19|SCC + LKAS|||||| |Hyundai|Genesis 2015-16|SCC + LKAS|||||| |Hyundai|Ioniq Electric 2019|SCC + LKAS|||||| |Hyundai|Ioniq Hybrid 2017-19|SCC + LKAS|||||| |Hyundai|Ioniq Plug-in Hybrid 2019|SCC + LKAS|||||| |Hyundai|Sonata 2018-19|SCC + LKAS|||||| |Hyundai|Tucson 2021|SCC + LKAS|||||| -|Hyundai|Veloster 2019-20|SCC + LKAS|||||| +|Hyundai|Veloster 2019-20|SCC + LKAS|||||| |Jeep|Grand Cherokee 2016-18|Adaptive Cruise|||||| |Jeep|Grand Cherokee 2019-20|Adaptive Cruise|||||| |Kia|Niro Plug-in Hybrid 2019|SCC + LKAS|||||| @@ -205,26 +195,36 @@ How We Rate The Cars |Lexus|RC 2020|All|||||| |Lexus|RX 2016-18|All|[3](#footnotes)||||| |Lexus|RX Hybrid 2016-19|All|[3](#footnotes)||||| -|Mazda|CX-9 2021|All|||||| -|Nissan|Altima 2019-20|ProPILOT|||||| -|Nissan|Leaf 2018-22|ProPILOT|||||| -|Nissan|Rogue 2018-20|ProPILOT|||||| -|Nissan|X-Trail 2017|ProPILOT|||||| -|Subaru|Crosstrek 2018-19|EyeSight|||||| -|Subaru|Impreza 2017-19|EyeSight|||||| +|Mazda|CX-5 2022|All|||||| +|Mazda|CX-9 2021|All|||||| +|Subaru|Crosstrek 2018-19|EyeSight|||||| +|Subaru|Impreza 2017-19|EyeSight|||||| +|Škoda|Kamiq 2021[5](#footnotes)|Driver Assistance|||||| +|Škoda|Karoq 2019|Driver Assistance|||||| +|Škoda|Kodiaq 2018-19|Driver Assistance|||||| +|Škoda|Octavia 2015, 2018-19|Driver Assistance|||||| +|Škoda|Octavia RS 2016|Driver Assistance|||||| +|Škoda|Scala 2020|Driver Assistance|||||| +|Škoda|Superb 2015-18|Driver Assistance|||||| |Toyota|Avalon 2016-18|TSS-P|[3](#footnotes)||||| +|Toyota|Avalon 2019-21|TSS-P|[3](#footnotes)||||| +|Toyota|Avalon Hybrid 2019-21|TSS-P|[3](#footnotes)||||| |Toyota|C-HR 2017-21|All|||||| |Toyota|C-HR Hybrid 2017-19|All|||||| |Toyota|Corolla 2017-19|All|[3](#footnotes)||||| |Toyota|Prius v 2017|TSS-P|[3](#footnotes)||||| |Toyota|RAV4 2016-18|TSS-P|[3](#footnotes)||||| +|Toyota|Sienna 2018-20|All|[3](#footnotes)||||| |Volkswagen|Arteon 2018, 2021[7](#footnotes)|Driver Assistance|||||| -|Volkswagen|California 2021[7](#footnotes)|Driver Assistance|||||| -|Volkswagen|Caravelle 2020[7](#footnotes)|Driver Assistance|||||| +|Volkswagen|California 2021[7](#footnotes)|Driver Assistance|||||| +|Volkswagen|Caravelle 2020[7](#footnotes)|Driver Assistance|||||| |Volkswagen|Jetta 2018-21|Driver Assistance|||||| |Volkswagen|Jetta GLI 2021|Driver Assistance|||||| -|Volkswagen|Passat 2015-19[6](#footnotes)|Driver Assistance|||||| +|Volkswagen|T-Cross 2021[7](#footnotes)|Driver Assistance|||||| +|Volkswagen|T-Roc 2021[7](#footnotes)|Driver Assistance|||||| +|Volkswagen|Taos 2022[7](#footnotes)|Driver Assistance|||||| |Volkswagen|Tiguan 2019-22[7](#footnotes)|Driver Assistance|||||| +|Volkswagen|Touran 2017|Driver Assistance|||||| diff --git a/release/files_common b/release/files_common index 96649b9f16..0ace73623f 100644 --- a/release/files_common +++ b/release/files_common @@ -105,7 +105,9 @@ selfdrive/car/ecu_addrs.py selfdrive/car/isotp_parallel_query.py selfdrive/car/tests/__init__.py selfdrive/car/tests/test_car_interfaces.py -selfdrive/car/torque_data.json +selfdrive/car/torque_data/params.yaml +selfdrive/car/torque_data/substitute.yaml +selfdrive/car/torque_data/override.yaml selfdrive/car/body/*.py selfdrive/car/chrysler/*.py diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 9220aee522..c6a64fe919 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -1,4 +1,4 @@ -import json +import yaml import os import time from abc import abstractmethod, ABC @@ -20,7 +20,9 @@ EventName = car.CarEvent.EventName MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS ACCEL_MAX = 2.0 ACCEL_MIN = -3.5 -TORQUE_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data.json') +TORQUE_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/params.yaml') +TORQUE_OVERRIDE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/override.yaml') +TORQUE_SUBSTITUTE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/substitute.yaml') # generic car and radar interfaces @@ -109,9 +111,25 @@ class CarInterfaceBase(ABC): @staticmethod def get_torque_params(candidate, default=float('NaN')): + with open(TORQUE_SUBSTITUTE_PATH) as f: + sub = yaml.load(f, Loader=yaml.FullLoader) + if candidate in sub: + candidate = sub[candidate] + with open(TORQUE_PARAMS_PATH) as f: - data = json.load(f) - return {key: data[key].get(candidate, default) for key in data} + params = yaml.load(f, Loader=yaml.FullLoader) + with open(TORQUE_OVERRIDE_PATH) as f: + params_override = yaml.load(f, Loader=yaml.FullLoader) + + assert len(set(sub.keys()) & set(params.keys()) & set(params_override.keys())) == 0 + + if candidate in params_override: + out = params_override[candidate] + elif candidate in params: + out = params[candidate] + else: + raise NotImplementedError(f"Did not find torque params for {candidate}") + return {key:out[i] for i, key in enumerate(params['legend'])} @abstractmethod def _update(self, c: car.CarControl) -> car.CarState: diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index 15df1aafef..412874c813 100755 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -33,6 +33,7 @@ class TestCarInterfaces(unittest.TestCase): assert car_interface self.assertGreater(car_params.mass, 1) + self.assertGreater(car_params.maxLateralAccel, 0) if car_params.steerControlType != car.CarParams.SteerControlType.angle: tuning = car_params.lateralTuning.which() diff --git a/selfdrive/car/torque_data.json b/selfdrive/car/torque_data.json deleted file mode 100644 index 4917cba9bc..0000000000 --- a/selfdrive/car/torque_data.json +++ /dev/null @@ -1 +0,0 @@ -{"LAT_ACCEL_FACTOR": {"HONDA PILOT 2017": 1.682289482065265, "HONDA CIVIC 2016": 1.5248128495527884, "TOYOTA CAMRY 2018": 2.1115709806216447, "TOYOTA COROLLA HYBRID TSS2 2019": 2.3250600977240077, "TOYOTA RAV4 2019": 2.625504029066767, "HYUNDAI PALISADE 2020": 2.5250855675875634, "TOYOTA SIENNA 2018": 1.8254254785341577, "ACURA RDX 2020": 1.3998101622214894, "TOYOTA RAV4 2017": 1.948190869577896, "HONDA RIDGELINE 2017": 1.4158181862793415, "TOYOTA PRIUS 2017": 1.9142926195557595, "TOYOTA HIGHLANDER HYBRID 2020": 2.1097056247344392, "HYUNDAI SONATA 2020": 3.2488989629905944, "KIA STINGER GT2 2018": 2.7592622336517834, "TOYOTA HIGHLANDER 2020": 2.0408544157877055, "HONDA ACCORD 2018": 1.6374118241564064, "TOYOTA PRIUS TSS2 2021": 2.3207270770298365, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 1.46050785084946, "LEXUS NX 2020": 2.29533657249232, "TOYOTA RAV4 HYBRID 2019": 2.4003012079562085, "HONDA CIVIC (BOSCH) 2019": 1.6523031416671652, "KIA NIRO HYBRID 2021": 2.743464625803003, "HONDA ACCORD HYBRID 2018": 1.5904016830979033, "LEXUS NX HYBRID 2018": 2.398678119681945, "TOYOTA COROLLA TSS2 2019": 2.3859244449846466, "VOLKSWAGEN ARTEON 1ST GEN": 1.4249208219414902, "TOYOTA CAMRY HYBRID 2021": 2.5434553806317055, "VOLKSWAGEN JETTA 7TH GEN": 1.2228130240634283, "HONDA INSIGHT 2019": 1.468352089969897, "SUBARU FORESTER 2019": 3.6185035528523546, "HYUNDAI ELANTRA 2021": 3.5294999663335185, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 2.2179616966432905, "HYUNDAI KONA HYBRID 2020": 4.493208192966529, "HONDA ODYSSEY 2018": 1.8838175399087222, "LEXUS RX 2016": 1.3912132245094184, "TOYOTA COROLLA 2017": 3.0143547548384735, "LEXUS ES 2019": 2.012201253045193, "HYUNDAI SANTA FE 2019": 3.039728566484244, "TOYOTA AVALON 2022": 2.4619858654670885, "JEEP GRAND CHEROKEE V6 2018": 1.8411674990629987, "CHEVROLET VOLT PREMIER 2017": 1.5943438675127841, "TOYOTA RAV4 HYBRID 2017": 1.9803053616868995, "LEXUS RX 2020": 1.664616846377383, "TOYOTA HIGHLANDER HYBRID 2018": 1.8866764457400844, "TOYOTA CAMRY HYBRID 2018": 2.014213351947917, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 1.4428896585442685, "TOYOTA MIRAI 2021": 2.7217623852898853, "LEXUS IS 2018": 3.5624668608596837, "TOYOTA HIGHLANDER 2017": 1.9199133105823853, "HYUNDAI SONATA HYBRID 2021": 2.7313907441569554, "VOLKSWAGEN ATLAS 1ST GEN": 1.4483948408160645, "LEXUS ES HYBRID 2019": 2.4138026617523547, "HYUNDAI GENESIS 2015-2016": 1.7636839808044658, "JEEP GRAND CHEROKEE 2019": 1.787264083939164, "SUBARU ASCENT LIMITED 2019": 3.0494069339774565, "HONDA CR-V 2017": 1.9828470679233807, "HONDA FIT 2018": 1.594940026552055, "TOYOTA CAMRY 2021": 2.5057990840460342, "AUDI Q3 2ND GEN": 1.4558300885316715, "AUDI A3 3RD GEN": 1.5304173783542625, "LEXUS RX HYBRID 2017": 1.577216425446677, "HONDA CIVIC 2022": 2.69252285552613, "GENESIS G70 2018": 3.866842361627636, "CHRYSLER PACIFICA HYBRID 2018": 1.5771851419640903, "VOLKSWAGEN PASSAT 8TH GEN": 1.2985597059739313, "HONDA CR-V 2016": 0.7745984062630755, "HYUNDAI IONIQ PHEV 2020": 2.5696218908589383, "GMC ACADIA DENALI 2018": 1.3310088601868082, "HYUNDAI SONATA 2019": 1.9736552675022665, "TOYOTA AVALON 2019": 1.7245149905226294, "TOYOTA C-HR 2018": 1.5895016960662856, "HONDA CR-V HYBRID 2019": 2.0687746810729193, "CHRYSLER PACIFICA 2020": 1.40536880000744, "HYUNDAI IONIQ ELECTRIC 2020": 3.3220838625838667, "VOLKSWAGEN TIGUAN 2ND GEN": NaN, "LEXUS NX 2018": 1.7753192756242595, "KIA OPTIMA SX 2019 & 2016": 3.12625562280304, "TOYOTA AVALON HYBRID 2019": 1.7681286449373381, "TOYOTA RAV4 HYBRID 2022": 2.5518187542231816, "HONDA PASSPORT 2021": 1.5174924139130355, "KIA K5 2021": 2.482916204106975, "ACURA ILX 2016": 1.5237423964720282, "HYUNDAI IONIQ HYBRID 2017-2019": 2.3723887901632645, "KIA NIRO EV 2020": 2.924651969180446, "SUBARU IMPREZA SPORT 2020": 2.5317689549587694, "CHRYSLER PACIFICA HYBRID 2017": 1.167126725149114, "HYUNDAI KONA ELECTRIC 2019": 4.201092987427836, "HYUNDAI ELANTRA HYBRID 2021": 3.7153193626001926, "HYUNDAI SANTA FE HYBRID 2022": 3.3049230586030545, "CHRYSLER PACIFICA 2018": 1.524867383058782, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": 2.5970979517766213, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 1.5460982690267173, "MAZDA CX-9 2021": 1.9514800984278198, "HYUNDAI SANTA FE 2022": 3.5354982200434524, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 1.8902492836532216, "HONDA HRV 2019": 2.1262957371020352, "TOYOTA AVALON HYBRID 2022": 2.4142150048378683, "SUBARU IMPREZA LIMITED 2019": 1.2203463907025918, "GENESIS G80 2017": 2.4086794443413906, "VOLKSWAGEN TAOS 1ST GEN": 2.0031666974545947, "KIA FORTE E 2018 & GT 2021": 2.022553820222557, "CADILLAC ESCALADE ESV 2016": 1.5522339636408988, "TOYOTA C-HR 2021": 1.6519334844316687, "TOYOTA C-HR HYBRID 2018": 1.3193315010905482}, "MAX_LAT_ACCEL_MEASURED": {"HONDA PILOT 2017": 0.9069354290994807, "HONDA CIVIC 2016": 0.4030275472529351, "TOYOTA CAMRY 2018": 1.686123168195758, "TOYOTA COROLLA HYBRID TSS2 2019": 1.9139332621491167, "TOYOTA RAV4 2019": 2.234047196286479, "HYUNDAI PALISADE 2020": 1.8303582523301922, "TOYOTA SIENNA 2018": 1.4752503435300715, "ACURA RDX 2020": 0.40911581320000334, "TOYOTA RAV4 2017": 1.6622227720995595, "HONDA RIDGELINE 2017": 0.8224685813281227, "TOYOTA PRIUS 2017": 1.4548827870876067, "TOYOTA HIGHLANDER HYBRID 2020": 2.0649784271823037, "HYUNDAI SONATA 2020": 2.243989856570093, "KIA STINGER GT2 2018": 1.9531287107084392, "TOYOTA HIGHLANDER 2020": 1.659381392090836, "HONDA ACCORD 2018": 0.40486739531686267, "TOYOTA PRIUS TSS2 2021": 1.861541601048098, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 1.1930739374812243, "LEXUS NX 2020": 1.565268724838564, "TOYOTA RAV4 HYBRID 2019": 2.0915384047218426, "HONDA CIVIC (BOSCH) 2019": 0.4062886118517984, "KIA NIRO HYBRID 2021": NaN, "HONDA ACCORD HYBRID 2018": 0.35128914564548286, "LEXUS NX HYBRID 2018": 1.81821359787186, "TOYOTA COROLLA TSS2 2019": 1.911280958056631, "VOLKSWAGEN ARTEON 1ST GEN": 1.2587939472578302, "TOYOTA CAMRY HYBRID 2021": 2.312510643730013, "VOLKSWAGEN JETTA 7TH GEN": 1.232161945396623, "HONDA INSIGHT 2019": 0.5174836462945298, "SUBARU FORESTER 2019": 2.29255993930968, "HYUNDAI ELANTRA 2021": NaN, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 2.133978602602408, "HYUNDAI KONA HYBRID 2020": NaN, "HONDA ODYSSEY 2018": 0.8254773781363679, "LEXUS RX 2016": 1.0954776820595344, "TOYOTA COROLLA 2017": 2.2012870528168964, "LEXUS ES 2019": 2.069508805495439, "HYUNDAI SANTA FE 2019": 2.3763720477660253, "TOYOTA AVALON 2022": 2.531962323786023, "JEEP GRAND CHEROKEE V6 2018": 1.4193323242487865, "CHEVROLET VOLT PREMIER 2017": 1.8576430337666092, "TOYOTA RAV4 HYBRID 2017": 1.7425797219020926, "LEXUS RX 2020": 1.5118835180227874, "TOYOTA HIGHLANDER HYBRID 2018": 1.6872527654528833, "TOYOTA CAMRY HYBRID 2018": 1.6793468378089895, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 1.5614447712441282, "TOYOTA MIRAI 2021": 2.271146483563897, "LEXUS IS 2018": NaN, "TOYOTA HIGHLANDER 2017": 1.6573774863189379, "HYUNDAI SONATA HYBRID 2021": 1.9464120717803253, "VOLKSWAGEN ATLAS 1ST GEN": 1.6867005451451638, "LEXUS ES HYBRID 2019": 1.956450687999482, "HYUNDAI GENESIS 2015-2016": 1.5359761378898085, "JEEP GRAND CHEROKEE 2019": 1.2418961305308847, "SUBARU ASCENT LIMITED 2019": NaN, "HONDA CR-V 2017": 0.2642062271814174, "HONDA FIT 2018": 0.5896345937094754, "TOYOTA CAMRY 2021": 2.1783533980215166, "AUDI Q3 2ND GEN": 1.1582239457022647, "AUDI A3 3RD GEN": 1.598699116126939, "LEXUS RX HYBRID 2017": 1.319771127672888, "HONDA CIVIC 2022": 1.1806949852580793, "GENESIS G70 2018": 2.2496820850331134, "CHRYSLER PACIFICA HYBRID 2018": 1.294798200968084, "VOLKSWAGEN PASSAT 8TH GEN": 1.247540921731637, "HONDA CR-V 2016": 0.6991119250342539, "HYUNDAI IONIQ PHEV 2020": 1.9062392690595655, "GMC ACADIA DENALI 2018": 1.2986994230652662, "HYUNDAI SONATA 2019": 1.257445187146704, "TOYOTA AVALON 2019": 1.664577368475227, "TOYOTA C-HR 2018": 1.308490445144888, "HONDA CR-V HYBRID 2019": 0.4693072746041504, "CHRYSLER PACIFICA 2020": 1.1712413003138664, "HYUNDAI IONIQ ELECTRIC 2020": NaN, "VOLKSWAGEN TIGUAN 2ND GEN": 1.1573057001955744, "LEXUS NX 2018": 1.9457312007432144, "KIA OPTIMA SX 2019 & 2016": 2.0928228595938845, "TOYOTA AVALON HYBRID 2019": NaN, "TOYOTA RAV4 HYBRID 2022": 1.7647290773049569, "HONDA PASSPORT 2021": 0.8248357750132685, "KIA K5 2021": 1.4628018983720577, "ACURA ILX 2016": 0.6330753921140401, "HYUNDAI IONIQ HYBRID 2017-2019": NaN, "KIA NIRO EV 2020": 2.020186575503497, "SUBARU IMPREZA SPORT 2020": 2.136786720514988, "CHRYSLER PACIFICA HYBRID 2017": 1.0642918033307907, "HYUNDAI KONA ELECTRIC 2019": NaN, "HYUNDAI ELANTRA HYBRID 2021": NaN, "HYUNDAI SANTA FE HYBRID 2022": NaN, "CHRYSLER PACIFICA 2018": 1.3654603720349934, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": NaN, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 1.255230465866663, "MAZDA CX-9 2021": NaN, "HYUNDAI SANTA FE 2022": 3.3823387508235827, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 1.544104124172169, "HONDA HRV 2019": 0.7492792210307291, "TOYOTA AVALON HYBRID 2022": NaN, "SUBARU IMPREZA LIMITED 2019": 1.2203463907025918, "GENESIS G80 2017": NaN, "VOLKSWAGEN TAOS 1ST GEN": 1.6590543949912684, "KIA FORTE E 2018 & GT 2021": 2.3970573789339786, "CADILLAC ESCALADE ESV 2016": NaN, "TOYOTA C-HR 2021": 1.3559230155096402, "TOYOTA C-HR HYBRID 2018": 1.271271459066948}, "FRICTION": {"HONDA PILOT 2017": 0.2168217463499328, "HONDA CIVIC 2016": 0.28406761310944795, "TOYOTA CAMRY 2018": 0.1327947477896041, "TOYOTA COROLLA HYBRID TSS2 2019": 0.21792021497538405, "TOYOTA RAV4 2019": 0.12757022360707945, "HYUNDAI PALISADE 2020": 0.13391574986922777, "TOYOTA SIENNA 2018": 0.1853443239485906, "ACURA RDX 2020": 0.18058553315570297, "TOYOTA RAV4 2017": 0.14319170324556796, "HONDA RIDGELINE 2017": 0.2380553573913589, "TOYOTA PRIUS 2017": 0.2079869382946584, "TOYOTA HIGHLANDER HYBRID 2020": 0.14038812589302646, "HYUNDAI SONATA 2020": 0.08266051305053168, "KIA STINGER GT2 2018": 0.11909534626930472, "TOYOTA HIGHLANDER 2020": 0.14658637853444048, "HONDA ACCORD 2018": 0.21616610462729247, "TOYOTA PRIUS TSS2 2021": 0.20613763260512002, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 0.16250373743651828, "LEXUS NX 2020": 0.14404022591302845, "TOYOTA RAV4 HYBRID 2019": 0.1319247989758836, "HONDA CIVIC (BOSCH) 2019": 0.2575217845562353, "KIA NIRO HYBRID 2021": 0.14468633728800306, "HONDA ACCORD HYBRID 2018": 0.21150723931119184, "LEXUS NX HYBRID 2018": 0.16117151597250162, "TOYOTA COROLLA TSS2 2019": 0.21045927995242877, "VOLKSWAGEN ARTEON 1ST GEN": 0.17828895368353925, "TOYOTA CAMRY HYBRID 2021": 0.16283734136957057, "VOLKSWAGEN JETTA 7TH GEN": 0.19508489725001105, "HONDA INSIGHT 2019": 0.25750800088299297, "SUBARU FORESTER 2019": 0.11783702069698135, "HYUNDAI ELANTRA 2021": 0.09377564130711125, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 0.14740189509875762, "HYUNDAI KONA HYBRID 2020": 0.0863709736632968, "HONDA ODYSSEY 2018": 0.2125595696498247, "LEXUS RX 2016": 0.21475140622981923, "TOYOTA COROLLA 2017": 0.12325064090161544, "LEXUS ES 2019": 0.12757526660498053, "HYUNDAI SANTA FE 2019": 0.12230125806479573, "TOYOTA AVALON 2022": 0.11030226705639488, "JEEP GRAND CHEROKEE V6 2018": 0.12871972792344108, "CHEVROLET VOLT PREMIER 2017": 0.16697256960295873, "TOYOTA RAV4 HYBRID 2017": 0.14074453855329072, "LEXUS RX 2020": 0.2249895411716623, "TOYOTA HIGHLANDER HYBRID 2018": 0.16692807938039034, "TOYOTA CAMRY HYBRID 2018": 0.13418904852016877, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 0.19324413131475543, "TOYOTA MIRAI 2021": 0.20035237756713503, "LEXUS IS 2018": 0.073103111226694, "TOYOTA HIGHLANDER 2017": 0.17502689439420385, "HYUNDAI SONATA HYBRID 2021": 0.09518615688045734, "VOLKSWAGEN ATLAS 1ST GEN": 0.12761803335799474, "LEXUS ES HYBRID 2019": 0.1682771025433274, "HYUNDAI GENESIS 2015-2016": 0.10254237048034251, "JEEP GRAND CHEROKEE 2019": 0.15702739382013717, "SUBARU ASCENT LIMITED 2019": 0.12936982863095342, "HONDA CR-V 2017": 0.22518506713451308, "HONDA FIT 2018": 0.10803295063463647, "TOYOTA CAMRY 2021": 0.15512845523424743, "AUDI Q3 2ND GEN": 0.14083949977629878, "AUDI A3 3RD GEN": 0.1611945965384188, "LEXUS RX HYBRID 2017": 0.19322020114452776, "HONDA CIVIC 2022": 0.24279247053469405, "GENESIS G70 2018": 0.06869638264150804, "CHRYSLER PACIFICA HYBRID 2018": 0.13887505891474383, "VOLKSWAGEN PASSAT 8TH GEN": 0.21714039653367842, "HONDA CR-V 2016": 0.41726236462791455, "HYUNDAI IONIQ PHEV 2020": 0.13800461817330806, "GMC ACADIA DENALI 2018": 0.3447163106452739, "HYUNDAI SONATA 2019": 0.15371520337813344, "TOYOTA AVALON 2019": 0.10392921606262978, "TOYOTA C-HR 2018": 0.2015190716953846, "HONDA CR-V HYBRID 2019": 0.19595630321202379, "CHRYSLER PACIFICA 2020": 0.14337114313208268, "HYUNDAI IONIQ ELECTRIC 2020": 0.08104502306679212, "VOLKSWAGEN TIGUAN 2ND GEN": NaN, "LEXUS NX 2018": 0.1471001686544422, "KIA OPTIMA SX 2019 & 2016": 0.11703652166984638, "TOYOTA AVALON HYBRID 2019": 0.10863628402866225, "TOYOTA RAV4 HYBRID 2022": 0.14334213238415072, "HONDA PASSPORT 2021": 0.19826160782809032, "KIA K5 2021": 0.1027179720106188, "ACURA ILX 2016": 0.35663988815912573, "HYUNDAI IONIQ HYBRID 2017-2019": 0.12332151728479951, "KIA NIRO EV 2020": 0.0892074288578785, "SUBARU IMPREZA SPORT 2020": 0.15841234487251604, "CHRYSLER PACIFICA HYBRID 2017": 0.1345638758810282, "HYUNDAI KONA ELECTRIC 2019": 0.08503096350356723, "HYUNDAI ELANTRA HYBRID 2021": 0.09887804390243872, "HYUNDAI SANTA FE HYBRID 2022": 0.11171499761140577, "CHRYSLER PACIFICA 2018": 0.13611561752951415, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": 0.10502695501512567, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 0.21818156330777305, "MAZDA CX-9 2021": 0.1793735649504697, "HYUNDAI SANTA FE 2022": 0.09184808719698756, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 0.14050744688135813, "HONDA HRV 2019": 0.17840321248608593, "TOYOTA AVALON HYBRID 2022": 0.16159049452515487, "SUBARU IMPREZA LIMITED 2019": 0.20322553080306893, "GENESIS G80 2017": 0.07934444681782107, "VOLKSWAGEN TAOS 1ST GEN": 0.18276122764341485, "KIA FORTE E 2018 & GT 2021": 0.11406160665068436, "CADILLAC ESCALADE ESV 2016": 0.15063766975884627, "TOYOTA C-HR 2021": 0.22798633346500694, "TOYOTA C-HR HYBRID 2018": 0.2036375866375624}, "ERROR_RATIO": {"HONDA PILOT 2017": 0.6158457247286419, "HONDA CIVIC 2016": 2.0785618623350928, "TOYOTA CAMRY 2018": 0.17356565057429169, "TOYOTA COROLLA HYBRID TSS2 2019": 0.10094741777075293, "TOYOTA RAV4 2019": 0.11812042718338775, "HYUNDAI PALISADE 2020": 0.30639442561268304, "TOYOTA SIENNA 2018": 0.1117307389748361, "ACURA RDX 2020": 1.9801454495960717, "TOYOTA RAV4 2017": 0.08589486116378196, "HONDA RIDGELINE 2017": 0.4319851914417577, "TOYOTA PRIUS 2017": 0.17281316158588575, "TOYOTA HIGHLANDER HYBRID 2020": 0.046325388721577, "HYUNDAI SONATA 2020": 0.4109860794021653, "KIA STINGER GT2 2018": 0.3517628781488943, "TOYOTA HIGHLANDER 2020": 0.14155072865224166, "HONDA ACCORD 2018": 2.510398061115294, "TOYOTA PRIUS TSS2 2021": 0.13593456264106363, "NISSAN LEAF 2018": NaN, "CHRYSLER PACIFICA HYBRID 2019": 0.08794943266738546, "LEXUS NX 2020": 0.3743942573190866, "TOYOTA RAV4 HYBRID 2019": 0.0845492503791727, "HONDA CIVIC (BOSCH) 2019": 2.4329816697390063, "KIA NIRO HYBRID 2021": NaN, "HONDA ACCORD HYBRID 2018": 2.9252406767451804, "LEXUS NX HYBRID 2018": 0.23060712246809048, "TOYOTA COROLLA TSS2 2019": 0.13822363784977285, "VOLKSWAGEN ARTEON 1ST GEN": 0.009661691674299285, "TOYOTA CAMRY HYBRID 2021": 0.029451711159377333, "VOLKSWAGEN JETTA 7TH GEN": 0.16591473170144055, "HONDA INSIGHT 2019": 1.3398692842898896, "SUBARU FORESTER 2019": 0.5269683780697442, "HYUNDAI ELANTRA 2021": NaN, "HYUNDAI IONIQ ELECTRIC LIMITED 2019": 0.02971857401969039, "HYUNDAI KONA HYBRID 2020": NaN, "HONDA ODYSSEY 2018": 1.0245957242729038, "LEXUS RX 2016": 0.07392586589971588, "TOYOTA COROLLA 2017": 0.31336988069649124, "LEXUS ES 2019": 0.08933657038050916, "HYUNDAI SANTA FE 2019": 0.2276812089092099, "TOYOTA AVALON 2022": 0.07120118798045925, "JEEP GRAND CHEROKEE V6 2018": 0.2065164316228118, "CHEVROLET VOLT PREMIER 2017": 0.2316223989408518, "TOYOTA RAV4 HYBRID 2017": 0.055653752888652736, "LEXUS RX 2020": 0.047792182371008345, "TOYOTA HIGHLANDER HYBRID 2018": 0.019259474082467202, "TOYOTA CAMRY HYBRID 2018": 0.11949733140330816, "TESLA AP2 MODEL S": NaN, "VOLKSWAGEN GOLF 7TH GEN": 0.1996863736436734, "TOYOTA MIRAI 2021": 0.11019259478417197, "LEXUS IS 2018": NaN, "TOYOTA HIGHLANDER 2017": 0.05279963713251727, "HYUNDAI SONATA HYBRID 2021": 0.3543918194389536, "VOLKSWAGEN ATLAS 1ST GEN": 0.21694647502209782, "LEXUS ES HYBRID 2019": 0.14775474433507507, "HYUNDAI GENESIS 2015-2016": 0.0814892037361157, "JEEP GRAND CHEROKEE 2019": 0.3126997097753535, "SUBARU ASCENT LIMITED 2019": NaN, "HONDA CR-V 2017": 5.652613829506629, "HONDA FIT 2018": 1.5217432826711779, "TOYOTA CAMRY 2021": 0.07910435053686729, "AUDI Q3 2ND GEN": 0.13535089102138698, "AUDI A3 3RD GEN": 0.14353941401245793, "LEXUS RX HYBRID 2017": 0.048663813961824696, "HONDA CIVIC 2022": 1.0748206908458815, "GENESIS G70 2018": 0.688303429295532, "CHRYSLER PACIFICA HYBRID 2018": 0.11083725786301112, "VOLKSWAGEN PASSAT 8TH GEN": 0.13315924904555493, "HONDA CR-V 2016": 0.488871482749128, "HYUNDAI IONIQ PHEV 2020": 0.2756096845519595, "GMC ACADIA DENALI 2018": 0.24055364003040136, "HYUNDAI SONATA 2019": 0.4473315280277132, "TOYOTA AVALON 2019": 0.026428086100632363, "TOYOTA C-HR 2018": 0.06075105822970755, "HONDA CR-V HYBRID 2019": 2.9906016360828276, "CHRYSLER PACIFICA 2020": 0.07748732608487266, "HYUNDAI IONIQ ELECTRIC 2020": NaN, "VOLKSWAGEN TIGUAN 2ND GEN": NaN, "LEXUS NX 2018": 0.16318394527060903, "KIA OPTIMA SX 2019 & 2016": 0.4378756841929454, "TOYOTA AVALON HYBRID 2019": NaN, "TOYOTA RAV4 HYBRID 2022": 0.36478548056633514, "HONDA PASSPORT 2021": 0.5993860184637646, "KIA K5 2021": 0.6271500841947655, "ACURA ILX 2016": 0.8435442647921855, "HYUNDAI IONIQ HYBRID 2017-2019": NaN, "KIA NIRO EV 2020": 0.40355577782011604, "SUBARU IMPREZA SPORT 2020": 0.11071291640854522, "CHRYSLER PACIFICA HYBRID 2017": 0.029812269495458284, "HYUNDAI KONA ELECTRIC 2019": NaN, "HYUNDAI ELANTRA HYBRID 2021": NaN, "HYUNDAI SANTA FE HYBRID 2022": NaN, "CHRYSLER PACIFICA 2018": 0.01705753895996445, "NISSAN ROGUE 2019": NaN, "KIA SORENTO GT LINE 2018": NaN, "COMMA BODY": NaN, "NISSAN LEAF 2018 Instrument Cluster": NaN, "LEXUS RX HYBRID 2020": 0.05790668871480552, "MAZDA CX-9 2021": NaN, "HYUNDAI SANTA FE 2022": 0.018126919430513307, "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": 0.1331760659016062, "HONDA HRV 2019": 1.599688433820939, "TOYOTA AVALON HYBRID 2022": NaN, "SUBARU IMPREZA LIMITED 2019": 0.2514545160390271, "GENESIS G80 2017": NaN, "VOLKSWAGEN TAOS 1ST GEN": 0.09725484306423876, "KIA FORTE E 2018 & GT 2021": 0.20381871942480628, "CADILLAC ESCALADE ESV 2016": NaN, "TOYOTA C-HR 2021": 0.05016813984196128, "TOYOTA C-HR HYBRID 2018": 0.2521485862766935}} \ No newline at end of file diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml new file mode 100644 index 0000000000..fb086fd13f --- /dev/null +++ b/selfdrive/car/torque_data/override.yaml @@ -0,0 +1,29 @@ +legend: [LAT_ACCEL_FACTOR, MAX_LAT_ACCEL_MEASURED, FRICTION] +### angle control +# Nissan appears to have torque +NISSAN X-TRAIL 2017: [.nan, 1.5, .nan] +NISSAN ALTIMA 2020: [.nan, 1.5, .nan] +NISSAN LEAF 2018 Instrument Cluster: [.nan, 1.5, .nan] +NISSAN LEAF 2018: [.nan, 1.5, .nan] +NISSAN ROGUE 2019: [.nan, 1.5, .nan] + +# Tesla has high torque +TESLA AP1 MODEL S: [.nan, 2.5, .nan] +TESLA AP2 MODEL S: [.nan, 2.5, .nan] + +# Guess +FORD ESCAPE 4TH GEN: [.nan, 1.5, .nan] +FORD FOCUS 4TH GEN: [.nan, 1.5, .nan] +### + +# No steering wheel +COMMA BODY: [.nan, 1000, .nan] + +# Totally new car +KIA EV6 2022: [3.0, 2.5, 0.05] + +# Dashcam or fallback configured as ideal car +mock: [10.0, 10, 0.0] + +# Manually checked +HONDA CIVIC 2022: [2.5, 1.2, 0.15] diff --git a/selfdrive/car/torque_data/params.yaml b/selfdrive/car/torque_data/params.yaml new file mode 100644 index 0000000000..160f605488 --- /dev/null +++ b/selfdrive/car/torque_data/params.yaml @@ -0,0 +1,96 @@ +ACURA ILX 2016: [1.524988973896102, 0.519011053086259, 0.34236219253028] +ACURA RDX 2018: [0.9987728568686902, 0.5323765166196301, 0.303218805715844] +ACURA RDX 2020: [1.4314459806646749, 0.33874701282109954, 0.18048847083897598] +AUDI A3 3RD GEN: [1.5122414863077502, 1.7443517531719404, 0.15194151892450905] +AUDI Q3 2ND GEN: [1.4439223359448605, 1.2254955789112076, 0.1413798895978097] +CHEVROLET VOLT PREMIER 2017: [1.5961527626411784, 1.8422651988094612, 0.1572393918005158] +CHRYSLER PACIFICA 2018: [1.593387270257916, 1.3366521181047952, 0.13776367250652022] +CHRYSLER PACIFICA 2020: [1.4323553627965695, 1.509076559398423, 0.14328246159386085] +CHRYSLER PACIFICA HYBRID 2017: [1.3032470208409048, 1.06831764583744, 0.13287170990024627] +CHRYSLER PACIFICA HYBRID 2018: [1.6068280248761635, 1.2943025830995154, 0.1358557824293823] +CHRYSLER PACIFICA HYBRID 2019: [1.4624643614072217, 1.1958788168371808, 0.15748488008472716] +GENESIS G70 2018: [3.8520195946707947, 2.354697063349854, 0.06830285485626221] +GMC ACADIA DENALI 2018: [1.3181430320331884, 1.1853735340610179, 0.3450592280031644] +HONDA ACCORD 2018: [1.7135052593468778, 0.3461280068322071, 0.21579936052863807] +HONDA ACCORD HYBRID 2018: [1.6651615004829625, 0.30322180951193245, 0.2083000440586149] +HONDA CIVIC (BOSCH) 2019: [1.691708637466905, 0.40132900729454185, 0.25460295304024094] +HONDA CIVIC 2016: [1.6528895627785531, 0.4018518740819229, 0.25458812851328544] +HONDA CR-V 2016: [0.7667141440182675, 0.5927571534745969, 0.40909087636157127] +HONDA CR-V 2017: [2.01323205142022, 0.2700612209345081, 0.2238412881331528] +HONDA CR-V HYBRID 2019: [2.072034634644233, 0.7152085160516978, 0.20237105008376083] +HONDA FIT 2018: [1.5719981427109775, 0.5712761407108976, 0.110773383324281] +HONDA HRV 2019: [2.0661212805710205, 0.7521343418694775, 0.17760375789242094] +HONDA INSIGHT 2019: [1.5201671214069354, 0.5660229120683284, 0.25808042580281876] +HONDA ODYSSEY 2018: [1.8774809275211801, 0.8394431662987996, 0.2096978613792822] +HONDA PASSPORT 2021: [1.5305538930036766, 0.7956063674638759, 0.19599407381531284] +HONDA PILOT 2017: [1.7262026201812795, 0.9470005614967523, 0.21351430733218763] +HONDA RIDGELINE 2017: [1.4146525028237624, 0.7356572861629564, 0.23307177552211328] +HYUNDAI GENESIS 2015-2016: [1.8466226943929824, 1.5552063647830634, 0.0984484465421171] +HYUNDAI IONIQ ELECTRIC LIMITED 2019: [1.7662975472852054, 1.613755614526594, 0.17087579756306276] +HYUNDAI IONIQ PHEV 2020: [3.2928700076638537, 2.1193482926455656, 0.12463700961468778] +HYUNDAI IONIQ PLUG-IN HYBRID 2019: [2.970807902012267, 1.6312321830002083, 0.1088964990357482] +HYUNDAI KONA ELECTRIC 2019: [4.398306735170212, 3.2961956260770484, 0.08651833437845884] +HYUNDAI PALISADE 2020: [2.544642494803999, 1.8721703683337008, 0.1301424599248651] +HYUNDAI SANTA FE 2019: [3.0787027729757632, 2.6173437483495565, 0.1207019341823945] +HYUNDAI SANTA FE HYBRID 2022: [3.501877602644835, 2.729064118456137, 0.10384068104538963] +HYUNDAI SANTA FE PlUG-IN HYBRID 2022: [1.6953050513611045, 1.5837614296206861, 0.12672855941458458] +HYUNDAI SONATA 2019: [2.2200457811703953, 1.2967330275895228, 0.14039920986586393] +HYUNDAI SONATA 2020: [3.284505627881726, 2.1259108157250735, 0.08452048323586728] +HYUNDAI SONATA HYBRID 2021: [2.8990264092395734, 2.061410192222139, 0.0899805488717382] +JEEP GRAND CHEROKEE 2019: [1.7321233388827006, 1.289689569171081, 0.15046331002097185] +JEEP GRAND CHEROKEE V6 2018: [1.8776598027756923, 1.4057367824262523, 0.11725947414922003] +KIA K5 2021: [2.405339728085138, 1.460032270828705, 0.11650989850813716] +KIA NIRO EV 2020: [2.9215954981365337, 2.1500583840260044, 0.09236802474810267] +KIA SORENTO GT LINE 2018: [2.464854685101844, 1.5335274218367956, 0.12056170567599558] +KIA STINGER GT2 2018: [2.7499043387418967, 1.849652021986449, 0.12048334239559202] +LEXUS ES 2019: [2.0203086922726112, 2.134803912579666, 0.12757526789308554] +LEXUS ES HYBRID 2019: [2.392442298703042, 1.863360677810788, 0.17690002108856212] +LEXUS NX 2018: [2.302625600642627, 2.1382378491466625, 0.14986840878892838] +LEXUS NX 2020: [2.4331999786982936, 2.1045680431705414, 0.14099899317761067] +LEXUS NX HYBRID 2018: [2.4025593501080955, 1.8080446063815507, 0.15349361249519017] +LEXUS RX 2016: [1.5876816543130423, 1.0427699298523752, 0.21334066732397142] +LEXUS RX 2020: [1.5228812994274734, 1.431102486563665, 0.2093316728710659] +LEXUS RX HYBRID 2017: [1.6984261557042386, 1.3211501880159107, 0.1820354534928893] +LEXUS RX HYBRID 2020: [1.5522309889823778, 1.255230465866663, 0.2220954003055114] +MAZDA CX-9 2021: [1.7601682915983443, 1.0889677335154337, 0.17713792194297195] +SKODA SUPERB 3RD GEN: [1.166437404652981, 1.1686163012668165, 0.12194533036948708] +SUBARU FORESTER 2019: [3.6617001649776793, 2.342197172531713, 0.11075960785398745] +SUBARU IMPREZA LIMITED 2019: [1.0670704910352047, 0.8234374840709592, 0.20986563268614938] +SUBARU IMPREZA SPORT 2020: [2.6068223389108303, 2.134872342760203, 0.15261513193561627] +TOYOTA AVALON 2016: [2.5185770183845646, 1.7153346784214922, 0.10603968787111022] +TOYOTA AVALON 2019: [1.7036141952825095, 1.239619084240008, 0.08459830394899492] +TOYOTA AVALON 2022: [2.3154403649717357, 2.7777922854327124, 0.11453999639164605] +TOYOTA C-HR 2018: [1.5591084333664578, 1.271271459066948, 0.20259087058453193] +TOYOTA C-HR 2021: [1.7678810166088303, 1.3742176337919942, 0.2319674583741509] +TOYOTA CAMRY 2018: [2.1172995371905015, 1.7156177222420887, 0.13519250664782062] +TOYOTA CAMRY 2021: [2.6922769557433055, 2.3476510120007434, 0.1450430192989234] +TOYOTA CAMRY HYBRID 2018: [2.0974120828287774, 1.7996193116697359, 0.13823613467632756] +TOYOTA CAMRY HYBRID 2021: [2.6426668350384457, 2.3901492458927986, 0.16103875108816076] +TOYOTA COROLLA 2017: [3.117154369115421, 1.8438132575043773, 0.12289685869250652] +TOYOTA COROLLA HYBRID TSS2 2019: [2.3287672277252005, 1.8118712531729109, 0.2215868445753317] +TOYOTA COROLLA TSS2 2019: [2.4204464833010175, 1.9258612322678952, 0.20670411068012526] +TOYOTA HIGHLANDER 2017: [1.8696367437248915, 1.626293990451463, 0.17485372210240796] +TOYOTA HIGHLANDER 2020: [2.022340166827233, 1.6183134804881791, 0.14592306380054457] +TOYOTA HIGHLANDER HYBRID 2018: [1.9421825202382728, 1.6433903296845025, 0.16928956792275918] +TOYOTA HIGHLANDER HYBRID 2020: [2.103373061114133, 2.104015182965606, 0.14447040132184993] +TOYOTA MIRAI 2021: [2.506899832157829, 1.7417213930750164, 0.20182618449440565] +TOYOTA PRIUS 2017: [2.0183401513314294, 1.5023147650693636, 0.20856908464957724] +TOYOTA PRIUS TSS2 2021: [2.327639738920072, 1.9104337425537743, 0.2030762265549664] +TOYOTA RAV4 2017: [2.085695074355425, 2.2142832316984733, 0.13339165270103975] +TOYOTA RAV4 2019: [2.5038362866776835, 2.0993589721530252, 0.1552425356342368] +TOYOTA RAV4 2019 8965: [2.5084506298290377, 2.4216520504763475, 0.11992835265067918] +TOYOTA RAV4 2019 x02: [2.7209621987605024, 2.2148637653781593, 0.10862567142268198] +TOYOTA RAV4 HYBRID 2017: [1.9796257271652042, 1.7503987331707576, 0.14628860048885406] +TOYOTA RAV4 HYBRID 2019: [2.2271858492309153, 2.074844961405639, 0.14382216826893632] +TOYOTA RAV4 HYBRID 2019 8965: [2.1077397198131336, 1.8162215166877735, 0.13891369391200137] +TOYOTA RAV4 HYBRID 2019 x02: [2.803624333289342, 2.272367966572498, 0.11364569214387774] +TOYOTA RAV4 HYBRID 2022: [2.241883248393209, 1.9304407208090029, 0.1565442715453653] +TOYOTA RAV4 HYBRID 2022 x02: [3.044930631831037, 2.3979189796380918, 0.14023209146703736] +TOYOTA SIENNA 2018: [1.8660896232147548, 1.3208264576110418, 0.18799149615227198] +VOLKSWAGEN ARTEON 1ST GEN: [1.45136518053819, 1.3639364049316804, 0.23806361745695032] +VOLKSWAGEN ATLAS 1ST GEN: [1.4677006726964945, 1.6733266634075656, 0.12959584092073367] +VOLKSWAGEN GOLF 7TH GEN: [1.3750394140491293, 1.5814743077200641, 0.2018321939386586] +VOLKSWAGEN JETTA 7TH GEN: [1.2271623034089392, 1.216955117387, 0.19437384688370712] +VOLKSWAGEN PASSAT 8TH GEN: [1.3432120736752917, 1.7087275587362314, 0.19444383787326647] +VOLKSWAGEN TIGUAN 2ND GEN: [0.9711965500094828, 1.0001565939459098, 0.1465626137072916] +legend: [LAT_ACCEL_FACTOR, MAX_LAT_ACCEL_MEASURED, FRICTION] diff --git a/selfdrive/car/torque_data/substitute.yaml b/selfdrive/car/torque_data/substitute.yaml new file mode 100644 index 0000000000..d368b2c672 --- /dev/null +++ b/selfdrive/car/torque_data/substitute.yaml @@ -0,0 +1,75 @@ +MAZDA 3: MAZDA CX-9 2021 +MAZDA 6: MAZDA CX-9 2021 +MAZDA CX-5: MAZDA CX-9 2021 +MAZDA CX-5 2022: MAZDA CX-9 2021 +MAZDA CX-9: MAZDA CX-9 2021 + +TOYOTA ALPHARD HYBRID 2021 : TOYOTA SIENNA 2018 +TOYOTA ALPHARD 2020: TOYOTA SIENNA 2018 +TOYOTA PRIUS v 2017 : TOYOTA PRIUS 2017 +TOYOTA RAV4 2022: TOYOTA RAV4 HYBRID 2022 +TOYOTA C-HR HYBRID 2018: TOYOTA C-HR 2018 +LEXUS IS 2018: LEXUS NX 2018 +LEXUS CT HYBRID 2018 : LEXUS NX 2018 +LEXUS ES HYBRID 2018: TOYOTA CAMRY HYBRID 2018 +LEXUS NX HYBRID 2020: LEXUS NX 2020 +LEXUS RC 2020: LEXUS NX 2020 +TOYOTA AVALON HYBRID 2019: TOYOTA AVALON 2019 +TOYOTA AVALON HYBRID 2022: TOYOTA AVALON 2022 + +KIA OPTIMA SX 2019 & 2016: HYUNDAI SONATA 2020 +KIA OPTIMA HYBRID 2017 & SPORTS 2019: HYUNDAI SONATA 2020 +KIA FORTE E 2018 & GT 2021: HYUNDAI SONATA 2020 +KIA CEED INTRO ED 2019: HYUNDAI SONATA 2020 +KIA SELTOS 2021: HYUNDAI SONATA 2020 +KIA NIRO HYBRID 2019: KIA NIRO EV 2020 +KIA NIRO HYBRID 2021: KIA NIRO EV 2020 +HYUNDAI VELOSTER 2019: HYUNDAI SONATA 2019 +HYUNDAI I30 N LINE 2019 & GT 2018 DCT: HYUNDAI SONATA 2019 +HYUNDAI KONA 2020: HYUNDAI KONA ELECTRIC 2019 +HYUNDAI KONA HYBRID 2020: HYUNDAI KONA ELECTRIC 2019 +HYUNDAI IONIQ HYBRID 2017-2019: HYUNDAI IONIQ PLUG-IN HYBRID 2019 +HYUNDAI IONIQ HYBRID 2020-2022: HYUNDAI IONIQ PLUG-IN HYBRID 2019 +HYUNDAI IONIQ ELECTRIC 2020: HYUNDAI IONIQ PLUG-IN HYBRID 2019 +HYUNDAI ELANTRA 2017: HYUNDAI SONATA 2019 +HYUNDAI ELANTRA HYBRID 2021: HYUNDAI SONATA 2020 +HYUNDAI ELANTRA 2021: HYUNDAI SONATA 2020 +HYUNDAI TUCSON 2019: HYUNDAI SANTA FE 2019 +HYUNDAI SANTA FE 2022: HYUNDAI SANTA FE HYBRID 2022 +GENESIS G90 2017: GENESIS G70 2018 +GENESIS G80 2017: GENESIS G70 2018 +GENESIS G70 2020: HYUNDAI SONATA 2020 + +HONDA FREED 2020: HONDA ODYSSEY 2018 +HONDA CR-V EU 2016: HONDA CR-V 2016 +HONDA CIVIC SEDAN 1.6 DIESEL 2019: HONDA CIVIC (BOSCH) 2019 +HONDA E 2020: HONDA CIVIC (BOSCH) 2019 +HONDA ODYSSEY CHN 2019: HONDA ODYSSEY 2018 + +BUICK REGAL ESSENCE 2018: CHEVROLET VOLT PREMIER 2017 +CADILLAC ESCALADE ESV 2016: CHEVROLET VOLT PREMIER 2017 +CADILLAC ATS Premium Performance 2018: CHEVROLET VOLT PREMIER 2017 +CHEVROLET MALIBU PREMIER 2017: CHEVROLET VOLT PREMIER 2017 +HOLDEN ASTRA RS-V BK 2017: CHEVROLET VOLT PREMIER 2017 + +SKODA OCTAVIA 3RD GEN: SKODA SUPERB 3RD GEN +SKODA SCALA 1ST GEN: SKODA SUPERB 3RD GEN +SKODA KODIAQ 1ST GEN: SKODA SUPERB 3RD GEN +SKODA KAROQ 1ST GEN: SKODA SUPERB 3RD GEN +SKODA KAMIQ 1ST GEN: SKODA SUPERB 3RD GEN +VOLKSWAGEN T-ROC 1ST GEN: VOLKSWAGEN TIGUAN 2ND GEN +VOLKSWAGEN T-CROSS 1ST GEN: VOLKSWAGEN TIGUAN 2ND GEN +VOLKSWAGEN TOURAN 2ND GEN: VOLKSWAGEN TIGUAN 2ND GEN +VOLKSWAGEN TRANSPORTER T6.1: VOLKSWAGEN TIGUAN 2ND GEN +AUDI Q2 1ST GEN: VOLKSWAGEN TIGUAN 2ND GEN +VOLKSWAGEN TAOS 1ST GEN: VOLKSWAGEN TIGUAN 2ND GEN +VOLKSWAGEN POLO 6TH GEN: VOLKSWAGEN GOLF 7TH GEN +SEAT LEON 3RD GEN: VOLKSWAGEN GOLF 7TH GEN +SEAT ATECA 1ST GEN: VOLKSWAGEN GOLF 7TH GEN + +# Old subarus don't have much data guessing it's like low torque impreza +SUBARU OUTBACK 2018 - 2019: SUBARU IMPREZA LIMITED 2019 +SUBARU OUTBACK 2015 - 2017: SUBARU IMPREZA LIMITED 2019 +SUBARU FORESTER 2017 - 2018: SUBARU IMPREZA LIMITED 2019 +SUBARU LEGACY 2015 - 2018: SUBARU IMPREZA LIMITED 2019 +SUBARU ASCENT LIMITED 2019: SUBARU FORESTER 2019 diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 05d016911b..662f8cc5b8 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -2d736ca51acc1ac06216631b0529b50d9a6d2170 \ No newline at end of file +41161c8d151b0c2017214cad0aad3156533ab868 From d8bfe2f0052390b8864910b00e43f61c0eeb9ff7 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Wed, 22 Jun 2022 19:20:07 -0700 Subject: [PATCH 124/302] Cleanup car interfaces (#24948) * remove interface overrides * Fix test * set torque tune for ev6 --- selfdrive/car/hyundai/interface.py | 6 +----- selfdrive/car/interfaces.py | 10 ++++++---- selfdrive/car/toyota/interface.py | 7 ------- 3 files changed, 7 insertions(+), 16 deletions(-) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 2739ebd8cc..7cfce55100 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -204,7 +204,6 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.80 ret.steerRatio = 13.75 tire_stiffness_factor = 0.5 - torque_params = CarInterfaceBase.get_torque_params(CAR.KIA_OPTIMA) set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION']) elif candidate == CAR.KIA_STINGER: ret.lateralTuning.pid.kf = 0.00005 @@ -245,10 +244,7 @@ class CarInterface(CarInterfaceBase): ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.noOutput), get_safety_config(car.CarParams.SafetyModel.hyundaiHDA2)] tire_stiffness_factor = 0.65 - - ret.maxLateralAccel = 2. - # TODO override until there is more data - set_torque_tune(ret.lateralTuning, 2.0, 0.05) + set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION']) # Genesis elif candidate == CAR.GENESIS_G70: diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index c6a64fe919..ced2ce8e61 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -119,12 +119,14 @@ class CarInterfaceBase(ABC): with open(TORQUE_PARAMS_PATH) as f: params = yaml.load(f, Loader=yaml.FullLoader) with open(TORQUE_OVERRIDE_PATH) as f: - params_override = yaml.load(f, Loader=yaml.FullLoader) + override = yaml.load(f, Loader=yaml.FullLoader) - assert len(set(sub.keys()) & set(params.keys()) & set(params_override.keys())) == 0 + # Ensure no overlap + if sum([candidate in x for x in [sub, params, override]]) > 1: + raise RuntimeError(f'{candidate} is defined twice in torque config') - if candidate in params_override: - out = params_override[candidate] + if candidate in override: + out = override[candidate] elif candidate in params: out = params[candidate] else: diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index d0f4789775..75f2ab3033 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -54,9 +54,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 17.4 tire_stiffness_factor = 0.5533 ret.mass = 3340. * CV.LB_TO_KG + STD_CARGO_KG - # TODO override until there is enough data - ret.maxLateralAccel = 1.8 - torque_params = CarInterfaceBase.get_torque_params(CAR.PRIUS) set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION'], steering_angle_deadzone_deg) elif candidate in (CAR.RAV4, CAR.RAV4H): @@ -132,10 +129,6 @@ class CarInterface(CarInterfaceBase): ret.mass = 3585. * CV.LB_TO_KG + STD_CARGO_KG # Average between ICE and Hybrid set_lat_tune(ret.lateralTuning, LatTunes.PID_D) - # TODO: remove once there's data - if candidate == CAR.RAV4_TSS2_2022: - ret.maxLateralAccel = CarInterfaceBase.get_torque_params(CAR.RAV4H_TSS2_2022)['MAX_LAT_ACCEL_MEASURED'] - # 2019+ RAV4 TSS2 uses two different steering racks and specific tuning seems to be necessary. # See https://github.com/commaai/openpilot/pull/21429#issuecomment-873652891 for fw in car_fw: From 221086857aac770f5d22273119e6175eeb06c729 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 23 Jun 2022 13:58:01 -0700 Subject: [PATCH 125/302] EV6: adjust steering thresholds (#24901) * EV6: adjust steering thresholds * Is there any friction * bump panda * no friction Co-authored-by: Harald Schafer --- panda | 2 +- selfdrive/car/hyundai/carstate.py | 8 +++++--- selfdrive/car/hyundai/values.py | 26 ++++++++++++++----------- selfdrive/car/torque_data/override.yaml | 4 ++-- 4 files changed, 23 insertions(+), 17 deletions(-) diff --git a/panda b/panda index 4bc85ad40a..2652453892 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 4bc85ad40ad032672008eb75567892ba45e0b932 +Subproject commit 265245389208e1e6ada86b169e879c0a2e30426c diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 9d864faac4..6c82c33856 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -5,7 +5,7 @@ from cereal import car from common.conversions import Conversions as CV from opendbc.can.parser import CANParser from opendbc.can.can_define import CANDefine -from selfdrive.car.hyundai.values import DBC, STEER_THRESHOLD, FEATURES, HDA2_CAR, EV_CAR, HYBRID_CAR, Buttons +from selfdrive.car.hyundai.values import DBC, FEATURES, HDA2_CAR, EV_CAR, HYBRID_CAR, Buttons, CarControllerParams from selfdrive.car.interfaces import CarStateBase PREV_BUTTON_SAMPLES = 4 @@ -32,6 +32,8 @@ class CarState(CarStateBase): self.park_brake = False self.buttons_counter = 0 + self.params = CarControllerParams(CP) + def update(self, cp, cp_cam): if self.CP.carFingerprint in HDA2_CAR: return self.update_hda2(cp, cp_cam) @@ -61,7 +63,7 @@ class CarState(CarStateBase): 50, cp.vl["CGW1"]["CF_Gway_TurnSigLh"], cp.vl["CGW1"]["CF_Gway_TurnSigRh"]) ret.steeringTorque = cp.vl["MDPS12"]["CR_Mdps_StrColTq"] ret.steeringTorqueEps = cp.vl["MDPS12"]["CR_Mdps_OutTq"] - ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD + ret.steeringPressed = abs(ret.steeringTorque) > self.params.STEER_THRESHOLD ret.steerFaultTemporary = cp.vl["MDPS12"]["CF_Mdps_ToiUnavail"] != 0 or cp.vl["MDPS12"]["CF_Mdps_ToiFlt"] != 0 # cruise state @@ -157,7 +159,7 @@ class CarState(CarStateBase): ret.steeringAngleDeg = cp.vl["STEERING_SENSORS"]["STEERING_ANGLE"] * -1 ret.steeringTorque = cp.vl["MDPS"]["STEERING_COL_TORQUE"] ret.steeringTorqueEps = cp.vl["MDPS"]["STEERING_OUT_TORQUE"] - ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD + ret.steeringPressed = abs(ret.steeringTorque) > self.params.STEER_THRESHOLD ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(50, cp.vl["BLINKERS"]["LEFT_LAMP"], cp.vl["BLINKERS"]["RIGHT_LAMP"]) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index cf47501588..219e1619c0 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -13,21 +13,27 @@ class CarControllerParams: ACCEL_MAX = 2.0 # m/s def __init__(self, CP): + self.STEER_DELTA_UP = 3 + self.STEER_DELTA_DOWN = 7 + self.STEER_DRIVER_ALLOWANCE = 50 + self.STEER_DRIVER_MULTIPLIER = 2 + self.STEER_DRIVER_FACTOR = 1 + self.STEER_THRESHOLD = 150 + + if CP.carFingerprint in HDA2_CAR: + self.STEER_MAX = 270 + self.STEER_DRIVER_ALLOWANCE = 250 + self.STEER_DRIVER_MULTIPLIER = 2 + self.STEER_THRESHOLD = 250 + # To determine the limit for your car, find the maximum value that the stock LKAS will request. # If the max stock LKAS request is <384, add your car to this list. - if CP.carFingerprint in HDA2_CAR: - self.STEER_MAX = 150 elif CP.carFingerprint in (CAR.GENESIS_G80, CAR.GENESIS_G90, CAR.ELANTRA, CAR.HYUNDAI_GENESIS, CAR.ELANTRA_GT_I30, CAR.IONIQ, - CAR.IONIQ_EV_LTD, CAR.SANTA_FE_PHEV_2022, CAR.SONATA_LF, CAR.KIA_FORTE, CAR.KIA_NIRO_HEV, - CAR.KIA_OPTIMA_H, CAR.KIA_SORENTO, CAR.KIA_STINGER): + CAR.IONIQ_EV_LTD, CAR.SANTA_FE_PHEV_2022, CAR.SONATA_LF, CAR.KIA_FORTE, CAR.KIA_NIRO_HEV, + CAR.KIA_OPTIMA_H, CAR.KIA_SORENTO, CAR.KIA_STINGER): self.STEER_MAX = 255 else: self.STEER_MAX = 384 - self.STEER_DELTA_UP = 3 - self.STEER_DELTA_DOWN = 7 - self.STEER_DRIVER_ALLOWANCE = 50 - self.STEER_DRIVER_MULTIPLIER = 2 - self.STEER_DRIVER_FACTOR = 1 class CAR: @@ -1268,5 +1274,3 @@ DBC = { CAR.KIA_EV6: dbc_dict('kia_ev6', None), CAR.SONATA_HYBRID: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), } - -STEER_THRESHOLD = 150 diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index fb086fd13f..a2200926c0 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -1,7 +1,7 @@ legend: [LAT_ACCEL_FACTOR, MAX_LAT_ACCEL_MEASURED, FRICTION] ### angle control # Nissan appears to have torque -NISSAN X-TRAIL 2017: [.nan, 1.5, .nan] +NISSAN X-TRAIL 2017: [.nan, 1.5, .nan] NISSAN ALTIMA 2020: [.nan, 1.5, .nan] NISSAN LEAF 2018 Instrument Cluster: [.nan, 1.5, .nan] NISSAN LEAF 2018: [.nan, 1.5, .nan] @@ -20,7 +20,7 @@ FORD FOCUS 4TH GEN: [.nan, 1.5, .nan] COMMA BODY: [.nan, 1000, .nan] # Totally new car -KIA EV6 2022: [3.0, 2.5, 0.05] +KIA EV6 2022: [3.0, 2.5, 0.0] # Dashcam or fallback configured as ideal car mock: [10.0, 10, 0.0] From 1dffd48a2bab07512af71cfa73e572d602977340 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 23 Jun 2022 15:07:34 -0700 Subject: [PATCH 126/302] count_events improvements --- selfdrive/debug/count_events.py | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/selfdrive/debug/count_events.py b/selfdrive/debug/count_events.py index c3870e0f9e..93dd5bdc47 100755 --- a/selfdrive/debug/count_events.py +++ b/selfdrive/debug/count_events.py @@ -1,8 +1,11 @@ #!/usr/bin/env python3 import sys +import math +import datetime from collections import Counter from pprint import pprint from tqdm import tqdm +from typing import cast from cereal.services import service_list from tools.lib.route import Route @@ -17,6 +20,8 @@ if __name__ == "__main__": cams = [s for s in service_list if s.endswith('CameraState')] cnt_cameras = dict.fromkeys(cams, 0) + start_time = math.inf + end_time = -math.inf for q in tqdm(r.qlog_paths()): if q is None: continue @@ -31,6 +36,10 @@ if __name__ == "__main__": if not msg.valid: cnt_valid[msg.which()] += 1 + end_time = max(end_time, msg.logMonoTime) + start_time = min(start_time, msg.logMonoTime) + + duration = (end_time - start_time) / 1e9 print("Events") pprint(cnt_events) @@ -42,4 +51,9 @@ if __name__ == "__main__": print("\n") print("Cameras") for k, v in cnt_cameras.items(): - print(" ", k.ljust(20), v) + s = service_list[k] + expected_frames = int(s.frequency * duration / cast(float, s.decimation)) + print(" ", k.ljust(20), f"{v}, {v/expected_frames:.1%} of expected") + + print("\n") + print("Route duration", datetime.timedelta(seconds=duration)) From 3b495fcb0b004fd00d12bf059473d9d0b7f7c0b9 Mon Sep 17 00:00:00 2001 From: Ayushman Kumar <41910134+ayushmankumar7@users.noreply.github.com> Date: Fri, 24 Jun 2022 14:32:48 +0530 Subject: [PATCH 127/302] Navd added to README (#24953) (#24954) * Navd added to README * Update README.md Co-authored-by: Willem Melching --- README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/README.md b/README.md index c426b839d5..34b17625f9 100755 --- a/README.md +++ b/README.md @@ -121,6 +121,7 @@ Directory Structure ├── modeld # Driving and monitoring model runners ├── proclogd # Logs information from proc ├── sensord # IMU interface code + ├── navd # Turn-by-turn navigation ├── test # Unit tests, system tests, and a car simulator └── ui # The UI From 5cd8bef921c886e17ea6afc9fcdad44be72a998c Mon Sep 17 00:00:00 2001 From: Robbe Derks Date: Fri, 24 Jun 2022 12:37:30 +0200 Subject: [PATCH 128/302] use correct tty device for serial --- tools/serial/connect.sh | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tools/serial/connect.sh b/tools/serial/connect.sh index 037152019f..a073310b0a 100755 --- a/tools/serial/connect.sh +++ b/tools/serial/connect.sh @@ -1,8 +1,8 @@ #!/bin/bash while true; do - if ls /dev/ttyUSB* 2> /dev/null; then - sudo screen /dev/ttyUSB* 115200 + if ls /dev/serial/by-id/usb-FTDI_FT230X* 2> /dev/null; then + sudo screen /dev/serial/by-id/usb-FTDI_FT230X* 115200 fi sleep 0.005 done From b854e67e91105da7301936aab8fd55f94dd46fbb Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Fri, 24 Jun 2022 17:56:33 +0200 Subject: [PATCH 129/302] Laikad: minor refactor (#24956) extract code to get_est_pos func --- selfdrive/locationd/laikad.py | 26 +++++++++++++++----------- 1 file changed, 15 insertions(+), 11 deletions(-) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index f1997bceb0..ba665b7530 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -62,6 +62,16 @@ class Laikad: cls=CacheSerializer)) self.last_cached_t = t + def get_est_pos(self, t, processed_measurements): + if self.last_pos_fix_t is None or abs(self.last_pos_fix_t - t) >= 2: + min_measurements = 5 if any(p.constellation_id == ConstellationId.GLONASS for p in processed_measurements) else 4 + pos_fix, pos_fix_residual = calc_pos_fix_gauss_newton(processed_measurements, self.posfix_functions, min_measurements=min_measurements) + if len(pos_fix) > 0: + self.last_pos_fix = pos_fix[:3] + self.last_pos_residual = pos_fix_residual + self.last_pos_fix_t = t + return self.last_pos_fix + def process_ublox_msg(self, ublox_msg, ublox_mono_time: int, block=False): if ublox_msg.which == 'measurementReport': t = ublox_mono_time * 1e-9 @@ -73,17 +83,11 @@ class Laikad: new_meas = read_raw_ublox(report) processed_measurements = process_measurements(new_meas, self.astro_dog) - if self.last_pos_fix_t is None or abs(self.last_pos_fix_t - t) >= 2: - min_measurements = 5 if any(p.constellation_id == ConstellationId.GLONASS for p in processed_measurements) else 4 - pos_fix, pos_fix_residual = calc_pos_fix_gauss_newton(processed_measurements, self.posfix_functions, min_measurements=min_measurements) - if len(pos_fix) > 0: - self.last_pos_fix = pos_fix[:3] - self.last_pos_residual = pos_fix_residual - self.last_pos_fix_t = t + est_pos = self.get_est_pos(t, processed_measurements) - corrected_measurements = correct_measurements(processed_measurements, self.last_pos_fix, self.astro_dog) if self.last_pos_fix_t is not None else [] + corrected_measurements = correct_measurements(processed_measurements, est_pos, self.astro_dog) if len(est_pos) > 0 else [] - self.update_localizer(self.last_pos_fix, t, corrected_measurements) + self.update_localizer(est_pos, t, corrected_measurements) kf_valid = all(self.kf_valid(t)) ecef_pos = self.gnss_kf.x[GStates.ECEF_POS].tolist() ecef_vel = self.gnss_kf.x[GStates.ECEF_VELOCITY].tolist() @@ -116,7 +120,7 @@ class Laikad: valid = self.kf_valid(t) if not all(valid): if not valid[0]: - cloudlog.info("Init gnss kalman filter") + cloudlog.info("Kalman filter uninitialized") elif not valid[1]: cloudlog.error("Time gap of over 10s detected, gnss kalman reset") elif not valid[2]: @@ -133,7 +137,7 @@ class Laikad: # Ensure gnss filter is updated even with no new measurements self.gnss_kf.predict(t) - def kf_valid(self, t: float): + def kf_valid(self, t: float) -> List[bool]: filter_time = self.gnss_kf.filter.filter_time return [filter_time is not None, filter_time is not None and abs(t - filter_time) < MAX_TIME_GAP, From e26db5dc91e2dd6348cb1dd79ce1549b74f39309 Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Fri, 24 Jun 2022 15:32:01 -0400 Subject: [PATCH 130/302] VW MQB: Add FW for 2016 Volkswagen Passat (#24957) * VW MQB: Add FW for 2016 Passat B8 Passat B8 TDi 2.0 240HP DSG 7 Europe * mechanical sort Co-authored-by: Pierre Christen --- selfdrive/car/volkswagen/values.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 9b6f6a16c3..0148a138a2 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -438,6 +438,7 @@ FW_VERSIONS = { }, CAR.PASSAT_MK8: { (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8703N906026E \xf1\x892114', b'\xf1\x8704E906023AH\xf1\x893379', b'\xf1\x8704L906026ET\xf1\x891990', b'\xf1\x8704L906026GA\xf1\x892013', @@ -450,17 +451,20 @@ FW_VERSIONS = { b'\xf1\x870D9300014L \xf1\x895002', b'\xf1\x870D9300041A \xf1\x894801', b'\xf1\x870DD300045T \xf1\x891601', + b'\xf1\x870DL300011H \xf1\x895201', b'\xf1\x870GC300042H \xf1\x891404', ], (Ecu.srs, 0x715, None): [ b'\xf1\x873Q0959655AE\xf1\x890195\xf1\x82\r56140056130012416612124111', b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r58160058140013036914110311', + b'\xf1\x873Q0959655BA\xf1\x890195\xf1\x82\r56140056130012516612125111', b'\xf1\x873Q0959655BB\xf1\x890195\xf1\x82\r56140056130012026612120211', b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\0165915005914001344701311442900', b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e5915005914001305701311052900', b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\02315120011111200631145171716121691132111', ], (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00611A1', b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0060803', b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0080803', b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521B00606A1', From 062a8bcdbd78826cbb035c1dabc6ebd18a9367dd Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 24 Jun 2022 13:01:49 -0700 Subject: [PATCH 131/302] cleanup torque tuning config (#24951) --- selfdrive/car/hyundai/interface.py | 12 ++--- selfdrive/car/interfaces.py | 59 +++++++++++++-------- selfdrive/car/toyota/interface.py | 8 ++- selfdrive/car/toyota/tunes.py | 6 +-- selfdrive/controls/lib/latcontrol_torque.py | 10 ---- 5 files changed, 45 insertions(+), 50 deletions(-) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 7cfce55100..58a67f58ce 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -7,7 +7,6 @@ from selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR from selfdrive.car import STD_CARGO_KG, create_button_enable_events, create_button_event, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase from selfdrive.car.disable_ecu import disable_ecu -from selfdrive.controls.lib.latcontrol_torque import set_torque_tune ButtonType = car.CarState.ButtonEvent.Type EventName = car.CarEvent.EventName @@ -51,7 +50,6 @@ class CarInterface(CarInterfaceBase): ret.stopAccel = 0.0 ret.longitudinalActuatorDelayUpperBound = 1.0 # s - torque_params = CarInterfaceBase.get_torque_params(candidate) if candidate in (CAR.SANTA_FE, CAR.SANTA_FE_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022): ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3982. * CV.LB_TO_KG + STD_CARGO_KG @@ -66,7 +64,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.84 ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable tire_stiffness_factor = 0.65 - set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION']) + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.SONATA_LF: ret.lateralTuning.pid.kf = 0.00005 ret.mass = 4497. * CV.LB_TO_KG @@ -96,13 +94,13 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.72 ret.steerRatio = 12.9 tire_stiffness_factor = 0.65 - set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION']) + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.ELANTRA_HEV_2021: ret.mass = (3017. * CV.LB_TO_KG) + STD_CARGO_KG ret.wheelbase = 2.72 ret.steerRatio = 12.9 tire_stiffness_factor = 0.65 - set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION']) + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.HYUNDAI_GENESIS: ret.lateralTuning.pid.kf = 0.00005 ret.mass = 2060. + STD_CARGO_KG @@ -204,7 +202,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.80 ret.steerRatio = 13.75 tire_stiffness_factor = 0.5 - set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION']) + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.KIA_STINGER: ret.lateralTuning.pid.kf = 0.00005 ret.mass = 1825. + STD_CARGO_KG @@ -244,7 +242,7 @@ class CarInterface(CarInterfaceBase): ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.noOutput), get_safety_config(car.CarParams.SafetyModel.hyundaiHDA2)] tire_stiffness_factor = 0.65 - set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION']) + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) # Genesis elif candidate == CAR.GENESIS_G70: diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index ced2ce8e61..e0b38d9e20 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -20,11 +20,36 @@ EventName = car.CarEvent.EventName MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS ACCEL_MAX = 2.0 ACCEL_MIN = -3.5 + TORQUE_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/params.yaml') TORQUE_OVERRIDE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/override.yaml') TORQUE_SUBSTITUTE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/substitute.yaml') +def get_torque_params(candidate, default=float('NaN')): + with open(TORQUE_SUBSTITUTE_PATH) as f: + sub = yaml.load(f, Loader=yaml.FullLoader) + if candidate in sub: + candidate = sub[candidate] + + with open(TORQUE_PARAMS_PATH) as f: + params = yaml.load(f, Loader=yaml.FullLoader) + with open(TORQUE_OVERRIDE_PATH) as f: + override = yaml.load(f, Loader=yaml.FullLoader) + + # Ensure no overlap + if sum([candidate in x for x in [sub, params, override]]) > 1: + raise RuntimeError(f'{candidate} is defined twice in torque config') + + if candidate in override: + out = override[candidate] + elif candidate in params: + out = params[candidate] + else: + raise NotImplementedError(f"Did not find torque params for {candidate}") + return {key:out[i] for i, key in enumerate(params['legend'])} + + # generic car and radar interfaces class CarInterfaceBase(ABC): @@ -85,7 +110,7 @@ class CarInterfaceBase(ABC): ret.steerControlType = car.CarParams.SteerControlType.torque ret.minSteerSpeed = 0. ret.wheelSpeedFactor = 1.0 - ret.maxLateralAccel = CarInterfaceBase.get_torque_params(candidate)['MAX_LAT_ACCEL_MEASURED'] + ret.maxLateralAccel = get_torque_params(candidate)['MAX_LAT_ACCEL_MEASURED'] ret.pcmCruise = True # openpilot's state is tied to the PCM's cruise state on most cars ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this @@ -110,28 +135,16 @@ class CarInterfaceBase(ABC): return ret @staticmethod - def get_torque_params(candidate, default=float('NaN')): - with open(TORQUE_SUBSTITUTE_PATH) as f: - sub = yaml.load(f, Loader=yaml.FullLoader) - if candidate in sub: - candidate = sub[candidate] - - with open(TORQUE_PARAMS_PATH) as f: - params = yaml.load(f, Loader=yaml.FullLoader) - with open(TORQUE_OVERRIDE_PATH) as f: - override = yaml.load(f, Loader=yaml.FullLoader) - - # Ensure no overlap - if sum([candidate in x for x in [sub, params, override]]) > 1: - raise RuntimeError(f'{candidate} is defined twice in torque config') - - if candidate in override: - out = override[candidate] - elif candidate in params: - out = params[candidate] - else: - raise NotImplementedError(f"Did not find torque params for {candidate}") - return {key:out[i] for i, key in enumerate(params['legend'])} + def configure_torque_tune(candidate, tune, steering_angle_deadzone_deg=0.0): + params = get_torque_params(candidate) + + tune.init('torque') + tune.torque.useSteeringAngle = True + tune.torque.kp = 1.0 / params['LAT_ACCEL_FACTOR'] + tune.torque.kf = 1.0 / params['LAT_ACCEL_FACTOR'] + tune.torque.ki = 0.1 / params['LAT_ACCEL_FACTOR'] + tune.torque.friction = params['FRICTION'] + tune.torque.steeringAngleDeadzoneDeg = steering_angle_deadzone_deg @abstractmethod def _update(self, c: car.CarControl) -> car.CarState: diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 75f2ab3033..fdb923f693 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -2,7 +2,6 @@ from cereal import car from common.conversions import Conversions as CV from panda import Panda -from selfdrive.controls.lib.latcontrol_torque import set_torque_tune from selfdrive.car.toyota.tunes import LatTunes, LongTunes, set_long_tune, set_lat_tune from selfdrive.car.toyota.values import Ecu, CAR, ToyotaFlags, TSS2_CAR, RADAR_ACC_CAR, NO_DSU_CAR, MIN_ACC_SPEED, EPS_SCALE, EV_HYBRID_CAR, CarControllerParams from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config @@ -32,9 +31,8 @@ class CarInterface(CarInterfaceBase): ret.stoppingControl = False # Toyota starts braking more when it thinks you want to stop stop_and_go = False - torque_params = CarInterfaceBase.get_torque_params(candidate) steering_angle_deadzone_deg = 0.0 - set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION'], steering_angle_deadzone_deg) + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning, steering_angle_deadzone_deg) if candidate == CAR.PRIUS: stop_and_go = True @@ -46,7 +44,7 @@ class CarInterface(CarInterfaceBase): for fw in car_fw: if fw.ecu == "eps" and not fw.fwVersion == b'8965B47060\x00\x00\x00\x00\x00\x00': steering_angle_deadzone_deg = 1.0 - set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION'], steering_angle_deadzone_deg) + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning, steering_angle_deadzone_deg) elif candidate == CAR.PRIUS_V: stop_and_go = True @@ -54,7 +52,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 17.4 tire_stiffness_factor = 0.5533 ret.mass = 3340. * CV.LB_TO_KG + STD_CARGO_KG - set_torque_tune(ret.lateralTuning, torque_params['LAT_ACCEL_FACTOR'], torque_params['FRICTION'], steering_angle_deadzone_deg) + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning, steering_angle_deadzone_deg) elif candidate in (CAR.RAV4, CAR.RAV4H): stop_and_go = True if (candidate in CAR.RAV4H) else False diff --git a/selfdrive/car/toyota/tunes.py b/selfdrive/car/toyota/tunes.py index 3de6daae21..a8b8758d89 100644 --- a/selfdrive/car/toyota/tunes.py +++ b/selfdrive/car/toyota/tunes.py @@ -1,6 +1,5 @@ #!/usr/bin/env python3 from enum import Enum -from selfdrive.controls.lib.latcontrol_torque import set_torque_tune class LongTunes(Enum): PEDAL = 0 @@ -24,7 +23,6 @@ class LatTunes(Enum): PID_L = 13 PID_M = 14 PID_N = 15 - TORQUE = 16 ###### LONG ###### @@ -51,9 +49,7 @@ def set_long_tune(tune, name): ###### LAT ###### def set_lat_tune(tune, name, MAX_LAT_ACCEL=2.5, FRICTION=0.01, steering_angle_deadzone_deg=0.0, use_steering_angle=True): - if name == LatTunes.TORQUE: - set_torque_tune(tune, MAX_LAT_ACCEL, FRICTION, steering_angle_deadzone_deg) - elif 'PID' in str(name): + if 'PID' in str(name): tune.init('pid') tune.pid.kiBP = [0.0] tune.pid.kpBP = [0.0] diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index f72ffc4b88..014c3480b8 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -22,16 +22,6 @@ from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY FRICTION_THRESHOLD = 0.2 -def set_torque_tune(tune, MAX_LAT_ACCEL=2.5, FRICTION=0.01, steering_angle_deadzone_deg=0.0): - tune.init('torque') - tune.torque.useSteeringAngle = True - tune.torque.kp = 1.0 / MAX_LAT_ACCEL - tune.torque.kf = 1.0 / MAX_LAT_ACCEL - tune.torque.ki = 0.1 / MAX_LAT_ACCEL - tune.torque.friction = FRICTION - tune.torque.steeringAngleDeadzoneDeg = steering_angle_deadzone_deg - - class LatControlTorque(LatControl): def __init__(self, CP, CI): super().__init__(CP, CI) From 6721f0ef57fd5bda5045e80edac815adcfdef380 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Fri, 24 Jun 2022 14:29:46 -0700 Subject: [PATCH 132/302] fix carla test fake driverState (#24959) use driverstatev2 --- tools/sim/bridge.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index faf67c3ef5..17dc2c7a62 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -198,12 +198,12 @@ def gps_callback(gps, vehicle_state): def fake_driver_monitoring(exit_event: threading.Event): - pm = messaging.PubMaster(['driverState', 'driverMonitoringState']) + pm = messaging.PubMaster(['driverStateV2', 'driverMonitoringState']) while not exit_event.is_set(): # dmonitoringmodeld output - dat = messaging.new_message('driverState') - dat.driverState.faceProb = 1.0 - pm.send('driverState', dat) + dat = messaging.new_message('driverStateV2') + dat.driverStateV2.leftDriverData.faceProb = 1.0 + pm.send('driverStateV2', dat) # dmonitoringd output dat = messaging.new_message('driverMonitoringState') From 10fb2b9456b9d0d065b411ac64fd97831ee2fa8c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 24 Jun 2022 15:16:46 -0700 Subject: [PATCH 133/302] Speed up YAML parsing with CSafeLoader (#24958) Use CSafeLoader --- selfdrive/car/interfaces.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index e0b38d9e20..136337c5a4 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -26,16 +26,16 @@ TORQUE_OVERRIDE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/override TORQUE_SUBSTITUTE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/substitute.yaml') -def get_torque_params(candidate, default=float('NaN')): +def get_torque_params(candidate): with open(TORQUE_SUBSTITUTE_PATH) as f: - sub = yaml.load(f, Loader=yaml.FullLoader) + sub = yaml.load(f, Loader=yaml.CSafeLoader) if candidate in sub: candidate = sub[candidate] with open(TORQUE_PARAMS_PATH) as f: - params = yaml.load(f, Loader=yaml.FullLoader) + params = yaml.load(f, Loader=yaml.CSafeLoader) with open(TORQUE_OVERRIDE_PATH) as f: - override = yaml.load(f, Loader=yaml.FullLoader) + override = yaml.load(f, Loader=yaml.CSafeLoader) # Ensure no overlap if sum([candidate in x for x in [sub, params, override]]) > 1: @@ -47,7 +47,7 @@ def get_torque_params(candidate, default=float('NaN')): out = params[candidate] else: raise NotImplementedError(f"Did not find torque params for {candidate}") - return {key:out[i] for i, key in enumerate(params['legend'])} + return {key: out[i] for i, key in enumerate(params['legend'])} # generic car and radar interfaces From 379dc24ecad7f1bdc9c11fbb2416cc2d68b3a297 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 24 Jun 2022 16:49:56 -0700 Subject: [PATCH 134/302] can replay: get logs in parallel (#24960) * get can replay segs in parallel * total not needed --- tools/replay/can_replay.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/tools/replay/can_replay.py b/tools/replay/can_replay.py index b212abc431..0b8b4fe0a1 100755 --- a/tools/replay/can_replay.py +++ b/tools/replay/can_replay.py @@ -2,6 +2,7 @@ import os import time import threading +import multiprocessing from tqdm import tqdm os.environ['FILEREADER_CACHE'] = '1' @@ -9,7 +10,7 @@ os.environ['FILEREADER_CACHE'] = '1' from common.basedir import BASEDIR from common.realtime import config_realtime_process, Ratekeeper, DT_CTRL from selfdrive.boardd.boardd import can_capnp_to_can_list -from tools.lib.logreader import LogReader +from tools.plotjuggler.juggle import load_segment from panda import Panda try: @@ -94,11 +95,10 @@ if __name__ == "__main__": ROUTE = "77611a1fac303767/2020-03-24--09-50-38" REPLAY_SEGS = list(range(10, 16)) # route has 82 segments available CAN_MSGS = [] - for i in tqdm(REPLAY_SEGS): - log_url = f"https://commadataci.blob.core.windows.net/openpilotci/{ROUTE}/{i}/rlog.bz2" - lr = LogReader(log_url) - CAN_MSGS += [can_capnp_to_can_list(m.can) for m in lr if m.which() == 'can'] - + logs = [f"https://commadataci.blob.core.windows.net/openpilotci/{ROUTE}/{i}/rlog.bz2" for i in REPLAY_SEGS] + with multiprocessing.Pool(24) as pool: + for lr in tqdm(pool.map(load_segment, logs)): + CAN_MSGS += [can_capnp_to_can_list(m.can) for m in lr if m.which() == 'can'] # set both to cycle ignition IGN_ON = int(os.getenv("ON", "0")) From 72edc309327e8f6a1630e06d27cb21d16ba1e3ae Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Sat, 25 Jun 2022 03:07:29 -0700 Subject: [PATCH 135/302] Hyundai: remove bad esp fingerprint (#24952) Remove unknown "esp" fp --- selfdrive/car/hyundai/values.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 219e1619c0..645d2f523b 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1146,9 +1146,6 @@ FW_VERSIONS = { b'\xf1\000DNhe SCC F-CUP 1.00 1.02 99110-L5000 ', b'\xf1\x8799110L5000\xf1\000DNhe SCC F-CUP 1.00 1.02 99110-L5000 ', ], - (Ecu.esp, 0x7b0, None): [ - b'\xf1\x87\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81\x00\x00\x00\x00\x00\x00\x00\x00', - ], (Ecu.eps, 0x7d4, None): [ b'\xf1\x8756310-L5500\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5500 4DNHC102', b'\xf1\x8756310-L5450\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5450 4DNHC102', From 461f747247add7d4c50344042997427cdb2a90fa Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 27 Jun 2022 17:18:56 +0800 Subject: [PATCH 136/302] logger.cc: remove unused function append_property (#24966) remove append_property --- selfdrive/loggerd/logger.cc | 9 --------- 1 file changed, 9 deletions(-) diff --git a/selfdrive/loggerd/logger.cc b/selfdrive/loggerd/logger.cc index 5aed47e291..8038f1926c 100644 --- a/selfdrive/loggerd/logger.cc +++ b/selfdrive/loggerd/logger.cc @@ -19,15 +19,6 @@ #include "common/swaglog.h" #include "common/version.h" -// ***** logging helpers ***** - -void append_property(const char* key, const char* value, void *cookie) { - std::vector > *properties = - (std::vector > *)cookie; - - properties->push_back(std::make_pair(std::string(key), std::string(value))); -} - // ***** log metadata ***** kj::Array logger_build_init_data() { MessageBuilder msg; From 748bbac3444cc30e6dafc2f0bda60b46f3fc8d5a Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 27 Jun 2022 17:19:46 +0800 Subject: [PATCH 137/302] loggerd: remove rotate_lock (#24969) remove lock --- selfdrive/loggerd/loggerd.cc | 16 ++++++---------- 1 file changed, 6 insertions(+), 10 deletions(-) diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index 4086f4991e..a75ab2c92b 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -6,7 +6,6 @@ ExitHandler do_exit; struct LoggerdState { LoggerState logger = {}; char segment_path[4096]; - std::mutex rotate_lock; std::atomic rotate_segment; std::atomic last_camera_seen_tms; std::atomic ready_to_rotate; // count of encoders ready to rotate @@ -15,15 +14,12 @@ struct LoggerdState { }; void logger_rotate(LoggerdState *s) { - { - std::unique_lock lk(s->rotate_lock); - int segment = -1; - int err = logger_next(&s->logger, LOG_ROOT.c_str(), s->segment_path, sizeof(s->segment_path), &segment); - assert(err == 0); - s->rotate_segment = segment; - s->ready_to_rotate = 0; - s->last_rotate_tms = millis_since_boot(); - } + int segment = -1; + int err = logger_next(&s->logger, LOG_ROOT.c_str(), s->segment_path, sizeof(s->segment_path), &segment); + assert(err == 0); + s->rotate_segment = segment; + s->ready_to_rotate = 0; + s->last_rotate_tms = millis_since_boot(); LOGW((s->logger.part == 0) ? "logging to %s" : "rotated to %s", s->segment_path); } From 0aa9ae21d4068d1e8099ff4256d86a204ec31c1c Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 27 Jun 2022 17:20:13 +0800 Subject: [PATCH 138/302] FfmpegEncoder: free codec_ctx in encoder_close (#24967) free context --- selfdrive/loggerd/encoder/ffmpeg_encoder.cc | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/loggerd/encoder/ffmpeg_encoder.cc b/selfdrive/loggerd/encoder/ffmpeg_encoder.cc index 22587819a4..5f8d140e8b 100644 --- a/selfdrive/loggerd/encoder/ffmpeg_encoder.cc +++ b/selfdrive/loggerd/encoder/ffmpeg_encoder.cc @@ -68,7 +68,9 @@ void FfmpegEncoder::encoder_open(const char* path) { void FfmpegEncoder::encoder_close() { if (!is_open) return; + writer_close(); + avcodec_free_context(&codec_ctx); is_open = false; } From 684d4b75a1c2f349da1e00dae9a40c39e3bb3607 Mon Sep 17 00:00:00 2001 From: Robbe Derks Date: Mon, 27 Jun 2022 15:33:46 +0200 Subject: [PATCH 139/302] Log SOM power draw (#24975) * log SOM power draw * bump cereal Co-authored-by: Comma Device Co-authored-by: Willem Melching --- cereal | 2 +- selfdrive/thermald/thermald.py | 13 +++++++------ system/hardware/base.py | 4 ++++ system/hardware/pc/hardware.py | 3 +++ system/hardware/tici/hardware.py | 3 +++ 5 files changed, 18 insertions(+), 7 deletions(-) diff --git a/cereal b/cereal index c6acc0698a..3fef4f7861 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit c6acc0698a604e715e960250359b6bf97e4987e3 +Subproject commit 3fef4f7861e04193fdb11dbd5b0eaf6d2b102ee1 diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 6cf5c428a8..f20c649b4e 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -348,12 +348,13 @@ def thermald_thread(end_event, hw_queue): power_monitor.calculate(peripheralState, onroad_conditions["ignition"]) msg.deviceState.offroadPowerUsageUwh = power_monitor.get_power_used() msg.deviceState.carBatteryCapacityUwh = max(0, power_monitor.get_car_battery_capacity()) - current_power_draw = HARDWARE.get_current_power_draw() # pylint: disable=assignment-from-none - if current_power_draw is not None: - statlog.sample("power_draw", current_power_draw) - msg.deviceState.powerDrawW = current_power_draw - else: - msg.deviceState.powerDrawW = 0 + current_power_draw = HARDWARE.get_current_power_draw() + statlog.sample("power_draw", current_power_draw) + msg.deviceState.powerDrawW = current_power_draw + + som_power_draw = HARDWARE.get_som_power_draw() + statlog.sample("som_power_draw", som_power_draw) + msg.deviceState.somPowerDrawW = som_power_draw # Check if we need to disable charging (handled by boardd) msg.deviceState.chargingDisabled = power_monitor.should_disable_charging(onroad_conditions["ignition"], in_car, off_ts) diff --git a/system/hardware/base.py b/system/hardware/base.py index 8684386f62..b052a48c5b 100644 --- a/system/hardware/base.py +++ b/system/hardware/base.py @@ -86,6 +86,10 @@ class HardwareBase(ABC): def get_current_power_draw(self): pass + @abstractmethod + def get_som_power_draw(self): + pass + @abstractmethod def shutdown(self): pass diff --git a/system/hardware/pc/hardware.py b/system/hardware/pc/hardware.py index b2c4a4343b..60d14e4a6b 100644 --- a/system/hardware/pc/hardware.py +++ b/system/hardware/pc/hardware.py @@ -55,6 +55,9 @@ class Pc(HardwareBase): def get_current_power_draw(self): return 0 + + def get_som_power_draw(self): + return 0 def shutdown(self): print("SHUTDOWN!") diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py index a69d3eb743..66cb98c606 100644 --- a/system/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -362,6 +362,9 @@ class Tici(HardwareBase): def get_current_power_draw(self): return (self.read_param_file("/sys/class/hwmon/hwmon1/power1_input", int) / 1e6) + def get_som_power_draw(self): + return (self.read_param_file("/sys/class/power_supply/bms/voltage_now", int) * self.read_param_file("/sys/class/power_supply/bms/current_now", int) / 1e12) + def shutdown(self): # Note that for this to work and have the device stay powered off, the panda needs to be in UsbPowerMode::CLIENT! os.system("sudo poweroff") From de0c12e5af0e550c194510a19253dd9100b1a9f7 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 27 Jun 2022 15:34:36 +0200 Subject: [PATCH 140/302] calibrationd: start faster by not waiting for carParams (#24976) * calibrationd: start faster by not waiting for carParams * fix process replay * update ref --- selfdrive/locationd/calibrationd.py | 10 ++++++---- selfdrive/test/process_replay/process_replay.py | 3 ++- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 9 insertions(+), 6 deletions(-) diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index e092c939ae..81bcc6ce1c 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -12,7 +12,7 @@ import capnp import numpy as np from typing import List, NoReturn, Optional -from cereal import car, log +from cereal import log import cereal.messaging as messaging from common.conversions import Conversions as CV from common.params import Params, put_nonblocking @@ -62,7 +62,7 @@ class Calibrator: def __init__(self, param_put: bool = False): self.param_put = param_put - self.CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) + self.not_car = False # Read saved calibration params = Params() @@ -192,7 +192,7 @@ class Calibrator: liveCalibration.rpyCalib = smooth_rpy.tolist() liveCalibration.rpyCalibSpread = self.calib_spread.tolist() - if self.CP.notCar: + if self.not_car: extrinsic_matrix = get_view_frame_from_road_frame(0, 0, 0, model_height) liveCalibration.validBlocks = INPUTS_NEEDED liveCalibration.calStatus = Calibration.CALIBRATED @@ -212,7 +212,7 @@ def calibrationd_thread(sm: Optional[messaging.SubMaster] = None, pm: Optional[m set_realtime_priority(1) if sm is None: - sm = messaging.SubMaster(['cameraOdometry', 'carState'], poll=['cameraOdometry']) + sm = messaging.SubMaster(['cameraOdometry', 'carState', 'carParams'], poll=['cameraOdometry']) if pm is None: pm = messaging.PubMaster(['liveCalibration']) @@ -223,6 +223,8 @@ def calibrationd_thread(sm: Optional[messaging.SubMaster] = None, pm: Optional[m timeout = 0 if sm.frame == -1 else 100 sm.update(timeout) + calibrator.not_car = sm['carParams'].notCar + if sm.updated['cameraOdometry']: calibrator.handle_v_ego(sm['carState'].vEgo) new_rpy = calibrator.handle_cam_odom(sm['cameraOdometry'].trans, diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 62c5eb4826..228f07c4c2 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -282,7 +282,8 @@ CONFIGS = [ proc_name="calibrationd", pub_sub={ "carState": ["liveCalibration"], - "cameraOdometry": [] + "cameraOdometry": [], + "carParams": [], }, ignore=["logMonoTime", "valid"], init_callback=get_car_params, diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 662f8cc5b8..292c41b978 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -41161c8d151b0c2017214cad0aad3156533ab868 +b55de9fdb2416e63ab554c95233a78219d8d3db9 \ No newline at end of file From 240c44e50c4dd44c2237f4f37d716fd898160917 Mon Sep 17 00:00:00 2001 From: Maxime Desroches Date: Mon, 27 Jun 2022 06:36:27 -0700 Subject: [PATCH 141/302] snapshot: fix rgb overflow (#24963) clamp rgb --- system/camerad/snapshot/snapshot.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/camerad/snapshot/snapshot.py b/system/camerad/snapshot/snapshot.py index 9a81937eec..946c220a77 100755 --- a/system/camerad/snapshot/snapshot.py +++ b/system/camerad/snapshot/snapshot.py @@ -39,7 +39,7 @@ def yuv_to_rgb(y, u, v): [0.00000, -0.39465, 2.03211], [1.13983, -0.58060, 0.00000], ]) - rgb = np.dot(yuv, m) + rgb = np.dot(yuv, m).clip(0, 255) return rgb.astype(np.uint8) From 915b4928ff044302bba0e8bdf15f154646f528e6 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 27 Jun 2022 16:03:26 +0200 Subject: [PATCH 142/302] ui: use current calibration to center vanishing point (#24955) * compute x and y offsets using calibration * fix default calibration * clamp to max values * only use when valid * not while calibrating * less diff * cleanup zoom --- selfdrive/ui/qt/onroad.cc | 21 +++++----- selfdrive/ui/qt/onroad.h | 2 +- selfdrive/ui/qt/widgets/cameraview.cc | 55 +++++++++++++++++---------- selfdrive/ui/qt/widgets/cameraview.h | 12 +++++- selfdrive/ui/ui.cc | 1 + selfdrive/ui/ui.h | 8 ++-- 6 files changed, 62 insertions(+), 37 deletions(-) diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 2759416236..ecd6d61471 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -208,6 +208,12 @@ void NvgWindow::updateState(const UIState &s) { setProperty("engageable", cs.getEngageable() || cs.getEnabled()); setProperty("dmActive", sm["driverMonitoringState"].getDriverMonitoringState().getIsActiveMode()); } + + if (s.scene.calibration_valid) { + CameraViewWidget::updateCalibration(s.scene.view_from_calib); + } else { + CameraViewWidget::updateCalibration(DEFAULT_CALIBRATION); + } } void NvgWindow::drawHud(QPainter &p) { @@ -399,23 +405,20 @@ void NvgWindow::initializeGL() { setBackgroundColor(bg_colors[STATUS_DISENGAGED]); } -void NvgWindow::updateFrameMat(int w, int h) { - CameraViewWidget::updateFrameMat(w, h); - +void NvgWindow::updateFrameMat() { + CameraViewWidget::updateFrameMat(); UIState *s = uiState(); + int w = width(), h = height(); + s->fb_w = w; s->fb_h = h; - auto intrinsic_matrix = s->wide_camera ? ecam_intrinsic_matrix : fcam_intrinsic_matrix; - float zoom = ZOOM / intrinsic_matrix.v[0]; - if (s->wide_camera) { - zoom *= 0.5; - } + // Apply transformation such that video pixel coordinates match video // 1) Put (0, 0) in the middle of the video // 2) Apply same scaling as video // 3) Put (0, 0) in top left corner of video s->car_space_transform.reset(); - s->car_space_transform.translate(w / 2, h / 2 + y_offset) + s->car_space_transform.translate(w / 2 - x_offset, h / 2 - y_offset) .scale(zoom, zoom) .translate(-intrinsic_matrix.v[2], -intrinsic_matrix.v[5]); } diff --git a/selfdrive/ui/qt/onroad.h b/selfdrive/ui/qt/onroad.h index 4cd88fc9e3..dc1e69da2a 100644 --- a/selfdrive/ui/qt/onroad.h +++ b/selfdrive/ui/qt/onroad.h @@ -70,7 +70,7 @@ protected: void paintGL() override; void initializeGL() override; void showEvent(QShowEvent *event) override; - void updateFrameMat(int w, int h) override; + void updateFrameMat() override; void drawLaneLines(QPainter &painter, const UIState *s); void drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV3::Reader &lead_data, const QPointF &vd); void drawHud(QPainter &p); diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 8666eb1d4e..a80672f2c3 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -6,6 +6,8 @@ #include #endif +#include + #include #include @@ -59,13 +61,6 @@ const char frame_fragment_shader[] = "}\n"; #endif -const mat4 device_transform = {{ - 1.0, 0.0, 0.0, 0.0, - 0.0, 1.0, 0.0, 0.0, - 0.0, 0.0, 1.0, 0.0, - 0.0, 0.0, 0.0, 1.0, -}}; - mat4 get_driver_view_transform(int screen_width, int screen_height, int stream_width, int stream_height) { const float driver_view_ratio = 2.0; const float yscale = stream_height * driver_view_ratio / stream_width; @@ -185,35 +180,55 @@ void CameraViewWidget::hideEvent(QHideEvent *event) { } } -void CameraViewWidget::updateFrameMat(int w, int h) { +void CameraViewWidget::updateFrameMat() { + int w = width(), h = height(); + if (zoomed_view) { if (stream_type == VISION_STREAM_DRIVER) { - frame_mat = matmul(device_transform, get_driver_view_transform(w, h, stream_width, stream_height)); + frame_mat = get_driver_view_transform(w, h, stream_width, stream_height); } else { - auto intrinsic_matrix = stream_type == VISION_STREAM_WIDE_ROAD ? ecam_intrinsic_matrix : fcam_intrinsic_matrix; - float zoom = ZOOM / intrinsic_matrix.v[0]; - if (stream_type == VISION_STREAM_WIDE_ROAD) { - zoom *= 0.5; - } + intrinsic_matrix = (stream_type == VISION_STREAM_WIDE_ROAD) ? ecam_intrinsic_matrix : fcam_intrinsic_matrix; + zoom = (stream_type == VISION_STREAM_WIDE_ROAD) ? 2.5 : 1.1; + + // Project point at "infinity" to compute x and y offsets + // to ensure this ends up in the middle of the screen + // TODO: use proper perspective transform? + const vec3 inf = {{1000., 0., 0.}}; + const vec3 Ep = matvecmul3(calibration, inf); + const vec3 Kep = matvecmul3(intrinsic_matrix, Ep); + + float x_offset_ = (Kep.v[0] / Kep.v[2] - intrinsic_matrix.v[2]) * zoom; + float y_offset_ = (Kep.v[1] / Kep.v[2] - intrinsic_matrix.v[5]) * zoom; + + float max_x_offset = intrinsic_matrix.v[2] * zoom - w / 2 - 5; + float max_y_offset = intrinsic_matrix.v[5] * zoom - h / 2 - 5; + + x_offset = std::clamp(x_offset_, -max_x_offset, max_x_offset); + y_offset = std::clamp(y_offset_, -max_y_offset, max_y_offset); + float zx = zoom * 2 * intrinsic_matrix.v[2] / width(); float zy = zoom * 2 * intrinsic_matrix.v[5] / height(); - const mat4 frame_transform = {{ - zx, 0.0, 0.0, 0.0, - 0.0, zy, 0.0, -y_offset / height() * 2, + zx, 0.0, 0.0, -x_offset / width() * 2, + 0.0, zy, 0.0, y_offset / height() * 2, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, }}; - frame_mat = matmul(device_transform, frame_transform); + frame_mat = frame_transform; } } else if (stream_width > 0 && stream_height > 0) { // fit frame to widget size float widget_aspect_ratio = (float)width() / height(); float frame_aspect_ratio = (float)stream_width / stream_height; - frame_mat = matmul(device_transform, get_fit_view_transform(widget_aspect_ratio, frame_aspect_ratio)); + frame_mat = get_fit_view_transform(widget_aspect_ratio, frame_aspect_ratio); } } +void CameraViewWidget::updateCalibration(const mat3 &calib) { + calibration = calib; + updateFrameMat(); +} + void CameraViewWidget::paintGL() { glClearColor(bg.redF(), bg.greenF(), bg.blueF(), bg.alphaF()); glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); @@ -311,7 +326,7 @@ void CameraViewWidget::vipcConnected(VisionIpcClient *vipc_client) { assert(glGetError() == GL_NO_ERROR); #endif - updateFrameMat(width(), height()); + updateFrameMat(); } void CameraViewWidget::vipcFrameReceived(VisionBuf *buf, uint32_t frame_id) { diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index 42e9043602..cc11ec2c27 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -42,11 +42,12 @@ signals: protected: void paintGL() override; void initializeGL() override; - void resizeGL(int w, int h) override { updateFrameMat(w, h); } + void resizeGL(int w, int h) override { updateFrameMat(); } void showEvent(QShowEvent *event) override; void hideEvent(QHideEvent *event) override; void mouseReleaseEvent(QMouseEvent *event) override { emit clicked(); } - virtual void updateFrameMat(int w, int h); + virtual void updateFrameMat(); + void updateCalibration(const mat3 &calib); void vipcThread(); bool zoomed_view; @@ -68,6 +69,13 @@ protected: std::atomic stream_type; QThread *vipc_thread = nullptr; + // Calibration + float x_offset = 0; + float y_offset = 0; + float zoom = 1.0; + mat3 calibration = DEFAULT_CALIBRATION; + mat3 intrinsic_matrix = fcam_intrinsic_matrix; + std::deque> frames; uint32_t draw_frame_id = 0; diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 4d1e1ab746..c8fc645cf2 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -140,6 +140,7 @@ static void update_state(UIState *s) { scene.view_from_calib.v[i*3 + j] = view_from_calib(i,j); } } + scene.calibration_valid = sm["liveCalibration"].getLiveCalibration().getCalStatus() == 1; } if (s->worldObjectsVisible()) { if (sm.updated("modelV2")) { diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index cbf3921e4e..7364b81a40 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -22,10 +22,7 @@ const int footer_h = 280; const int UI_FREQ = 20; // Hz typedef cereal::CarControl::HUDControl::AudibleAlert AudibleAlert; -// TODO: this is also hardcoded in common/transformations/camera.py -// TODO: choose based on frame input size -const float y_offset = 150.0; -const float ZOOM = 2912.8; +const mat3 DEFAULT_CALIBRATION = {{ 0.0, 1.0, 0.0, 0.0, 0.0, 1.0, 1.0, 0.0, 0.0 }}; struct Alert { QString text1; @@ -93,7 +90,8 @@ typedef struct { } line_vertices_data; typedef struct UIScene { - mat3 view_from_calib; + bool calibration_valid = false; + mat3 view_from_calib = DEFAULT_CALIBRATION; cereal::PandaState::PandaType pandaType; // modelV2 From b95e68778271cccf558452686e022ae57f25a701 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 27 Jun 2022 21:31:54 +0200 Subject: [PATCH 143/302] split locationd and liblocationd tests (#24977) * laikad: use cython version of gnss kf * fix import error * test liblocationd separate * Revert "laikad: use cython version of gnss kf" This reverts commit bdd769b9554e7e45e976dabd6595403943e864bb. --- .github/workflows/selfdrive_tests.yaml | 3 +- .../locationd/test/_test_locationd_lib.py | 106 ++++++++++++++++++ selfdrive/locationd/test/test_locationd.py | 94 ---------------- 3 files changed, 108 insertions(+), 95 deletions(-) create mode 100755 selfdrive/locationd/test/_test_locationd_lib.py diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index fedeaa734b..52dd012baa 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -299,6 +299,7 @@ jobs: $UNIT_TEST selfdrive/loggerd && \ $UNIT_TEST selfdrive/car && \ $UNIT_TEST selfdrive/locationd && \ + selfdrive/locationd/test/_test_locationd_lib.py && \ $UNIT_TEST selfdrive/athena && \ $UNIT_TEST selfdrive/thermald && \ $UNIT_TEST selfdrive/hardware/tici && \ @@ -364,7 +365,7 @@ jobs: CI=1 AZURE_TOKEN='$AZURE_TOKEN' python selfdrive/test/process_replay/test_processes.py -j$(nproc) --upload-only" - name: "Upload coverage to Codecov" uses: codecov/codecov-action@v2 - + model_replay_onnx: name: model replay onnx runs-on: ubuntu-20.04 diff --git a/selfdrive/locationd/test/_test_locationd_lib.py b/selfdrive/locationd/test/_test_locationd_lib.py new file mode 100755 index 0000000000..8a0ed3ef05 --- /dev/null +++ b/selfdrive/locationd/test/_test_locationd_lib.py @@ -0,0 +1,106 @@ +#!/usr/bin/env python3 +"""This test can't be run together with other locationd tests. +cffi.dlopen breaks the list of registered filters.""" +import os +import random +import unittest + +from cffi import FFI + +import cereal.messaging as messaging +from cereal import log + +SENSOR_DECIMATION = 1 +VISION_DECIMATION = 1 + +LIBLOCATIOND_PATH = os.path.abspath(os.path.join(os.path.dirname(__file__), '../liblocationd.so')) + + +class TestLocationdLib(unittest.TestCase): + def setUp(self): + header = '''typedef ...* Localizer_t; +Localizer_t localizer_init(); +void localizer_get_message_bytes(Localizer_t localizer, bool inputsOK, bool sensorsOK, bool gpsOK, bool msgValid, char *buff, size_t buff_size); +void localizer_handle_msg_bytes(Localizer_t localizer, const char *data, size_t size);''' + + self.ffi = FFI() + self.ffi.cdef(header) + self.lib = self.ffi.dlopen(LIBLOCATIOND_PATH) + + self.localizer = self.lib.localizer_init() + + self.buff_size = 2048 + self.msg_buff = self.ffi.new(f'char[{self.buff_size}]') + + def localizer_handle_msg(self, msg_builder): + bytstr = msg_builder.to_bytes() + self.lib.localizer_handle_msg_bytes(self.localizer, self.ffi.from_buffer(bytstr), len(bytstr)) + + def localizer_get_msg(self, t=0, inputsOK=True, sensorsOK=True, gpsOK=True, msgValid=True): + self.lib.localizer_get_message_bytes(self.localizer, inputsOK, sensorsOK, gpsOK, msgValid, self.ffi.addressof(self.msg_buff, 0), self.buff_size) + return log.Event.from_bytes(self.ffi.buffer(self.msg_buff), nesting_limit=self.buff_size // 8) + + def test_liblocalizer(self): + msg = messaging.new_message('liveCalibration') + msg.liveCalibration.validBlocks = random.randint(1, 10) + msg.liveCalibration.rpyCalib = [random.random() / 10 for _ in range(3)] + + self.localizer_handle_msg(msg) + liveloc = self.localizer_get_msg() + self.assertTrue(liveloc is not None) + + @unittest.skip("temporarily disabled due to false positives") + def test_device_fell(self): + msg = messaging.new_message('sensorEvents', 1) + msg.sensorEvents[0].sensor = 1 + msg.sensorEvents[0].timestamp = msg.logMonoTime + msg.sensorEvents[0].type = 1 + msg.sensorEvents[0].init('acceleration') + msg.sensorEvents[0].acceleration.v = [10.0, 0.0, 0.0] # zero with gravity + self.localizer_handle_msg(msg) + + ret = self.localizer_get_msg() + self.assertTrue(ret.liveLocationKalman.deviceStable) + + msg = messaging.new_message('sensorEvents', 1) + msg.sensorEvents[0].sensor = 1 + msg.sensorEvents[0].timestamp = msg.logMonoTime + msg.sensorEvents[0].type = 1 + msg.sensorEvents[0].init('acceleration') + msg.sensorEvents[0].acceleration.v = [50.1, 0.0, 0.0] # more than 40 m/s**2 + self.localizer_handle_msg(msg) + + ret = self.localizer_get_msg() + self.assertFalse(ret.liveLocationKalman.deviceStable) + + def test_posenet_spike(self): + for _ in range(SENSOR_DECIMATION): + msg = messaging.new_message('carState') + msg.carState.vEgo = 6.0 # more than 5 m/s + self.localizer_handle_msg(msg) + + ret = self.localizer_get_msg() + self.assertTrue(ret.liveLocationKalman.posenetOK) + + for _ in range(20 * VISION_DECIMATION): # size of hist_old + msg = messaging.new_message('cameraOdometry') + msg.cameraOdometry.rot = [0.0, 0.0, 0.0] + msg.cameraOdometry.rotStd = [0.1, 0.1, 0.1] + msg.cameraOdometry.trans = [0.0, 0.0, 0.0] + msg.cameraOdometry.transStd = [2.0, 0.1, 0.1] + self.localizer_handle_msg(msg) + + for _ in range(20 * VISION_DECIMATION): # size of hist_new + msg = messaging.new_message('cameraOdometry') + msg.cameraOdometry.rot = [0.0, 0.0, 0.0] + msg.cameraOdometry.rotStd = [1.0, 1.0, 1.0] + msg.cameraOdometry.trans = [0.0, 0.0, 0.0] + msg.cameraOdometry.transStd = [10.1, 0.1, 0.1] # more than 4 times larger + self.localizer_handle_msg(msg) + + ret = self.localizer_get_msg() + self.assertFalse(ret.liveLocationKalman.posenetOK) + +if __name__ == "__main__": + unittest.main() + diff --git a/selfdrive/locationd/test/test_locationd.py b/selfdrive/locationd/test/test_locationd.py index 7f5d752100..29036b8387 100755 --- a/selfdrive/locationd/test/test_locationd.py +++ b/selfdrive/locationd/test/test_locationd.py @@ -1,110 +1,16 @@ #!/usr/bin/env python3 -import os import json import random import unittest import time import capnp -from cffi import FFI -from cereal import log import cereal.messaging as messaging from cereal.services import service_list from common.params import Params from selfdrive.manager.process_config import managed_processes -SENSOR_DECIMATION = 1 -VISION_DECIMATION = 1 - -LIBLOCATIOND_PATH = os.path.abspath(os.path.join(os.path.dirname(__file__), '../liblocationd.so')) - - -class TestLocationdLib(unittest.TestCase): - def setUp(self): - header = '''typedef ...* Localizer_t; -Localizer_t localizer_init(); -void localizer_get_message_bytes(Localizer_t localizer, bool inputsOK, bool sensorsOK, bool gpsOK, bool msgValid, char *buff, size_t buff_size); -void localizer_handle_msg_bytes(Localizer_t localizer, const char *data, size_t size);''' - - self.ffi = FFI() - self.ffi.cdef(header) - self.lib = self.ffi.dlopen(LIBLOCATIOND_PATH) - - self.localizer = self.lib.localizer_init() - - self.buff_size = 2048 - self.msg_buff = self.ffi.new(f'char[{self.buff_size}]') - - def localizer_handle_msg(self, msg_builder): - bytstr = msg_builder.to_bytes() - self.lib.localizer_handle_msg_bytes(self.localizer, self.ffi.from_buffer(bytstr), len(bytstr)) - - def localizer_get_msg(self, t=0, inputsOK=True, sensorsOK=True, gpsOK=True, msgValid=True): - self.lib.localizer_get_message_bytes(self.localizer, inputsOK, sensorsOK, gpsOK, msgValid, self.ffi.addressof(self.msg_buff, 0), self.buff_size) - return log.Event.from_bytes(self.ffi.buffer(self.msg_buff), nesting_limit=self.buff_size // 8) - - def test_liblocalizer(self): - msg = messaging.new_message('liveCalibration') - msg.liveCalibration.validBlocks = random.randint(1, 10) - msg.liveCalibration.rpyCalib = [random.random() / 10 for _ in range(3)] - - self.localizer_handle_msg(msg) - liveloc = self.localizer_get_msg() - self.assertTrue(liveloc is not None) - - @unittest.skip("temporarily disabled due to false positives") - def test_device_fell(self): - msg = messaging.new_message('sensorEvents', 1) - msg.sensorEvents[0].sensor = 1 - msg.sensorEvents[0].timestamp = msg.logMonoTime - msg.sensorEvents[0].type = 1 - msg.sensorEvents[0].init('acceleration') - msg.sensorEvents[0].acceleration.v = [10.0, 0.0, 0.0] # zero with gravity - self.localizer_handle_msg(msg) - - ret = self.localizer_get_msg() - self.assertTrue(ret.liveLocationKalman.deviceStable) - - msg = messaging.new_message('sensorEvents', 1) - msg.sensorEvents[0].sensor = 1 - msg.sensorEvents[0].timestamp = msg.logMonoTime - msg.sensorEvents[0].type = 1 - msg.sensorEvents[0].init('acceleration') - msg.sensorEvents[0].acceleration.v = [50.1, 0.0, 0.0] # more than 40 m/s**2 - self.localizer_handle_msg(msg) - - ret = self.localizer_get_msg() - self.assertFalse(ret.liveLocationKalman.deviceStable) - - def test_posenet_spike(self): - for _ in range(SENSOR_DECIMATION): - msg = messaging.new_message('carState') - msg.carState.vEgo = 6.0 # more than 5 m/s - self.localizer_handle_msg(msg) - - ret = self.localizer_get_msg() - self.assertTrue(ret.liveLocationKalman.posenetOK) - - for _ in range(20 * VISION_DECIMATION): # size of hist_old - msg = messaging.new_message('cameraOdometry') - msg.cameraOdometry.rot = [0.0, 0.0, 0.0] - msg.cameraOdometry.rotStd = [0.1, 0.1, 0.1] - msg.cameraOdometry.trans = [0.0, 0.0, 0.0] - msg.cameraOdometry.transStd = [2.0, 0.1, 0.1] - self.localizer_handle_msg(msg) - - for _ in range(20 * VISION_DECIMATION): # size of hist_new - msg = messaging.new_message('cameraOdometry') - msg.cameraOdometry.rot = [0.0, 0.0, 0.0] - msg.cameraOdometry.rotStd = [1.0, 1.0, 1.0] - msg.cameraOdometry.trans = [0.0, 0.0, 0.0] - msg.cameraOdometry.transStd = [10.1, 0.1, 0.1] # more than 4 times larger - self.localizer_handle_msg(msg) - - ret = self.localizer_get_msg() - self.assertFalse(ret.liveLocationKalman.posenetOK) - class TestLocationdProc(unittest.TestCase): MAX_WAITS = 1000 From aaca31b73eb109a053e94b2153eb3068a0976c95 Mon Sep 17 00:00:00 2001 From: "Shafiqur R. Khan" <37314609+shfqrkhn@users.noreply.github.com> Date: Mon, 27 Jun 2022 14:10:57 -0600 Subject: [PATCH 144/302] 2022 RAV4 XLE engine FW (#24973) Update values.py Added ecu.engine address for 2022 RAV4 XLE (ICE) bought in Edmonton, Canada --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 32f66b6fa0..76f84302ce 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1296,6 +1296,7 @@ FW_VERSIONS = { b'\x028965B0R01500\x00\x00\x00\x008965B0R02500\x00\x00\x00\x00', ], (Ecu.engine, 0x700, None): [ + b'\x01896634AA0000\x00\x00\x00\x00', b'\x01896634AA1000\x00\x00\x00\x00', b'\x01896634A88000\x00\x00\x00\x00', ], From b3226d505b9260ec8565acfda7138601a76039a6 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Mon, 27 Jun 2022 15:25:47 -0700 Subject: [PATCH 145/302] Torque control: higher low speed gains and better steering angle deadzone logic (#24980) * Try no friction and no deadzone * Learn fromd ata * update refs --- selfdrive/controls/lib/latcontrol_torque.py | 6 +++--- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index 014c3480b8..46caa41a90 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -56,15 +56,15 @@ class LatControlTorque(LatControl): lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2 - low_speed_factor = interp(CS.vEgo, [0, 15], [500, 0]) + low_speed_factor = interp(CS.vEgo, [0, 10, 20], [500, 500, 200]) setpoint = desired_lateral_accel + low_speed_factor * desired_curvature measurement = actual_lateral_accel + low_speed_factor * actual_curvature - error = apply_deadzone(setpoint - measurement, lateral_accel_deadzone) + error = setpoint - measurement pid_log.error = error ff = desired_lateral_accel - params.roll * ACCELERATION_DUE_TO_GRAVITY # convert friction into lateral accel units for feedforward - friction_compensation = interp(error, [-FRICTION_THRESHOLD, FRICTION_THRESHOLD], [-self.friction, self.friction]) + friction_compensation = interp(apply_deadzone(error, lateral_accel_deadzone), [-FRICTION_THRESHOLD, FRICTION_THRESHOLD], [-self.friction, self.friction]) ff += friction_compensation / self.kf freeze_integrator = CS.steeringRateLimited or CS.steeringPressed or CS.vEgo < 5 output_torque = self.pid.update(error, diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 292c41b978..1402284b96 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -b55de9fdb2416e63ab554c95233a78219d8d3db9 \ No newline at end of file +a16ca1082cd493f6cea5252eaaba9f8c6574334a From 3a2bcc092c74925edb161959cdcc66073a9cd8f3 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 28 Jun 2022 01:08:11 -0700 Subject: [PATCH 146/302] onroad UI: fix onroad double tap (#24982) * The default implementation calls mousePressEvent(). * no sidebar when entering body * wrong one * you can't double tap with body anyway (fixes inconsistencies with prime vs not prime) * hide sidebar --- selfdrive/ui/qt/home.cc | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/ui/qt/home.cc b/selfdrive/ui/qt/home.cc index e522d6160d..aec9bffbc0 100644 --- a/selfdrive/ui/qt/home.cc +++ b/selfdrive/ui/qt/home.cc @@ -85,6 +85,7 @@ void HomeWindow::mousePressEvent(QMouseEvent* e) { } void HomeWindow::mouseDoubleClickEvent(QMouseEvent* e) { + HomeWindow::mousePressEvent(e); const SubMaster &sm = *(uiState()->sm); if (sm["carParams"].getCarParams().getNotCar()) { if (onroad->isVisible()) { @@ -92,6 +93,7 @@ void HomeWindow::mouseDoubleClickEvent(QMouseEvent* e) { } else if (body->isVisible()) { slayout->setCurrentWidget(onroad); } + showSidebar(false); } } From d693285b02a0f005ce1d29793c8672ab2fe24a24 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 28 Jun 2022 01:09:52 -0700 Subject: [PATCH 147/302] Power Monitoring test: fix exceptions (#24981) * fix missing POWER_DRAW * think should be 0 --- selfdrive/thermald/tests/test_power_monitoring.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/thermald/tests/test_power_monitoring.py b/selfdrive/thermald/tests/test_power_monitoring.py index c0524add69..efe607155a 100755 --- a/selfdrive/thermald/tests/test_power_monitoring.py +++ b/selfdrive/thermald/tests/test_power_monitoring.py @@ -119,7 +119,8 @@ class TestPowerMonitoring(unittest.TestCase): @parameterized.expand(ALL_PANDA_TYPES) def test_max_time_offroad(self, hw_type): MOCKED_MAX_OFFROAD_TIME = 3600 - with pm_patch("MAX_TIME_OFFROAD_S", MOCKED_MAX_OFFROAD_TIME, constant=True), pm_patch("HARDWARE.get_current_power_draw", None): + POWER_DRAW = 0 # To stop shutting down for other reasons + with pm_patch("MAX_TIME_OFFROAD_S", MOCKED_MAX_OFFROAD_TIME, constant=True), pm_patch("HARDWARE.get_current_power_draw", POWER_DRAW): pm = PowerMonitoring() pm.car_battery_capacity_uWh = CAR_BATTERY_CAPACITY_uWh start_time = ssb From fdc22554b8c2a2e4b9e0df91beddf469d735b399 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Tue, 28 Jun 2022 11:32:51 +0200 Subject: [PATCH 148/302] Update rednose: use EKF_sym_pyx (#24978) * Update rednose * Update rednose * cleanup --- rednose_repo | 2 +- selfdrive/locationd/models/car_kf.py | 4 ++-- selfdrive/locationd/models/gnss_kf.py | 16 +++++++++++----- 3 files changed, 14 insertions(+), 8 deletions(-) diff --git a/rednose_repo b/rednose_repo index 7663289f1e..3a6f937ad1 160000 --- a/rednose_repo +++ b/rednose_repo @@ -1 +1 @@ -Subproject commit 7663289f1e68860f53dc34337ef080dde69a2586 +Subproject commit 3a6f937ad1bb234dca7b0b2052faabdd58f3e085 diff --git a/selfdrive/locationd/models/car_kf.py b/selfdrive/locationd/models/car_kf.py index fe7d2e650b..3faf4f8d4e 100755 --- a/selfdrive/locationd/models/car_kf.py +++ b/selfdrive/locationd/models/car_kf.py @@ -15,7 +15,7 @@ if __name__ == '__main__': # Generating sympy import sympy as sp from rednose.helpers.ekf_sym import gen_code else: - from rednose.helpers.ekf_sym_pyx import EKF_sym # pylint: disable=no-name-in-module, import-error + from rednose.helpers.ekf_sym_pyx import EKF_sym_pyx # pylint: disable=no-name-in-module, import-error i = 0 @@ -171,7 +171,7 @@ class CarKalman(KalmanFilter): if P_initial is not None: self.P_initial = P_initial # init filter - self.filter = EKF_sym(generated_dir, self.name, self.Q, self.initial_x, self.P_initial, dim_state, dim_state_err, global_vars=self.global_vars, logger=cloudlog) + self.filter = EKF_sym_pyx(generated_dir, self.name, self.Q, self.initial_x, self.P_initial, dim_state, dim_state_err, global_vars=self.global_vars, logger=cloudlog) if __name__ == "__main__": diff --git a/selfdrive/locationd/models/gnss_kf.py b/selfdrive/locationd/models/gnss_kf.py index ce0ff84dc2..5c9cb4b3d1 100755 --- a/selfdrive/locationd/models/gnss_kf.py +++ b/selfdrive/locationd/models/gnss_kf.py @@ -3,12 +3,17 @@ import sys from typing import List import numpy as np -import sympy as sp -from rednose.helpers.ekf_sym import EKF_sym, gen_code from selfdrive.locationd.models.constants import ObservationKind from selfdrive.locationd.models.gnss_helpers import parse_pr, parse_prr +if __name__ == '__main__': # Generating sympy + import sympy as sp + from rednose.helpers.ekf_sym import gen_code +else: + from rednose.helpers.ekf_sym_pyx import EKF_sym_pyx # pylint: disable=no-name-in-module,import-error + from rednose.helpers.ekf_sym import EKF_sym # pylint: disable=no-name-in-module,import-error + class States(): ECEF_POS = slice(0, 3) # x, y and z in ECEF in meters @@ -115,12 +120,13 @@ class GNSSKalman(): gen_code(generated_dir, name, f_sym, dt, state_sym, obs_eqs, dim_state, dim_state, maha_test_kinds=maha_test_kinds) - def __init__(self, generated_dir): + def __init__(self, generated_dir, cython=False): self.dim_state = self.x_initial.shape[0] # init filter - self.filter = EKF_sym(generated_dir, self.name, self.Q, self.x_initial, self.P_initial, self.dim_state, - self.dim_state, maha_test_kinds=self.maha_test_kinds) + filter_cls = EKF_sym_pyx if cython else EKF_sym + self.filter = filter_cls(generated_dir, self.name, self.Q, self.x_initial, self.P_initial, self.dim_state, + self.dim_state, maha_test_kinds=self.maha_test_kinds) self.init_state(GNSSKalman.x_initial, covs=GNSSKalman.P_initial) @property From 4cf63f4758c937a169962f325517b442f6c9492f Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 28 Jun 2022 11:59:15 +0200 Subject: [PATCH 149/302] bump rednose --- rednose_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rednose_repo b/rednose_repo index 3a6f937ad1..a79a87300a 160000 --- a/rednose_repo +++ b/rednose_repo @@ -1 +1 @@ -Subproject commit 3a6f937ad1bb234dca7b0b2052faabdd58f3e085 +Subproject commit a79a87300a6c5093d99f281307c65b1e99295b20 From 3823f55476b56fd3db0afe686b1d2f3d508817bc Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 28 Jun 2022 13:43:15 +0200 Subject: [PATCH 150/302] add laikad to process replay (#24889) * merge * Fix closing process executor after fetching orbits * cleanup * Add ref commit and revert test_processes hack * Fix * Fix ref * Fix test * Temp * Temp * Trying * Trying * Cleanup and change test * add ref commit * remove print * fix test getting stuck * cleanup fetch_orbits Co-authored-by: Gijs Koning --- selfdrive/locationd/laikad.py | 50 ++++++++++++------- selfdrive/locationd/test/test_laikad.py | 27 ++++++++-- selfdrive/test/process_replay/README.md | 3 +- .../test/process_replay/process_replay.py | 18 +++++++ selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/test/profiling/profiler.py | 3 ++ 6 files changed, 81 insertions(+), 22 deletions(-) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index ba665b7530..60028b637a 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -1,5 +1,6 @@ #!/usr/bin/env python3 import json +import os import time from collections import defaultdict from concurrent.futures import Future, ProcessPoolExecutor @@ -32,8 +33,10 @@ class Laikad: save_ephemeris=False, last_known_position=None): self.astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types, clear_old_ephemeris=True) self.gnss_kf = GNSSKalman(GENERATED_DIR) - self.orbit_fetch_executor = ProcessPoolExecutor() + + self.orbit_fetch_executor: Optional[ProcessPoolExecutor] = None self.orbit_fetch_future: Optional[Future] = None + self.last_fetch_orbits_t = None self.last_cached_t = None self.save_ephemeris = save_ephemeris @@ -44,9 +47,13 @@ class Laikad: self.last_pos_fix_t = None def load_cache(self): + if not self.save_ephemeris: + return + cache = Params().get(EPHEMERIS_CACHE) if not cache: return + try: cache = json.loads(cache, object_hook=deserialize_hook) self.astro_dog.add_orbits(cache['orbits']) @@ -71,7 +78,7 @@ class Laikad: self.last_pos_residual = pos_fix_residual self.last_pos_fix_t = t return self.last_pos_fix - + def process_ublox_msg(self, ublox_msg, ublox_mono_time: int, block=False): if ublox_msg.which == 'measurementReport': t = ublox_mono_time * 1e-9 @@ -152,17 +159,22 @@ class Laikad: def fetch_orbits(self, t: GPSTime, block): if t not in self.astro_dog.orbit_fetched_times and (self.last_fetch_orbits_t is None or t - self.last_fetch_orbits_t > SECS_IN_HR): astro_dog_vars = self.astro_dog.valid_const, self.astro_dog.auto_update, self.astro_dog.valid_ephem_types - if self.orbit_fetch_future is None: + + ret = None + + if block: + ret = get_orbit_data(t, *astro_dog_vars) + elif self.orbit_fetch_future is None: + self.orbit_fetch_executor = ProcessPoolExecutor(max_workers=1) self.orbit_fetch_future = self.orbit_fetch_executor.submit(get_orbit_data, t, *astro_dog_vars) - if block: - self.orbit_fetch_future.result() - if self.orbit_fetch_future.done(): - ret = self.orbit_fetch_future.result() + elif self.orbit_fetch_future.done(): self.last_fetch_orbits_t = t - if ret: - self.astro_dog.orbits, self.astro_dog.orbit_fetched_times = ret - self.cache_ephemeris(t=t) - self.orbit_fetch_future = None + ret = self.orbit_fetch_future.result() + self.orbit_fetch_executor = self.orbit_fetch_future = None + + if ret is not None: + self.astro_dog.orbits, self.astro_dog.orbit_fetched_times = ret + self.cache_ephemeris(t=t) def get_orbit_data(t: GPSTime, valid_const, auto_update, valid_ephem_types): @@ -174,7 +186,7 @@ def get_orbit_data(t: GPSTime, valid_const, auto_update, valid_ephem_types): astro_dog.get_orbit_data(t, only_predictions=True) data = (astro_dog.orbits, astro_dog.orbit_fetched_times) except RuntimeError as e: - cloudlog.info(f"No orbit data found. {e}") + cloudlog.warning(f"No orbit data found. {e}") cloudlog.info(f"Done parsing orbits. Took {time.monotonic() - start_time:.1f}s") return data @@ -255,17 +267,21 @@ class EphemerisSourceType(IntEnum): glonassIacUltraRapid = 2 -def main(): - sm = messaging.SubMaster(['ubloxGnss']) - pm = messaging.PubMaster(['gnssMeasurements']) +def main(sm=None, pm=None): + if sm is None: + sm = messaging.SubMaster(['ubloxGnss']) + if pm is None: + pm = messaging.PubMaster(['gnssMeasurements']) + + replay = "REPLAY" in os.environ # todo get last_known_position - laikad = Laikad(save_ephemeris=True) + laikad = Laikad(save_ephemeris=not replay) while True: sm.update() if sm.updated['ubloxGnss']: ublox_msg = sm['ubloxGnss'] - msg = laikad.process_ublox_msg(ublox_msg, sm.logMonoTime['ubloxGnss']) + msg = laikad.process_ublox_msg(ublox_msg, sm.logMonoTime['ubloxGnss'], block=replay) if msg is not None: pm.send('gnssMeasurements', msg) diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py index 3a72303b0c..c353da9624 100755 --- a/selfdrive/locationd/test/test_laikad.py +++ b/selfdrive/locationd/test/test_laikad.py @@ -7,6 +7,7 @@ from unittest import mock from unittest.mock import Mock, patch from common.params import Params +from laika.constants import SECS_IN_DAY from laika.ephemeris import EphemerisType, GPSEphemeris from laika.gps_time import GPSTime from laika.helpers import ConstellationId, TimeRangeHolder @@ -62,6 +63,26 @@ class TestLaikad(unittest.TestCase): def setUp(self): Params().delete(EPHEMERIS_CACHE) + def test_fetch_orbits_non_blocking(self): + gpstime = GPSTime.from_datetime(datetime(2021, month=3, day=1)) + laikad = Laikad() + laikad.fetch_orbits(gpstime, block=False) + laikad.orbit_fetch_future.result(5) + # Get results and save orbits to laikad: + laikad.fetch_orbits(gpstime, block=False) + + ephem = laikad.astro_dog.orbits['G01'][0] + self.assertIsNotNone(ephem) + + laikad.fetch_orbits(gpstime+2*SECS_IN_DAY, block=False) + laikad.orbit_fetch_future.result(5) + # Get results and save orbits to laikad: + laikad.fetch_orbits(gpstime + 2 * SECS_IN_DAY, block=False) + + ephem2 = laikad.astro_dog.orbits['G01'][0] + self.assertIsNotNone(ephem) + self.assertNotEqual(ephem, ephem2) + def test_ephemeris_source_in_msg(self): data_mock = defaultdict(str) data_mock['sv_id'] = 1 @@ -155,7 +176,7 @@ class TestLaikad(unittest.TestCase): while Params().get(EPHEMERIS_CACHE) is None: time.sleep(0.1) max_time -= 0.1 - if max_time == 0: + if max_time < 0: self.fail("Cache has not been written after 2 seconds") # Test cache with no ephemeris @@ -170,7 +191,7 @@ class TestLaikad(unittest.TestCase): wait_for_cache() # Check both nav and orbits separate - laikad = Laikad(auto_update=False, valid_ephem_types=EphemerisType.NAV) + laikad = Laikad(auto_update=False, valid_ephem_types=EphemerisType.NAV, save_ephemeris=True) # Verify orbits and nav are loaded from cache self.dict_has_values(laikad.astro_dog.orbits) self.dict_has_values(laikad.astro_dog.nav) @@ -185,7 +206,7 @@ class TestLaikad(unittest.TestCase): mock_method.assert_not_called() # Verify cache is working for only orbits by running a segment - laikad = Laikad(auto_update=False, valid_ephem_types=EphemerisType.ULTRA_RAPID_ORBIT) + laikad = Laikad(auto_update=False, valid_ephem_types=EphemerisType.ULTRA_RAPID_ORBIT, save_ephemeris=True) msg = verify_messages(self.logs, laikad, return_one_success=True) self.assertIsNotNone(msg) # Verify orbit data is not downloaded diff --git a/selfdrive/test/process_replay/README.md b/selfdrive/test/process_replay/README.md index 9fa4ca644a..531ddb3a02 100644 --- a/selfdrive/test/process_replay/README.md +++ b/selfdrive/test/process_replay/README.md @@ -5,7 +5,7 @@ Process replay is a regression test designed to identify any changes in the outp If the test fails, make sure that you didn't unintentionally change anything. If there are intentional changes, the reference logs will be updated. Use `test_processes.py` to run the test locally. -Use `FILEREADER_CACHE='1' test_processes.py` to cache log files. +Use `FILEREADER_CACHE='1' test_processes.py` to cache log files. Currently the following processes are tested: @@ -15,6 +15,7 @@ Currently the following processes are tested: * calibrationd * dmonitoringd * locationd +* laikad * paramsd * ubloxd diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 228f07c4c2..def61a10a1 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -236,6 +236,13 @@ def ublox_rcv_callback(msg): return [] +def laika_rcv_callback(msg, CP, cfg, fsm): + if msg.ubloxGnss.which() == "measurementReport": + return ["gnssMeasurements"], True + else: + return [], False + + CONFIGS = [ ProcessConfig( proc_name="controlsd", @@ -338,6 +345,17 @@ CONFIGS = [ tolerance=None, fake_pubsubmaster=False, ), + ProcessConfig( + proc_name="laikad", + pub_sub={ + "ubloxGnss": ["gnssMeasurements"], + }, + ignore=["logMonoTime"], + init_callback=get_car_params, + should_recv_callback=laika_rcv_callback, + tolerance=NUMPY_TOLERANCE, + fake_pubsubmaster=True, + ), ] diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 1402284b96..3e02830bf4 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -a16ca1082cd493f6cea5252eaaba9f8c6574334a +2ee969b34585f8055bb3eabab2dcc4061cc4bef9 \ No newline at end of file diff --git a/selfdrive/test/profiling/profiler.py b/selfdrive/test/profiling/profiler.py index 5f73176fab..91226fc577 100755 --- a/selfdrive/test/profiling/profiler.py +++ b/selfdrive/test/profiling/profiler.py @@ -53,6 +53,7 @@ def profile(proc, func, car='toyota'): msgs = list(LogReader(rlog_url)) * int(os.getenv("LOOP", "1")) os.environ['FINGERPRINT'] = fingerprint + os.environ['REPLAY'] = "1" def run(sm, pm, can_sock): try: @@ -81,12 +82,14 @@ if __name__ == '__main__': from selfdrive.controls.radard import radard_thread from selfdrive.locationd.paramsd import main as paramsd_thread from selfdrive.controls.plannerd import main as plannerd_thread + from selfdrive.locationd.laikad import main as laikad_thread procs = { 'radard': radard_thread, 'controlsd': controlsd_thread, 'paramsd': paramsd_thread, 'plannerd': plannerd_thread, + 'laikad': laikad_thread, } proc = sys.argv[1] From 005bc44df692acb3389924d362f5b761987c7c9d Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 28 Jun 2022 14:29:41 +0200 Subject: [PATCH 151/302] laikad: use cython filter (#24983) use cython filter --- selfdrive/locationd/laikad.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 60028b637a..5098b25d38 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -32,7 +32,7 @@ class Laikad: def __init__(self, valid_const=("GPS", "GLONASS"), auto_update=False, valid_ephem_types=(EphemerisType.ULTRA_RAPID_ORBIT, EphemerisType.NAV), save_ephemeris=False, last_known_position=None): self.astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types, clear_old_ephemeris=True) - self.gnss_kf = GNSSKalman(GENERATED_DIR) + self.gnss_kf = GNSSKalman(GENERATED_DIR, cython=True) self.orbit_fetch_executor: Optional[ProcessPoolExecutor] = None self.orbit_fetch_future: Optional[Future] = None @@ -145,7 +145,7 @@ class Laikad: self.gnss_kf.predict(t) def kf_valid(self, t: float) -> List[bool]: - filter_time = self.gnss_kf.filter.filter_time + filter_time = self.gnss_kf.filter.get_filter_time() return [filter_time is not None, filter_time is not None and abs(t - filter_time) < MAX_TIME_GAP, all(np.isfinite(self.gnss_kf.x[GStates.ECEF_POS]))] From 338df150d5112d4c6772edb797cb45370fdc3599 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 28 Jun 2022 15:48:57 +0200 Subject: [PATCH 152/302] ui: disable sync with model until more stable (#24984) --- selfdrive/ui/qt/widgets/cameraview.cc | 17 ++++++++++++++--- 1 file changed, 14 insertions(+), 3 deletions(-) diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index a80672f2c3..0bc90b5307 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -235,10 +235,21 @@ void CameraViewWidget::paintGL() { if (frames.empty()) return; - int frame_idx; - for (frame_idx = 0; frame_idx < frames.size() - 1; frame_idx++) { - if (frames[frame_idx].first == draw_frame_id) break; + int frame_idx = frames.size() - 1; + + // Always draw latest frame until sync logic is more stable + // for (frame_idx = 0; frame_idx < frames.size() - 1; frame_idx++) { + // if (frames[frame_idx].first == draw_frame_id) break; + // } + + // Log duplicate/dropped frames + static int prev_id = 0; + if (frames[frame_idx].first == prev_id) { + qInfo() << "Drawing same frame twice" << frames[frame_idx].first; + } else if (frames[frame_idx].first != prev_id + 1) { + qInfo() << "Skipped frame" << frames[frame_idx].first; } + prev_id = frames[frame_idx].first; glViewport(0, 0, width(), height()); glBindVertexArray(frame_vao); From fd5b3d76036b78864111790931a3abcb1d11ee0f Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 28 Jun 2022 22:12:42 +0800 Subject: [PATCH 153/302] move replay from selfdrive/ui/replay to tools/replay (#24971) * mv to tools/replay * change folder * add .gitignore * fix build doc * disable warning * enable warning after build * build qt/util.cc qt/api.cc to library * cleanup --- .github/workflows/selfdrive_tests.yaml | 2 +- SConstruct | 2 ++ docs/c_docs.rst | 2 +- release/files_common | 4 ++-- selfdrive/loggerd/tests/test_logger.cc | 2 +- selfdrive/ui/SConscript | 20 +++++-------------- tools/CTF.md | 2 +- tools/replay/.gitignore | 5 +++++ tools/replay/README.md | 14 ++++++------- tools/replay/SConscript | 19 ++++++++++++++++++ {selfdrive/ui => tools}/replay/camera.cc | 4 ++-- {selfdrive/ui => tools}/replay/camera.h | 4 ++-- {selfdrive/ui => tools}/replay/consoleui.cc | 2 +- {selfdrive/ui => tools}/replay/consoleui.h | 2 +- {selfdrive/ui => tools}/replay/filereader.cc | 4 ++-- {selfdrive/ui => tools}/replay/filereader.h | 0 {selfdrive/ui => tools}/replay/framereader.cc | 4 ++-- {selfdrive/ui => tools}/replay/framereader.h | 2 +- {selfdrive/ui => tools}/replay/logreader.cc | 4 ++-- {selfdrive/ui => tools}/replay/logreader.h | 2 +- {selfdrive/ui => tools}/replay/main.cc | 4 ++-- {selfdrive/ui => tools}/replay/replay.cc | 4 ++-- {selfdrive/ui => tools}/replay/replay.h | 4 ++-- {selfdrive/ui => tools}/replay/route.cc | 6 +++--- {selfdrive/ui => tools}/replay/route.h | 6 +++--- .../ui => tools}/replay/tests/test_replay.cc | 4 ++-- .../ui => tools}/replay/tests/test_runner.cc | 0 {selfdrive/ui => tools}/replay/util.cc | 2 +- {selfdrive/ui => tools}/replay/util.h | 0 29 files changed, 73 insertions(+), 57 deletions(-) create mode 100644 tools/replay/.gitignore create mode 100644 tools/replay/SConscript rename {selfdrive/ui => tools}/replay/camera.cc (96%) rename {selfdrive/ui => tools}/replay/camera.h (92%) rename {selfdrive/ui => tools}/replay/consoleui.cc (99%) rename {selfdrive/ui => tools}/replay/consoleui.h (96%) rename {selfdrive/ui => tools}/replay/filereader.cc (94%) rename {selfdrive/ui => tools}/replay/filereader.h (100%) rename {selfdrive/ui => tools}/replay/framereader.cc (98%) rename {selfdrive/ui => tools}/replay/framereader.h (97%) rename {selfdrive/ui => tools}/replay/logreader.cc (97%) rename {selfdrive/ui => tools}/replay/logreader.h (97%) rename {selfdrive/ui => tools}/replay/main.cc (96%) rename {selfdrive/ui => tools}/replay/replay.cc (99%) rename {selfdrive/ui => tools}/replay/replay.h (97%) rename {selfdrive/ui => tools}/replay/route.cc (97%) rename {selfdrive/ui => tools}/replay/route.h (92%) rename {selfdrive/ui => tools}/replay/tests/test_replay.cc (98%) rename {selfdrive/ui => tools}/replay/tests/test_runner.cc (100%) rename {selfdrive/ui => tools}/replay/util.cc (99%) rename {selfdrive/ui => tools}/replay/util.h (100%) diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 52dd012baa..a40aa31341 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -310,7 +310,7 @@ jobs: ./selfdrive/boardd/tests/test_boardd_usbprotocol && \ ./selfdrive/loggerd/tests/test_logger &&\ ./system/proclogd/tests/test_proclog && \ - ./selfdrive/ui/replay/tests/test_replay && \ + ./tools/replay/tests/test_replay && \ ./system/camerad/test/ae_gray_test && \ coverage xml" - name: "Upload coverage to Codecov" diff --git a/SConstruct b/SConstruct index b243a4dc45..425ce3d761 100644 --- a/SConstruct +++ b/SConstruct @@ -411,6 +411,8 @@ SConscript(['selfdrive/locationd/SConscript']) SConscript(['selfdrive/sensord/SConscript']) SConscript(['selfdrive/ui/SConscript']) +SConscript(['tools/replay/SConscript']) + if GetOption('test'): SConscript('panda/tests/safety/SConscript') diff --git a/docs/c_docs.rst b/docs/c_docs.rst index 4e1e8a247a..5638b40bf0 100644 --- a/docs/c_docs.rst +++ b/docs/c_docs.rst @@ -54,7 +54,7 @@ soundd replay """""" .. autodoxygenindex:: - :project: selfdrive_ui_replay + :project: tools_replay qt "" diff --git a/release/files_common b/release/files_common index 0ace73623f..7e8dbd37a6 100644 --- a/release/files_common +++ b/release/files_common @@ -296,8 +296,8 @@ selfdrive/ui/qt/offroad/*.qml selfdrive/ui/qt/widgets/*.cc selfdrive/ui/qt/widgets/*.h -selfdrive/ui/replay/*.cc -selfdrive/ui/replay/*.h +tools/replay/*.cc +tools/replay/*.h selfdrive/ui/qt/maps/*.cc selfdrive/ui/qt/maps/*.h diff --git a/selfdrive/loggerd/tests/test_logger.cc b/selfdrive/loggerd/tests/test_logger.cc index 11a50fa2e7..c8f6620924 100644 --- a/selfdrive/loggerd/tests/test_logger.cc +++ b/selfdrive/loggerd/tests/test_logger.cc @@ -9,7 +9,7 @@ #include "cereal/messaging/messaging.h" #include "common/util.h" #include "selfdrive/loggerd/logger.h" -#include "selfdrive/ui/replay/util.h" +#include "tools/replay/util.h" typedef cereal::Sentinel::SentinelType SentinelType; diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 28fcc5f56f..970f715f54 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -18,10 +18,11 @@ if arch == "Darwin": del base_libs[base_libs.index('OpenCL')] qt_env['FRAMEWORKS'] += ['OpenCL'] -widgets_src = ["ui.cc", "qt/util.cc", "qt/widgets/input.cc", "qt/widgets/drive_stats.cc", +qt_util = qt_env.Library("qt_util", ["#selfdrive/ui/qt/api.cc", "#selfdrive/ui/qt/util.cc"], LIBS=base_libs) +widgets_src = ["ui.cc", "qt/widgets/input.cc", "qt/widgets/drive_stats.cc", "qt/widgets/ssh_keys.cc", "qt/widgets/toggle.cc", "qt/widgets/controls.cc", "qt/widgets/offroad_alerts.cc", "qt/widgets/prime.cc", "qt/widgets/keyboard.cc", - "qt/widgets/scrollview.cc", "qt/widgets/cameraview.cc", "#third_party/qrcode/QrCode.cc", "qt/api.cc", + "qt/widgets/scrollview.cc", "qt/widgets/cameraview.cc", "#third_party/qrcode/QrCode.cc", "qt/request_repeater.cc", "qt/qt_window.cc", "qt/offroad/networking.cc", "qt/offroad/wifiManager.cc"] qt_env['CPPDEFINES'] = [] @@ -31,7 +32,7 @@ if maps: qt_env['CPPDEFINES'] += ["ENABLE_MAPS"] widgets = qt_env.Library("qt_widgets", widgets_src, LIBS=base_libs) -qt_libs = [widgets] + base_libs +qt_libs = [widgets, qt_util] + base_libs # build assets assets = "#selfdrive/assets/assets.cc" @@ -107,17 +108,6 @@ if GetOption('extras'): # keep installers small assert f[0].get_size() < 300*1e3 - -# build headless replay +# build watch3 if arch in ['x86_64', 'Darwin'] or GetOption('extras'): - qt_env['CXXFLAGS'] += ["-Wno-deprecated-declarations"] - - replay_lib_src = ["replay/replay.cc", "replay/consoleui.cc", "replay/camera.cc", "replay/filereader.cc", "replay/logreader.cc", "replay/framereader.cc", "replay/route.cc", "replay/util.cc"] - - replay_lib = qt_env.Library("qt_replay", replay_lib_src, LIBS=base_libs) - replay_libs = [replay_lib, 'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv', 'ncurses'] + qt_libs - qt_env.Program("replay/replay", ["replay/main.cc"], LIBS=replay_libs) qt_env.Program("watch3", ["watch3.cc"], LIBS=qt_libs + ['common', 'json11', 'zmq', 'visionipc', 'messaging']) - - if GetOption('test'): - qt_env.Program('replay/tests/test_replay', ['replay/tests/test_runner.cc', 'replay/tests/test_replay.cc'], LIBS=[replay_libs]) diff --git a/tools/CTF.md b/tools/CTF.md index 396e7575a4..a14a41d55d 100644 --- a/tools/CTF.md +++ b/tools/CTF.md @@ -12,7 +12,7 @@ Welcome to the first part of the comma CTF! getting started ```bash # start the route reply -cd selfdrive/ui/replay +cd tools/replay ./replay '0c7f0c7f0c7f0c7f|2021-10-13--13-00-00' --dcam --ecam # start the UI in another terminal diff --git a/tools/replay/.gitignore b/tools/replay/.gitignore new file mode 100644 index 0000000000..83f0e99a8b --- /dev/null +++ b/tools/replay/.gitignore @@ -0,0 +1,5 @@ +moc_* +*.moc + +replay +tests/test_replay diff --git a/tools/replay/README.md b/tools/replay/README.md index 759a448d73..b705fb60db 100644 --- a/tools/replay/README.md +++ b/tools/replay/README.md @@ -9,12 +9,12 @@ python lib/auth.py # Start a replay -selfdrive/ui/replay/replay +tools/replay/replay # Example: -# selfdrive/ui/replay/replay '4cf7a6ad03080c90|2021-09-29--13-46-36' +# tools/replay/replay '4cf7a6ad03080c90|2021-09-29--13-46-36' # or use --demo to replay the default demo route: -# selfdrive/ui/replay/replay --demo +# tools/replay/replay --demo # watch the replay with the normal openpilot UI cd selfdrive/ui && ./ui @@ -25,8 +25,8 @@ python replay/ui.py ## usage ``` bash -$ selfdrive/ui/replay/replay -h -Usage: selfdrive/ui/replay/replay [options] route +$ tools/replay/replay -h +Usage: tools/replay/replay [options] route Mock openpilot components by publishing logged messages. Options: @@ -51,7 +51,7 @@ simply replay a route using the `--dcam` and `--ecam` flags: ```bash # start a replay -cd selfdrive/ui/replay && ./replay --demo --dcam --ecam +cd tools/replay && ./replay --demo --dcam --ecam # then start watch3 cd selfdrive/ui && ./watch3 @@ -70,5 +70,5 @@ In order to replay specific route: MOCK=1 selfdrive/boardd/tests/boardd_old.py # In another terminal: -selfdrive/ui/replay/replay +tools/replay/replay ``` diff --git a/tools/replay/SConscript b/tools/replay/SConscript new file mode 100644 index 0000000000..4a85f46d61 --- /dev/null +++ b/tools/replay/SConscript @@ -0,0 +1,19 @@ +import os +Import('env', 'qt_env', 'arch', 'common', 'messaging', 'visionipc', + 'cereal', 'transformations') + +base_libs = [common, messaging, cereal, visionipc, transformations, 'zmq', + 'capnp', 'kj', 'm', 'OpenCL', 'ssl', 'crypto', 'pthread'] + qt_env["LIBS"] + +qt_libs = ['qt_util'] + base_libs +if arch in ['x86_64', 'Darwin'] or GetOption('extras'): + qt_env['CXXFLAGS'] += ["-Wno-deprecated-declarations"] + + replay_lib_src = ["replay.cc", "consoleui.cc", "camera.cc", "filereader.cc", "logreader.cc", "framereader.cc", "route.cc", "util.cc"] + + replay_lib = qt_env.Library("qt_replay", replay_lib_src, LIBS=qt_libs) + replay_libs = [replay_lib, 'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv', 'ncurses'] + qt_libs + qt_env.Program("replay", ["main.cc"], LIBS=replay_libs) + + if GetOption('test'): + qt_env.Program('tests/test_replay', ['tests/test_runner.cc', 'tests/test_replay.cc'], LIBS=[replay_libs]) diff --git a/selfdrive/ui/replay/camera.cc b/tools/replay/camera.cc similarity index 96% rename from selfdrive/ui/replay/camera.cc rename to tools/replay/camera.cc index 2e8b68a415..87afe63a2a 100644 --- a/selfdrive/ui/replay/camera.cc +++ b/tools/replay/camera.cc @@ -1,5 +1,5 @@ -#include "selfdrive/ui/replay/camera.h" -#include "selfdrive/ui/replay/util.h" +#include "tools/replay/camera.h" +#include "tools/replay/util.h" #include diff --git a/selfdrive/ui/replay/camera.h b/tools/replay/camera.h similarity index 92% rename from selfdrive/ui/replay/camera.h rename to tools/replay/camera.h index 7f078511cf..66d33142fb 100644 --- a/selfdrive/ui/replay/camera.h +++ b/tools/replay/camera.h @@ -3,8 +3,8 @@ #include #include "cereal/visionipc/visionipc_server.h" #include "common/queue.h" -#include "selfdrive/ui/replay/framereader.h" -#include "selfdrive/ui/replay/logreader.h" +#include "tools/replay/framereader.h" +#include "tools/replay/logreader.h" class CameraServer { public: diff --git a/selfdrive/ui/replay/consoleui.cc b/tools/replay/consoleui.cc similarity index 99% rename from selfdrive/ui/replay/consoleui.cc rename to tools/replay/consoleui.cc index 05eb09c9ed..e4a3146a69 100644 --- a/selfdrive/ui/replay/consoleui.cc +++ b/tools/replay/consoleui.cc @@ -1,4 +1,4 @@ -#include "selfdrive/ui/replay/consoleui.h" +#include "tools/replay/consoleui.h" #include #include diff --git a/selfdrive/ui/replay/consoleui.h b/tools/replay/consoleui.h similarity index 96% rename from selfdrive/ui/replay/consoleui.h rename to tools/replay/consoleui.h index bce1146d46..20e07524dd 100644 --- a/selfdrive/ui/replay/consoleui.h +++ b/tools/replay/consoleui.h @@ -7,7 +7,7 @@ #include #include -#include "selfdrive/ui/replay/replay.h" +#include "tools/replay/replay.h" #include class ConsoleUI : public QObject { diff --git a/selfdrive/ui/replay/filereader.cc b/tools/replay/filereader.cc similarity index 94% rename from selfdrive/ui/replay/filereader.cc rename to tools/replay/filereader.cc index 5f862bec35..88879067c9 100644 --- a/selfdrive/ui/replay/filereader.cc +++ b/tools/replay/filereader.cc @@ -1,9 +1,9 @@ -#include "selfdrive/ui/replay/filereader.h" +#include "tools/replay/filereader.h" #include #include "common/util.h" -#include "selfdrive/ui/replay/util.h" +#include "tools/replay/util.h" std::string cacheFilePath(const std::string &url) { static std::string cache_path = [] { diff --git a/selfdrive/ui/replay/filereader.h b/tools/replay/filereader.h similarity index 100% rename from selfdrive/ui/replay/filereader.h rename to tools/replay/filereader.h diff --git a/selfdrive/ui/replay/framereader.cc b/tools/replay/framereader.cc similarity index 98% rename from selfdrive/ui/replay/framereader.cc rename to tools/replay/framereader.cc index 38d98bddc5..bfa85a0625 100644 --- a/selfdrive/ui/replay/framereader.cc +++ b/tools/replay/framereader.cc @@ -1,5 +1,5 @@ -#include "selfdrive/ui/replay/framereader.h" -#include "selfdrive/ui/replay/util.h" +#include "tools/replay/framereader.h" +#include "tools/replay/util.h" #include #include "libyuv.h" diff --git a/selfdrive/ui/replay/framereader.h b/tools/replay/framereader.h similarity index 97% rename from selfdrive/ui/replay/framereader.h rename to tools/replay/framereader.h index 443636e27d..10bf34a24e 100644 --- a/selfdrive/ui/replay/framereader.h +++ b/tools/replay/framereader.h @@ -4,7 +4,7 @@ #include #include -#include "selfdrive/ui/replay/filereader.h" +#include "tools/replay/filereader.h" extern "C" { #include diff --git a/selfdrive/ui/replay/logreader.cc b/tools/replay/logreader.cc similarity index 97% rename from selfdrive/ui/replay/logreader.cc rename to tools/replay/logreader.cc index 579fe50644..f27224ac53 100644 --- a/selfdrive/ui/replay/logreader.cc +++ b/tools/replay/logreader.cc @@ -1,7 +1,7 @@ -#include "selfdrive/ui/replay/logreader.h" +#include "tools/replay/logreader.h" #include -#include "selfdrive/ui/replay/util.h" +#include "tools/replay/util.h" Event::Event(const kj::ArrayPtr &amsg, bool frame) : reader(amsg), frame(frame) { words = kj::ArrayPtr(amsg.begin(), reader.getEnd()); diff --git a/selfdrive/ui/replay/logreader.h b/tools/replay/logreader.h similarity index 97% rename from selfdrive/ui/replay/logreader.h rename to tools/replay/logreader.h index b4a38a5721..fb63bf3913 100644 --- a/selfdrive/ui/replay/logreader.h +++ b/tools/replay/logreader.h @@ -7,7 +7,7 @@ #include "cereal/gen/cpp/log.capnp.h" #include "system/camerad/cameras/camera_common.h" -#include "selfdrive/ui/replay/filereader.h" +#include "tools/replay/filereader.h" const CameraType ALL_CAMERAS[] = {RoadCam, DriverCam, WideRoadCam}; const int MAX_CAMERAS = std::size(ALL_CAMERAS); diff --git a/selfdrive/ui/replay/main.cc b/tools/replay/main.cc similarity index 96% rename from selfdrive/ui/replay/main.cc rename to tools/replay/main.cc index e09587023c..d3d6894877 100644 --- a/selfdrive/ui/replay/main.cc +++ b/tools/replay/main.cc @@ -1,8 +1,8 @@ #include #include -#include "selfdrive/ui/replay/consoleui.h" -#include "selfdrive/ui/replay/replay.h" +#include "tools/replay/consoleui.h" +#include "tools/replay/replay.h" const QString DEMO_ROUTE = "4cf7a6ad03080c90|2021-09-29--13-46-36"; diff --git a/selfdrive/ui/replay/replay.cc b/tools/replay/replay.cc similarity index 99% rename from selfdrive/ui/replay/replay.cc rename to tools/replay/replay.cc index cf7520b361..c886a7e186 100644 --- a/selfdrive/ui/replay/replay.cc +++ b/tools/replay/replay.cc @@ -1,4 +1,4 @@ -#include "selfdrive/ui/replay/replay.h" +#include "tools/replay/replay.h" #include #include @@ -8,7 +8,7 @@ #include "common/params.h" #include "common/timing.h" #include "system/hardware/hw.h" -#include "selfdrive/ui/replay/util.h" +#include "tools/replay/util.h" Replay::Replay(QString route, QStringList allow, QStringList block, SubMaster *sm_, uint32_t flags, QString data_dir, QObject *parent) : sm(sm_), flags_(flags), QObject(parent) { diff --git a/selfdrive/ui/replay/replay.h b/tools/replay/replay.h similarity index 97% rename from selfdrive/ui/replay/replay.h rename to tools/replay/replay.h index c89a835f64..13269d3ec9 100644 --- a/selfdrive/ui/replay/replay.h +++ b/tools/replay/replay.h @@ -4,8 +4,8 @@ #include -#include "selfdrive/ui/replay/camera.h" -#include "selfdrive/ui/replay/route.h" +#include "tools/replay/camera.h" +#include "tools/replay/route.h" // one segment uses about 100M of memory constexpr int FORWARD_SEGS = 5; diff --git a/selfdrive/ui/replay/route.cc b/tools/replay/route.cc similarity index 97% rename from selfdrive/ui/replay/route.cc rename to tools/replay/route.cc index 3d595141cd..5b47090229 100644 --- a/selfdrive/ui/replay/route.cc +++ b/tools/replay/route.cc @@ -1,4 +1,4 @@ -#include "selfdrive/ui/replay/route.h" +#include "tools/replay/route.h" #include #include @@ -11,8 +11,8 @@ #include "system/hardware/hw.h" #include "selfdrive/ui/qt/api.h" -#include "selfdrive/ui/replay/replay.h" -#include "selfdrive/ui/replay/util.h" +#include "tools/replay/replay.h" +#include "tools/replay/util.h" Route::Route(const QString &route, const QString &data_dir) : data_dir_(data_dir) { route_ = parseRoute(route); diff --git a/selfdrive/ui/replay/route.h b/tools/replay/route.h similarity index 92% rename from selfdrive/ui/replay/route.h rename to tools/replay/route.h index ac8fba75ca..6ca9c3b883 100644 --- a/selfdrive/ui/replay/route.h +++ b/tools/replay/route.h @@ -2,9 +2,9 @@ #include -#include "selfdrive/ui/replay/framereader.h" -#include "selfdrive/ui/replay/logreader.h" -#include "selfdrive/ui/replay/util.h" +#include "tools/replay/framereader.h" +#include "tools/replay/logreader.h" +#include "tools/replay/util.h" struct RouteIdentifier { QString dongle_id; diff --git a/selfdrive/ui/replay/tests/test_replay.cc b/tools/replay/tests/test_replay.cc similarity index 98% rename from selfdrive/ui/replay/tests/test_replay.cc rename to tools/replay/tests/test_replay.cc index bf984f5f3d..bd5dee013c 100644 --- a/selfdrive/ui/replay/tests/test_replay.cc +++ b/tools/replay/tests/test_replay.cc @@ -6,8 +6,8 @@ #include "catch2/catch.hpp" #include "common/util.h" -#include "selfdrive/ui/replay/replay.h" -#include "selfdrive/ui/replay/util.h" +#include "tools/replay/replay.h" +#include "tools/replay/util.h" const QString DEMO_ROUTE = "4cf7a6ad03080c90|2021-09-29--13-46-36"; const std::string TEST_RLOG_URL = "https://commadataci.blob.core.windows.net/openpilotci/0c94aa1e1296d7c6/2021-05-05--19-48-37/0/rlog.bz2"; diff --git a/selfdrive/ui/replay/tests/test_runner.cc b/tools/replay/tests/test_runner.cc similarity index 100% rename from selfdrive/ui/replay/tests/test_runner.cc rename to tools/replay/tests/test_runner.cc diff --git a/selfdrive/ui/replay/util.cc b/tools/replay/util.cc similarity index 99% rename from selfdrive/ui/replay/util.cc rename to tools/replay/util.cc index 099219ccde..a6ebbec615 100644 --- a/selfdrive/ui/replay/util.cc +++ b/tools/replay/util.cc @@ -1,4 +1,4 @@ -#include "selfdrive/ui/replay/util.h" +#include "tools/replay/util.h" #include #include diff --git a/selfdrive/ui/replay/util.h b/tools/replay/util.h similarity index 100% rename from selfdrive/ui/replay/util.h rename to tools/replay/util.h From 42d51a1b959fbd00cd43b7fb36cd5dce00f22c55 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 28 Jun 2022 17:20:37 +0200 Subject: [PATCH 154/302] Properly pass KF dependencies to rednose (#24985) * Fix rednose dependencies * bump rednose * bump rednose --- SConstruct | 21 +++++++++++++-------- rednose_repo | 2 +- 2 files changed, 14 insertions(+), 9 deletions(-) diff --git a/SConstruct b/SConstruct index 425ce3d761..1209894ba4 100644 --- a/SConstruct +++ b/SConstruct @@ -356,22 +356,27 @@ Export('cereal', 'messaging', 'visionipc') # Build rednose library and ekf models +rednose_deps = [ + "#selfdrive/locationd/models/constants.py", + "#selfdrive/locationd/models/gnss_helpers.py", +] + rednose_config = { 'generated_folder': '#selfdrive/locationd/models/generated', 'to_build': { - 'gnss': ('#selfdrive/locationd/models/gnss_kf.py', True, []), - 'live': ('#selfdrive/locationd/models/live_kf.py', True, ['live_kf_constants.h']), - 'car': ('#selfdrive/locationd/models/car_kf.py', True, []), + 'gnss': ('#selfdrive/locationd/models/gnss_kf.py', True, [], rednose_deps), + 'live': ('#selfdrive/locationd/models/live_kf.py', True, ['live_kf_constants.h'], rednose_deps), + 'car': ('#selfdrive/locationd/models/car_kf.py', True, [], rednose_deps), }, } if arch != "larch64": rednose_config['to_build'].update({ - 'loc_4': ('#selfdrive/locationd/models/loc_kf.py', True, []), - 'pos_computer_4': ('#rednose/helpers/lst_sq_computer.py', False, []), - 'pos_computer_5': ('#rednose/helpers/lst_sq_computer.py', False, []), - 'feature_handler_5': ('#rednose/helpers/feature_handler.py', False, []), - 'lane': ('#xx/pipeline/lib/ekf/lane_kf.py', True, []), + 'loc_4': ('#selfdrive/locationd/models/loc_kf.py', True, [], rednose_deps), + 'pos_computer_4': ('#rednose/helpers/lst_sq_computer.py', False, [], []), + 'pos_computer_5': ('#rednose/helpers/lst_sq_computer.py', False, [], []), + 'feature_handler_5': ('#rednose/helpers/feature_handler.py', False, [], []), + 'lane': ('#xx/pipeline/lib/ekf/lane_kf.py', True, [], rednose_deps), }) Export('rednose_config') diff --git a/rednose_repo b/rednose_repo index a79a87300a..225dbacbaa 160000 --- a/rednose_repo +++ b/rednose_repo @@ -1 +1 @@ -Subproject commit a79a87300a6c5093d99f281307c65b1e99295b20 +Subproject commit 225dbacbaac312f85eaaee0b97a3acc31f9c6b47 From 712445c5314d0634e1f6a78a95901dd14ac6bc57 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 28 Jun 2022 17:39:22 +0200 Subject: [PATCH 155/302] build.py: remove retry logic (#24986) --- selfdrive/manager/build.py | 101 ++++++++++++++++--------------------- 1 file changed, 43 insertions(+), 58 deletions(-) diff --git a/selfdrive/manager/build.py b/selfdrive/manager/build.py index 10b4c0a4b8..12f894061a 100755 --- a/selfdrive/manager/build.py +++ b/selfdrive/manager/build.py @@ -1,8 +1,6 @@ #!/usr/bin/env python3 import os import subprocess -import sys -import time import textwrap from pathlib import Path @@ -28,62 +26,49 @@ def build(spinner: Spinner, dirty: bool = False) -> None: nproc = os.cpu_count() j_flag = "" if nproc is None else f"-j{nproc - 1}" - for retry in [True, False]: - scons: subprocess.Popen = subprocess.Popen(["scons", j_flag, "--cache-populate"], cwd=BASEDIR, env=env, stderr=subprocess.PIPE) - assert scons.stderr is not None - - compile_output = [] - - # Read progress from stderr and update spinner - while scons.poll() is None: - try: - line = scons.stderr.readline() - if line is None: - continue - line = line.rstrip() - - prefix = b'progress: ' - if line.startswith(prefix): - i = int(line[len(prefix):]) - spinner.update_progress(MAX_BUILD_PROGRESS * min(1., i / TOTAL_SCONS_NODES), 100.) - elif len(line): - compile_output.append(line) - print(line.decode('utf8', 'replace')) - except Exception: - pass - - if scons.returncode != 0: - # Read remaining output - r = scons.stderr.read().split(b'\n') - compile_output += r - - if retry and (not dirty): - if not os.getenv("CI"): - print("scons build failed, cleaning in") - for i in range(3, -1, -1): - print("....%d" % i) - time.sleep(1) - subprocess.check_call(["scons", "-c"], cwd=BASEDIR, env=env) - else: - print("scons build failed after retry") - sys.exit(1) - else: - # Build failed log errors - errors = [line.decode('utf8', 'replace') for line in compile_output - if any(err in line for err in [b'error: ', b'not found, needed by target'])] - error_s = "\n".join(errors) - add_file_handler(cloudlog) - cloudlog.error("scons build failed\n" + error_s) - - # Show TextWindow - spinner.close() - if not os.getenv("CI"): - error_s = "\n \n".join("\n".join(textwrap.wrap(e, 65)) for e in errors) - with TextWindow("openpilot failed to build\n \n" + error_s) as t: - t.wait_for_exit() - exit(1) - else: - break + scons: subprocess.Popen = subprocess.Popen(["scons", j_flag, "--cache-populate"], cwd=BASEDIR, env=env, stderr=subprocess.PIPE) + assert scons.stderr is not None + + compile_output = [] + + # Read progress from stderr and update spinner + while scons.poll() is None: + try: + line = scons.stderr.readline() + if line is None: + continue + line = line.rstrip() + + prefix = b'progress: ' + if line.startswith(prefix): + i = int(line[len(prefix):]) + spinner.update_progress(MAX_BUILD_PROGRESS * min(1., i / TOTAL_SCONS_NODES), 100.) + elif len(line): + compile_output.append(line) + print(line.decode('utf8', 'replace')) + except Exception: + pass + + if scons.returncode != 0: + # Read remaining output + r = scons.stderr.read().split(b'\n') + compile_output += r + + # Build failed log errors + errors = [line.decode('utf8', 'replace') for line in compile_output + if any(err in line for err in [b'error: ', b'not found, needed by target'])] + error_s = "\n".join(errors) + add_file_handler(cloudlog) + cloudlog.error("scons build failed\n" + error_s) + + # Show TextWindow + spinner.close() + if not os.getenv("CI"): + error_s = "\n \n".join("\n".join(textwrap.wrap(e, 65)) for e in errors) + with TextWindow("openpilot failed to build\n \n" + error_s) as t: + t.wait_for_exit() + exit(1) + # enforce max cache size cache_files = [f for f in CACHE_DIR.rglob('*') if f.is_file()] From 75f5282e832a844aafccac3bfa53ffb029c53a2b Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 28 Jun 2022 14:19:17 -0700 Subject: [PATCH 156/302] Chrysler: fix steering angle signals (#24926) * Chrysler_Update * only steering * revert other changes for now only steering * bump * Update ref_commit * bump opendbc * update refs Co-authored-by: Jonathan --- opendbc | 2 +- selfdrive/car/chrysler/carstate.py | 4 ++-- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/opendbc b/opendbc index 82be71072c..47b79c4d5a 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 82be71072c52fc78cf0e1eabc396af26c18ddc11 +Subproject commit 47b79c4d5ab5adc0bdd9d228c3d9594da0355c49 diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index f71a300263..202526df05 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -47,8 +47,6 @@ class CarState(CarStateBase): ret.leftBlinker = cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 1 ret.rightBlinker = cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 2 - ret.steeringAngleDeg = cp.vl["STEERING"]["STEER_ANGLE"] - ret.steeringRateDeg = cp.vl["STEERING"]["STEERING_RATE"] ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["GEAR"]["PRNDL"], None)) ret.cruiseState.available = cp.vl["DAS_3"]["ACC_AVAILABLE"] == 1 # ACC is white @@ -58,6 +56,8 @@ class CarState(CarStateBase): ret.cruiseState.nonAdaptive = cp.vl["DASHBOARD"]["CRUISE_STATE"] in (1, 2) ret.accFaulted = cp.vl["DAS_3"]["ACC_FAULTED"] != 0 + ret.steeringAngleDeg = cp.vl["STEERING"]["STEER_ANGLE"] + ret.steeringRateDeg = cp.vl["STEERING"]["STEERING_RATE"] ret.steeringTorque = cp.vl["EPS_STATUS"]["TORQUE_DRIVER"] ret.steeringTorqueEps = cp.vl["EPS_STATUS"]["TORQUE_MOTOR"] ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 3e02830bf4..946ddce19e 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -2ee969b34585f8055bb3eabab2dcc4061cc4bef9 \ No newline at end of file +a0b5ce7b2e0b9c073e51ac8908402d53e1d99722 \ No newline at end of file From 4db3ca4cf2eca777c1cff7cb5a3010569f6cc7d5 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 28 Jun 2022 20:38:08 -0700 Subject: [PATCH 157/302] Toyota: Add missing 2021 RAV4 TSS2 esp FW (#24989) Add missing Canadian TRD 2021 RAV4 --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 76f84302ce..c7a26257f3 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1262,6 +1262,7 @@ FW_VERSIONS = { b'\x01F152642711\x00\x00\x00\x00\x00\x00', b'\x01F152642750\x00\x00\x00\x00\x00\x00', b'\x01F152642751\x00\x00\x00\x00\x00\x00', + b'\x01F15260R292\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B42170\x00\x00\x00\x00\x00\x00', From e0cd3bf5fc56229c2a0b835d0ef43a0bf683bfa5 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 29 Jun 2022 17:27:37 +0800 Subject: [PATCH 158/302] framereader.cc: remove nv12toyuv_buffer (#24991) remove nv12toyuv_buffer --- tools/replay/framereader.cc | 9 +++------ tools/replay/framereader.h | 1 - 2 files changed, 3 insertions(+), 7 deletions(-) diff --git a/tools/replay/framereader.cc b/tools/replay/framereader.cc index bfa85a0625..ecde9ad5d2 100644 --- a/tools/replay/framereader.cc +++ b/tools/replay/framereader.cc @@ -117,8 +117,6 @@ bool FrameReader::load(const std::byte *data, size_t size, bool no_hw_decoder, s if (has_hw_decoder && !no_hw_decoder) { if (!initHardwareDecoder(HW_DEVICE_TYPE)) { rWarning("No device with hardware decoder found. fallback to CPU decoding."); - } else { - nv12toyuv_buffer.resize(getYUVSize()); } } @@ -227,17 +225,16 @@ AVFrame *FrameReader::decodeFrame(AVPacket *pkt) { } bool FrameReader::copyBuffers(AVFrame *f, uint8_t *yuv) { + assert(f != nullptr && yuv != nullptr); + uint8_t *y = yuv; + uint8_t *uv = y + width * height; if (hw_pix_fmt == HW_PIX_FMT) { - uint8_t *y = yuv ? yuv : nv12toyuv_buffer.data(); - uint8_t *uv = y + width * height; for (int i = 0; i < height/2; i++) { memcpy(y + (i*2 + 0)*width, f->data[0] + (i*2 + 0)*f->linesize[0], width); memcpy(y + (i*2 + 1)*width, f->data[0] + (i*2 + 1)*f->linesize[0], width); memcpy(uv + i*width, f->data[1] + i*f->linesize[1], width); } } else { - uint8_t *y = yuv ? yuv : nv12toyuv_buffer.data(); - uint8_t *uv = y + width * height; libyuv::I420ToNV12(f->data[0], f->linesize[0], f->data[1], f->linesize[1], f->data[2], f->linesize[2], diff --git a/tools/replay/framereader.h b/tools/replay/framereader.h index 10bf34a24e..e50b61d7f4 100644 --- a/tools/replay/framereader.h +++ b/tools/replay/framereader.h @@ -46,7 +46,6 @@ private: AVPixelFormat hw_pix_fmt = AV_PIX_FMT_NONE; AVBufferRef *hw_device_ctx = nullptr; - std::vector nv12toyuv_buffer; int prev_idx = -1; inline static std::atomic has_hw_decoder = true; }; From 67cf20977d8fc250ac9d43261554712e1b74c689 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 29 Jun 2022 11:36:03 +0200 Subject: [PATCH 159/302] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 3fef4f7861..df08568318 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 3fef4f7861e04193fdb11dbd5b0eaf6d2b102ee1 +Subproject commit df08568318da97ed6f87747caee0a5b2c30086c4 From bef5350fa3cc99a79af75a108f50d6a76ce07988 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 29 Jun 2022 12:19:37 +0200 Subject: [PATCH 160/302] don't log LaikadEphemeris in initData --- common/params.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/params.cc b/common/params.cc index b8526bc231..f93c87cd98 100644 --- a/common/params.cc +++ b/common/params.cc @@ -128,7 +128,7 @@ std::unordered_map keys = { {"IsTakingSnapshot", CLEAR_ON_MANAGER_START}, {"IsUpdateAvailable", CLEAR_ON_MANAGER_START}, {"JoystickDebugMode", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF}, - {"LaikadEphemeris", PERSISTENT}, + {"LaikadEphemeris", PERSISTENT | DONT_LOG}, {"LastAthenaPingTime", CLEAR_ON_MANAGER_START}, {"LastGPSPosition", PERSISTENT}, {"LastManagerExitReason", CLEAR_ON_MANAGER_START}, From 879a7c3201a037c27c92ad6b92143114f52f29d3 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 29 Jun 2022 14:47:46 -0700 Subject: [PATCH 161/302] UI: wrap all text for translation (#24961) * rough multiple language demo * more wrappings * stash * add some bad translations * updates * map from french to spanish still has same problem of needing to call setText on everything * add files * restart UI * use return code * relative path * more translations * don't loop restart * Toggle and prime translations * try on device * try QComboBox with readable style * stash * not yet scrollable * stash * dynamic translations (doesn't work for dynamic widget strings yet) * clean up multiple option selector * store languages in json * try transparent * Try transparent popup * see how this looks * tweaks * clean up * clean up * clean up 2 and missing tr * wrap more strings * missing updater * fixes * add basic test to ensure all strings wrapped * try in CI * clean up * test name * fix test * always install qt dev tools * fix deps * fast test * add section so it prints multiple errors * debug * debug get rid of those * make any difference? * comment * oh... * run with offscreen platform * try out section * clean up * fix missing wrappings (it works!) * move down * space * clear relevant params, set TICI=1 --- .github/workflows/selfdrive_tests.yaml | 2 + selfdrive/ui/SConscript | 3 + selfdrive/ui/installer/installer.cc | 8 +- selfdrive/ui/qt/home.cc | 4 +- selfdrive/ui/qt/maps/map_settings.cc | 16 +-- selfdrive/ui/qt/offroad/driverview.cc | 2 +- selfdrive/ui/qt/offroad/networking.cc | 32 ++--- selfdrive/ui/qt/offroad/onboarding.cc | 14 +-- selfdrive/ui/qt/offroad/settings.cc | 110 +++++++++--------- selfdrive/ui/qt/onroad.cc | 14 +-- selfdrive/ui/qt/setup/reset.cc | 18 +-- selfdrive/ui/qt/setup/setup.cc | 42 +++---- selfdrive/ui/qt/setup/updater.cc | 16 +-- selfdrive/ui/qt/sidebar.cc | 16 +-- selfdrive/ui/qt/text.cc | 4 +- selfdrive/ui/qt/util.cc | 8 +- selfdrive/ui/qt/widgets/drive_stats.cc | 8 +- selfdrive/ui/qt/widgets/drive_stats.h | 2 +- selfdrive/ui/qt/widgets/input.cc | 10 +- selfdrive/ui/qt/widgets/offroad_alerts.cc | 6 +- selfdrive/ui/qt/widgets/prime.cc | 28 ++--- selfdrive/ui/qt/widgets/ssh_keys.cc | 18 +-- selfdrive/ui/qt/widgets/ssh_keys.h | 2 +- selfdrive/ui/tests/.gitignore | 1 + .../ui/tests/create_test_translations.sh | 18 +++ selfdrive/ui/tests/test_runner.cc | 19 ++- selfdrive/ui/tests/test_translations.cc | 51 ++++++++ tools/ubuntu_setup.sh | 1 + 28 files changed, 282 insertions(+), 191 deletions(-) create mode 100755 selfdrive/ui/tests/create_test_translations.sh create mode 100644 selfdrive/ui/tests/test_translations.cc diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index a40aa31341..f5edfe5929 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -305,6 +305,8 @@ jobs: $UNIT_TEST selfdrive/hardware/tici && \ $UNIT_TEST selfdrive/modeld && \ $UNIT_TEST tools/lib/tests && \ + ./selfdrive/ui/tests/create_test_translations.sh && \ + QT_QPA_PLATFORM=offscreen ./selfdrive/ui/tests/test_translations && \ ./common/tests/test_util && \ ./common/tests/test_swaglog && \ ./selfdrive/boardd/tests/test_boardd_usbprotocol && \ diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 970f715f54..0835c16372 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -58,6 +58,9 @@ qt_src = ["main.cc", "qt/sidebar.cc", "qt/onroad.cc", "qt/body.cc", "qt/window.cc", "qt/home.cc", "qt/offroad/settings.cc", "qt/offroad/onboarding.cc", "qt/offroad/driverview.cc"] qt_env.Program("_ui", qt_src + [asset_obj], LIBS=qt_libs) +if GetOption('test'): + qt_src.remove("main.cc") # replaced by test_runner + qt_env.Program('tests/test_translations', [asset_obj, 'tests/test_runner.cc', 'tests/test_translations.cc'] + qt_src, LIBS=qt_libs) # setup and factory resetter diff --git a/selfdrive/ui/installer/installer.cc b/selfdrive/ui/installer/installer.cc index 3588026ba6..fe31a2dcb1 100644 --- a/selfdrive/ui/installer/installer.cc +++ b/selfdrive/ui/installer/installer.cc @@ -53,7 +53,7 @@ Installer::Installer(QWidget *parent) : QWidget(parent) { layout->setContentsMargins(150, 290, 150, 150); layout->setSpacing(0); - QLabel *title = new QLabel("Installing..."); + QLabel *title = new QLabel(tr("Installing...")); title->setStyleSheet("font-size: 90px; font-weight: 600;"); layout->addWidget(title, 0, Qt::AlignTop); @@ -141,9 +141,9 @@ void Installer::cachedFetch(const QString &cache) { void Installer::readProgress() { const QVector> stages = { // prefix, weight in percentage - {"Receiving objects: ", 91}, - {"Resolving deltas: ", 2}, - {"Updating files: ", 7}, + {tr("Receiving objects: "), 91}, + {tr("Resolving deltas: "), 2}, + {tr("Updating files: "), 7}, }; auto line = QString(proc.readAllStandardError()); diff --git a/selfdrive/ui/qt/home.cc b/selfdrive/ui/qt/home.cc index aec9bffbc0..0edeb252b7 100644 --- a/selfdrive/ui/qt/home.cc +++ b/selfdrive/ui/qt/home.cc @@ -111,7 +111,7 @@ OffroadHome::OffroadHome(QWidget* parent) : QFrame(parent) { date = new QLabel(); header_layout->addWidget(date, 1, Qt::AlignHCenter | Qt::AlignLeft); - update_notif = new QPushButton("UPDATE"); + update_notif = new QPushButton(tr("UPDATE")); update_notif->setVisible(false); update_notif->setStyleSheet("background-color: #364DEF;"); QObject::connect(update_notif, &QPushButton::clicked, [=]() { center_layout->setCurrentIndex(1); }); @@ -202,6 +202,6 @@ void OffroadHome::refresh() { update_notif->setVisible(updateAvailable); alert_notif->setVisible(alerts); if (alerts) { - alert_notif->setText(QString::number(alerts) + (alerts > 1 ? " ALERTS" : " ALERT")); + alert_notif->setText(QString::number(alerts) + (alerts > 1 ? tr(" ALERTS") : tr(" ALERT"))); } } diff --git a/selfdrive/ui/qt/maps/map_settings.cc b/selfdrive/ui/qt/maps/map_settings.cc index 674c7fa7cb..eaa8b1f703 100644 --- a/selfdrive/ui/qt/maps/map_settings.cc +++ b/selfdrive/ui/qt/maps/map_settings.cc @@ -59,11 +59,11 @@ MapPanel::MapPanel(QWidget* parent) : QWidget(parent) { current_widget = new QWidget(this); QVBoxLayout *current_layout = new QVBoxLayout(current_widget); - QLabel *title = new QLabel("Current Destination"); + QLabel *title = new QLabel(tr("Current Destination")); title->setStyleSheet("font-size: 55px"); current_layout->addWidget(title); - current_route = new ButtonControl("", "CLEAR"); + current_route = new ButtonControl("", tr("CLEAR")); current_route->setStyleSheet("padding-left: 40px;"); current_layout->addWidget(current_route); QObject::connect(current_route, &ButtonControl::clicked, [=]() { @@ -78,7 +78,7 @@ MapPanel::MapPanel(QWidget* parent) : QWidget(parent) { main_layout->addWidget(current_widget); // Recents - QLabel *recents_title = new QLabel("Recent Destinations"); + QLabel *recents_title = new QLabel(tr("Recent Destinations")); recents_title->setStyleSheet("font-size: 55px"); main_layout->addWidget(recents_title); main_layout->addSpacing(20); @@ -92,7 +92,7 @@ MapPanel::MapPanel(QWidget* parent) : QWidget(parent) { QWidget * no_prime_widget = new QWidget; { QVBoxLayout *no_prime_layout = new QVBoxLayout(no_prime_widget); - QLabel *signup_header = new QLabel("Try the Navigation Beta"); + QLabel *signup_header = new QLabel(tr("Try the Navigation Beta")); signup_header->setStyleSheet(R"(font-size: 75px; color: white; font-weight:600;)"); signup_header->setAlignment(Qt::AlignCenter); @@ -104,7 +104,7 @@ MapPanel::MapPanel(QWidget* parent) : QWidget(parent) { screenshot->setPixmap(pm.scaledToWidth(1080, Qt::SmoothTransformation)); no_prime_layout->addWidget(screenshot, 0, Qt::AlignHCenter); - QLabel *signup = new QLabel("Get turn-by-turn directions displayed and more with a comma \nprime subscription. Sign up now: https://connect.comma.ai"); + QLabel *signup = new QLabel(tr("Get turn-by-turn directions displayed and more with a comma \nprime subscription. Sign up now: https://connect.comma.ai")); signup->setStyleSheet(R"(font-size: 45px; color: white; font-weight:300;)"); signup->setAlignment(Qt::AlignCenter); @@ -161,12 +161,12 @@ void MapPanel::showEvent(QShowEvent *event) { void MapPanel::clear() { home_button->setIcon(QPixmap("../assets/navigation/home_inactive.png")); home_address->setStyleSheet(R"(font-size: 50px; color: grey;)"); - home_address->setText("No home\nlocation set"); + home_address->setText(tr("No home\nlocation set")); home_button->disconnect(); work_button->setIcon(QPixmap("../assets/navigation/work_inactive.png")); work_address->setStyleSheet(R"(font-size: 50px; color: grey;)"); - work_address->setText("No work\nlocation set"); + work_address->setText(tr("No work\nlocation set")); work_button->disconnect(); clearLayout(recent_layout); @@ -279,7 +279,7 @@ void MapPanel::parseResponse(const QString &response, bool success) { } if (!has_recents) { - QLabel *no_recents = new QLabel("no recent destinations"); + QLabel *no_recents = new QLabel(tr("no recent destinations")); no_recents->setStyleSheet(R"(font-size: 50px; color: #9c9c9c)"); recent_layout->addWidget(no_recents); } diff --git a/selfdrive/ui/qt/offroad/driverview.cc b/selfdrive/ui/qt/offroad/driverview.cc index dc9f292df1..5bf70584a1 100644 --- a/selfdrive/ui/qt/offroad/driverview.cc +++ b/selfdrive/ui/qt/offroad/driverview.cc @@ -53,7 +53,7 @@ void DriverViewScene::paintEvent(QPaintEvent* event) { p.setPen(Qt::white); p.setRenderHint(QPainter::TextAntialiasing); configFont(p, "Inter", 100, "Bold"); - p.drawText(geometry(), Qt::AlignCenter, "camera starting"); + p.drawText(geometry(), Qt::AlignCenter, tr("camera starting")); return; } diff --git a/selfdrive/ui/qt/offroad/networking.cc b/selfdrive/ui/qt/offroad/networking.cc index 418ccd3179..536ca495ca 100644 --- a/selfdrive/ui/qt/offroad/networking.cc +++ b/selfdrive/ui/qt/offroad/networking.cc @@ -27,7 +27,7 @@ Networking::Networking(QWidget* parent, bool show_advanced) : QFrame(parent) { QVBoxLayout* vlayout = new QVBoxLayout(wifiScreen); vlayout->setContentsMargins(20, 20, 20, 20); if (show_advanced) { - QPushButton* advancedSettings = new QPushButton("Advanced"); + QPushButton* advancedSettings = new QPushButton(tr("Advanced")); advancedSettings->setObjectName("advanced_btn"); advancedSettings->setStyleSheet("margin-right: 30px;"); advancedSettings->setFixedSize(400, 100); @@ -84,7 +84,7 @@ void Networking::connectToNetwork(const Network &n) { } else if (n.security_type == SecurityType::OPEN) { wifi->connect(n); } else if (n.security_type == SecurityType::WPA) { - QString pass = InputDialog::getText("Enter password", this, "for \"" + n.ssid + "\"", true, 8); + QString pass = InputDialog::getText(tr("Enter password"), this, tr("for \"") + n.ssid + "\"", true, 8); if (!pass.isEmpty()) { wifi->connect(n, pass); } @@ -94,7 +94,7 @@ void Networking::connectToNetwork(const Network &n) { void Networking::wrongPassword(const QString &ssid) { if (wifi->seenNetworks.contains(ssid)) { const Network &n = wifi->seenNetworks.value(ssid); - QString pass = InputDialog::getText("Wrong password", this, "for \"" + n.ssid +"\"", true, 8); + QString pass = InputDialog::getText(tr("Wrong password"), this, tr("for \"") + n.ssid +"\"", true, 8); if (!pass.isEmpty()) { wifi->connect(n, pass); } @@ -118,7 +118,7 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid main_layout->setSpacing(20); // Back button - QPushButton* back = new QPushButton("Back"); + QPushButton* back = new QPushButton(tr("Back")); back->setObjectName("back_btn"); back->setFixedSize(400, 100); connect(back, &QPushButton::clicked, [=]() { emit backPress(); }); @@ -126,14 +126,14 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid ListWidget *list = new ListWidget(this); // Enable tethering layout - tetheringToggle = new ToggleControl("Enable Tethering", "", "", wifi->isTetheringEnabled()); + tetheringToggle = new ToggleControl(tr("Enable Tethering"), "", "", wifi->isTetheringEnabled()); list->addItem(tetheringToggle); QObject::connect(tetheringToggle, &ToggleControl::toggleFlipped, this, &AdvancedNetworking::toggleTethering); // Change tethering password - ButtonControl *editPasswordButton = new ButtonControl("Tethering Password", "EDIT"); + ButtonControl *editPasswordButton = new ButtonControl(tr("Tethering Password"), tr("EDIT")); connect(editPasswordButton, &ButtonControl::clicked, [=]() { - QString pass = InputDialog::getText("Enter new tethering password", this, "", true, 8, wifi->getTetheringPassword()); + QString pass = InputDialog::getText(tr("Enter new tethering password"), this, "", true, 8, wifi->getTetheringPassword()); if (!pass.isEmpty()) { wifi->changeTetheringPassword(pass); } @@ -141,7 +141,7 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid list->addItem(editPasswordButton); // IP address - ipLabel = new LabelControl("IP Address", wifi->ipv4_address); + ipLabel = new LabelControl(tr("IP Address"), wifi->ipv4_address); list->addItem(ipLabel); // SSH keys @@ -150,7 +150,7 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid // Roaming toggle const bool roamingEnabled = params.getBool("GsmRoaming"); - ToggleControl *roamingToggle = new ToggleControl("Enable Roaming", "", "", roamingEnabled); + ToggleControl *roamingToggle = new ToggleControl(tr("Enable Roaming"), "", "", roamingEnabled); QObject::connect(roamingToggle, &SshToggle::toggleFlipped, [=](bool state) { params.putBool("GsmRoaming", state); wifi->updateGsmSettings(state, QString::fromStdString(params.get("GsmApn"))); @@ -158,11 +158,11 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid list->addItem(roamingToggle); // APN settings - ButtonControl *editApnButton = new ButtonControl("APN Setting", "EDIT"); + ButtonControl *editApnButton = new ButtonControl(tr("APN Setting"), tr("EDIT")); connect(editApnButton, &ButtonControl::clicked, [=]() { const bool roamingEnabled = params.getBool("GsmRoaming"); const QString cur_apn = QString::fromStdString(params.get("GsmApn")); - QString apn = InputDialog::getText("Enter APN", this, "leave blank for automatic configuration", false, -1, cur_apn).trimmed(); + QString apn = InputDialog::getText(tr("Enter APN"), this, tr("leave blank for automatic configuration"), false, -1, cur_apn).trimmed(); if (apn.isEmpty()) { params.remove("GsmApn"); @@ -207,7 +207,7 @@ WifiUI::WifiUI(QWidget *parent, WifiManager* wifi) : QWidget(parent), wifi(wifi) checkmark = QPixmap(ASSET_PATH + "offroad/icon_checkmark.svg").scaledToWidth(49, Qt::SmoothTransformation); circled_slash = QPixmap(ASSET_PATH + "img_circled_slash.svg").scaledToWidth(49, Qt::SmoothTransformation); - QLabel *scanning = new QLabel("Scanning for networks..."); + QLabel *scanning = new QLabel(tr("Scanning for networks...")); scanning->setStyleSheet("font-size: 65px;"); main_layout->addWidget(scanning, 0, Qt::AlignCenter); @@ -260,7 +260,7 @@ void WifiUI::refresh() { clearLayout(main_layout); if (wifi->seenNetworks.size() == 0) { - QLabel *scanning = new QLabel("Scanning for networks..."); + QLabel *scanning = new QLabel(tr("Scanning for networks...")); scanning->setStyleSheet("font-size: 65px;"); main_layout->addWidget(scanning, 0, Qt::AlignCenter); return; @@ -286,17 +286,17 @@ void WifiUI::refresh() { hlayout->addWidget(ssidLabel, network.connected == ConnectedType::CONNECTING ? 0 : 1); if (network.connected == ConnectedType::CONNECTING) { - QPushButton *connecting = new QPushButton("CONNECTING..."); + QPushButton *connecting = new QPushButton(tr("CONNECTING...")); connecting->setObjectName("connecting"); hlayout->addWidget(connecting, 2, Qt::AlignLeft); } // Forget button if (wifi->isKnownConnection(network.ssid) && !wifi->isTetheringEnabled()) { - QPushButton *forgetBtn = new QPushButton("FORGET"); + QPushButton *forgetBtn = new QPushButton(tr("FORGET")); forgetBtn->setObjectName("forgetBtn"); QObject::connect(forgetBtn, &QPushButton::clicked, [=]() { - if (ConfirmationDialog::confirm("Forget Wi-Fi Network \"" + QString::fromUtf8(network.ssid) + "\"?", this)) { + if (ConfirmationDialog::confirm(tr("Forget Wi-Fi Network \"") + QString::fromUtf8(network.ssid) + "\"?", this)) { wifi->forgetConnection(network.ssid); } }); diff --git a/selfdrive/ui/qt/offroad/onboarding.cc b/selfdrive/ui/qt/offroad/onboarding.cc index d32cc26e43..77e84293b2 100644 --- a/selfdrive/ui/qt/offroad/onboarding.cc +++ b/selfdrive/ui/qt/offroad/onboarding.cc @@ -76,7 +76,7 @@ void TermsPage::showEvent(QShowEvent *event) { main_layout->setContentsMargins(45, 35, 45, 45); main_layout->setSpacing(0); - QLabel *title = new QLabel("Terms & Conditions"); + QLabel *title = new QLabel(tr("Terms & Conditions")); title->setStyleSheet("font-size: 90px; font-weight: 600;"); main_layout->addWidget(title); @@ -104,11 +104,11 @@ void TermsPage::showEvent(QShowEvent *event) { buttons->setSpacing(45); main_layout->addLayout(buttons); - QPushButton *decline_btn = new QPushButton("Decline"); + QPushButton *decline_btn = new QPushButton(tr("Decline")); buttons->addWidget(decline_btn); QObject::connect(decline_btn, &QPushButton::clicked, this, &TermsPage::declinedTerms); - accept_btn = new QPushButton("Scroll to accept"); + accept_btn = new QPushButton(tr("Scroll to accept")); accept_btn->setEnabled(false); accept_btn->setStyleSheet(R"( QPushButton { @@ -123,7 +123,7 @@ void TermsPage::showEvent(QShowEvent *event) { } void TermsPage::enableAccept() { - accept_btn->setText("Agree"); + accept_btn->setText(tr("Agree")); accept_btn->setEnabled(true); } @@ -137,7 +137,7 @@ void DeclinePage::showEvent(QShowEvent *event) { main_layout->setSpacing(40); QLabel *text = new QLabel(this); - text->setText("You must accept the Terms and Conditions in order to use openpilot."); + text->setText(tr("You must accept the Terms and Conditions in order to use openpilot.")); text->setStyleSheet(R"(font-size: 80px; font-weight: 300; margin: 200px;)"); text->setWordWrap(true); main_layout->addWidget(text, 0, Qt::AlignCenter); @@ -146,12 +146,12 @@ void DeclinePage::showEvent(QShowEvent *event) { buttons->setSpacing(45); main_layout->addLayout(buttons); - QPushButton *back_btn = new QPushButton("Back"); + QPushButton *back_btn = new QPushButton(tr("Back")); buttons->addWidget(back_btn); QObject::connect(back_btn, &QPushButton::clicked, this, &DeclinePage::getBack); - QPushButton *uninstall_btn = new QPushButton(QString("Decline, uninstall %1").arg(getBrand())); + QPushButton *uninstall_btn = new QPushButton(QString(tr("Decline, uninstall %1")).arg(getBrand())); uninstall_btn->setStyleSheet("background-color: #B73D3D"); buttons->addWidget(uninstall_btn); QObject::connect(uninstall_btn, &QPushButton::clicked, [=]() { diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 175e6cf5a3..392287d65d 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -29,45 +29,45 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { std::vector> toggles{ { "OpenpilotEnabledToggle", - "Enable openpilot", - "Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off.", + tr("Enable openpilot"), + tr("Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off."), "../assets/offroad/icon_openpilot.png", }, { "IsLdwEnabled", - "Enable Lane Departure Warnings", - "Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h).", + tr("Enable Lane Departure Warnings"), + tr("Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h)."), "../assets/offroad/icon_warning.png", }, { "IsRHD", - "Enable Right-Hand Drive", - "Allow openpilot to obey left-hand traffic conventions and perform driver monitoring on right driver seat.", + tr("Enable Right-Hand Drive"), + tr("Allow openpilot to obey left-hand traffic conventions and perform driver monitoring on right driver seat."), "../assets/offroad/icon_openpilot_mirrored.png", }, { "IsMetric", - "Use Metric System", - "Display speed in km/h instead of mph.", + tr("Use Metric System"), + tr("Display speed in km/h instead of mph."), "../assets/offroad/icon_metric.png", }, { "RecordFront", - "Record and Upload Driver Camera", - "Upload data from the driver facing camera and help improve the driver monitoring algorithm.", + tr("Record and Upload Driver Camera"), + tr("Upload data from the driver facing camera and help improve the driver monitoring algorithm."), "../assets/offroad/icon_monitoring.png", }, { "DisengageOnAccelerator", - "Disengage On Accelerator Pedal", - "When enabled, pressing the accelerator pedal will disengage openpilot.", + tr("Disengage On Accelerator Pedal"), + tr("When enabled, pressing the accelerator pedal will disengage openpilot."), "../assets/offroad/icon_disengage_on_accelerator.svg", }, #ifdef ENABLE_MAPS { "NavSettingTime24h", - "Show ETA in 24h format", - "Use 24h format instead of am/pm", + tr("Show ETA in 24h format"), + tr("Use 24h format instead of am/pm"), "../assets/offroad/icon_metric.png", }, #endif @@ -79,8 +79,8 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { if (params.getBool("DisableRadar_Allow")) { toggles.push_back({ "DisableRadar", - "openpilot Longitudinal Control", - "openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB!", + tr("openpilot Longitudinal Control"), + tr("openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB!"), "../assets/offroad/icon_speed_limit.png", }); } @@ -95,29 +95,29 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { setSpacing(50); - addItem(new LabelControl("Dongle ID", getDongleId().value_or("N/A"))); - addItem(new LabelControl("Serial", params.get("HardwareSerial").c_str())); + addItem(new LabelControl(tr("Dongle ID"), getDongleId().value_or(tr("N/A")))); + addItem(new LabelControl(tr("Serial"), params.get("HardwareSerial").c_str())); // offroad-only buttons - auto dcamBtn = new ButtonControl("Driver Camera", "PREVIEW", - "Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off)"); + auto dcamBtn = new ButtonControl(tr("Driver Camera"), tr("PREVIEW"), + tr("Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off)")); connect(dcamBtn, &ButtonControl::clicked, [=]() { emit showDriverView(); }); addItem(dcamBtn); - auto resetCalibBtn = new ButtonControl("Reset Calibration", "RESET", " "); + auto resetCalibBtn = new ButtonControl(tr("Reset Calibration"), tr("RESET"), ""); connect(resetCalibBtn, &ButtonControl::showDescription, this, &DevicePanel::updateCalibDescription); connect(resetCalibBtn, &ButtonControl::clicked, [&]() { - if (ConfirmationDialog::confirm("Are you sure you want to reset calibration?", this)) { + if (ConfirmationDialog::confirm(tr("Are you sure you want to reset calibration?"), this)) { params.remove("CalibrationParams"); } }); addItem(resetCalibBtn); if (!params.getBool("Passive")) { - auto retrainingBtn = new ButtonControl("Review Training Guide", "REVIEW", "Review the rules, features, and limitations of openpilot"); + auto retrainingBtn = new ButtonControl(tr("Review Training Guide"), tr("REVIEW"), tr("Review the rules, features, and limitations of openpilot")); connect(retrainingBtn, &ButtonControl::clicked, [=]() { - if (ConfirmationDialog::confirm("Are you sure you want to review the training guide?", this)) { + if (ConfirmationDialog::confirm(tr("Are you sure you want to review the training guide?"), this)) { emit reviewTrainingGuide(); } }); @@ -125,7 +125,7 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { } if (Hardware::TICI()) { - auto regulatoryBtn = new ButtonControl("Regulatory", "VIEW", ""); + auto regulatoryBtn = new ButtonControl(tr("Regulatory"), tr("VIEW"), ""); connect(regulatoryBtn, &ButtonControl::clicked, [=]() { const std::string txt = util::read_file("../assets/offroad/fcc.html"); RichTextDialog::alert(QString::fromStdString(txt), this); @@ -143,12 +143,12 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { QHBoxLayout *power_layout = new QHBoxLayout(); power_layout->setSpacing(30); - QPushButton *reboot_btn = new QPushButton("Reboot"); + QPushButton *reboot_btn = new QPushButton(tr("Reboot")); reboot_btn->setObjectName("reboot_btn"); power_layout->addWidget(reboot_btn); QObject::connect(reboot_btn, &QPushButton::clicked, this, &DevicePanel::reboot); - QPushButton *poweroff_btn = new QPushButton("Power Off"); + QPushButton *poweroff_btn = new QPushButton(tr("Power Off")); poweroff_btn->setObjectName("poweroff_btn"); power_layout->addWidget(poweroff_btn); QObject::connect(poweroff_btn, &QPushButton::clicked, this, &DevicePanel::poweroff); @@ -168,8 +168,8 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { void DevicePanel::updateCalibDescription() { QString desc = - "openpilot requires the device to be mounted within 4° left or right and " - "within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required."; + tr("openpilot requires the device to be mounted within 4° left or right and " + "within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required."); std::string calib_bytes = Params().get("CalibrationParams"); if (!calib_bytes.empty()) { try { @@ -179,9 +179,9 @@ void DevicePanel::updateCalibDescription() { if (calib.getCalStatus() != 0) { double pitch = calib.getRpyCalib()[1] * (180 / M_PI); double yaw = calib.getRpyCalib()[2] * (180 / M_PI); - desc += QString(" Your device is pointed %1° %2 and %3° %4.") - .arg(QString::number(std::abs(pitch), 'g', 1), pitch > 0 ? "down" : "up", - QString::number(std::abs(yaw), 'g', 1), yaw > 0 ? "left" : "right"); + desc += QString(tr(" Your device is pointed %1° %2 and %3° %4.")) + .arg(QString::number(std::abs(pitch), 'g', 1), pitch > 0 ? tr("down") : tr("up"), + QString::number(std::abs(yaw), 'g', 1), yaw > 0 ? tr("left") : tr("right")); } } catch (kj::Exception) { qInfo() << "invalid CalibrationParams"; @@ -192,51 +192,51 @@ void DevicePanel::updateCalibDescription() { void DevicePanel::reboot() { if (!uiState()->engaged()) { - if (ConfirmationDialog::confirm("Are you sure you want to reboot?", this)) { + if (ConfirmationDialog::confirm(tr("Are you sure you want to reboot?"), this)) { // Check engaged again in case it changed while the dialog was open if (!uiState()->engaged()) { Params().putBool("DoReboot", true); } } } else { - ConfirmationDialog::alert("Disengage to Reboot", this); + ConfirmationDialog::alert(tr("Disengage to Reboot"), this); } } void DevicePanel::poweroff() { if (!uiState()->engaged()) { - if (ConfirmationDialog::confirm("Are you sure you want to power off?", this)) { + if (ConfirmationDialog::confirm(tr("Are you sure you want to power off?"), this)) { // Check engaged again in case it changed while the dialog was open if (!uiState()->engaged()) { Params().putBool("DoShutdown", true); } } } else { - ConfirmationDialog::alert("Disengage to Power Off", this); + ConfirmationDialog::alert(tr("Disengage to Power Off"), this); } } SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) { - gitBranchLbl = new LabelControl("Git Branch"); - gitCommitLbl = new LabelControl("Git Commit"); - osVersionLbl = new LabelControl("OS Version"); - versionLbl = new LabelControl("Version", "", QString::fromStdString(params.get("ReleaseNotes")).trimmed()); - lastUpdateLbl = new LabelControl("Last Update Check", "", "The last time openpilot successfully checked for an update. The updater only runs while the car is off."); - updateBtn = new ButtonControl("Check for Update", ""); + gitBranchLbl = new LabelControl(tr("Git Branch")); + gitCommitLbl = new LabelControl(tr("Git Commit")); + osVersionLbl = new LabelControl(tr("OS Version")); + versionLbl = new LabelControl(tr("Version"), "", QString::fromStdString(params.get("ReleaseNotes")).trimmed()); + lastUpdateLbl = new LabelControl(tr("Last Update Check"), "", tr("The last time openpilot successfully checked for an update. The updater only runs while the car is off.")); + updateBtn = new ButtonControl(tr("Check for Update"), ""); connect(updateBtn, &ButtonControl::clicked, [=]() { if (params.getBool("IsOffroad")) { fs_watch->addPath(QString::fromStdString(params.getParamPath("LastUpdateTime"))); fs_watch->addPath(QString::fromStdString(params.getParamPath("UpdateFailedCount"))); - updateBtn->setText("CHECKING"); + updateBtn->setText(tr("CHECKING")); updateBtn->setEnabled(false); } std::system("pkill -1 -f selfdrive.updated"); }); - auto uninstallBtn = new ButtonControl("Uninstall " + getBrand(), "UNINSTALL"); + auto uninstallBtn = new ButtonControl(tr("Uninstall ") + getBrand(), tr("UNINSTALL")); connect(uninstallBtn, &ButtonControl::clicked, [&]() { - if (ConfirmationDialog::confirm("Are you sure you want to uninstall?", this)) { + if (ConfirmationDialog::confirm(tr("Are you sure you want to uninstall?"), this)) { params.putBool("DoUninstall", true); } }); @@ -250,8 +250,8 @@ SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) { fs_watch = new QFileSystemWatcher(this); QObject::connect(fs_watch, &QFileSystemWatcher::fileChanged, [=](const QString path) { if (path.contains("UpdateFailedCount") && std::atoi(params.get("UpdateFailedCount").c_str()) > 0) { - lastUpdateLbl->setText("failed to fetch update"); - updateBtn->setText("CHECK"); + lastUpdateLbl->setText(tr("failed to fetch update")); + updateBtn->setText(tr("CHECK")); updateBtn->setEnabled(true); } else if (path.contains("LastUpdateTime")) { updateLabels(); @@ -272,7 +272,7 @@ void SoftwarePanel::updateLabels() { versionLbl->setText(getBrandVersion()); lastUpdateLbl->setText(lastUpdate); - updateBtn->setText("CHECK"); + updateBtn->setText(tr("CHECK")); updateBtn->setEnabled(true); gitBranchLbl->setText(QString::fromStdString(params.get("GitBranch"))); gitCommitLbl->setText(QString::fromStdString(params.get("GitCommit")).left(10)); @@ -301,7 +301,7 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) { )"); // close button - QPushButton *close_btn = new QPushButton("×"); + QPushButton *close_btn = new QPushButton(tr("×")); close_btn->setStyleSheet(R"( QPushButton { font-size: 140px; @@ -327,15 +327,15 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) { QObject::connect(device, &DevicePanel::showDriverView, this, &SettingsWindow::showDriverView); QList> panels = { - {"Device", device}, - {"Network", network_panel(this)}, - {"Toggles", new TogglesPanel(this)}, - {"Software", new SoftwarePanel(this)}, + {tr("Device"), device}, + {tr("Network"), network_panel(this)}, + {tr("Toggles"), new TogglesPanel(this)}, + {tr("Software"), new SoftwarePanel(this)}, }; #ifdef ENABLE_MAPS auto map_panel = new MapPanel(this); - panels.push_back({"Navigation", map_panel}); + panels.push_back({tr("Navigation"), map_panel}); QObject::connect(map_panel, &MapPanel::closeSettings, this, &SettingsWindow::closeSettings); #endif @@ -367,7 +367,7 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) { nav_btns->addButton(btn); sidebar_layout->addWidget(btn, 0, Qt::AlignRight); - const int lr_margin = name != "Network" ? 50 : 0; // Network panel handles its own margins + const int lr_margin = name != tr("Network") ? 50 : 0; // Network panel handles its own margins panel->setContentsMargins(lr_margin, 25, lr_margin, 25); ScrollView *panel_frame = new ScrollView(panel, this); diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index ecd6d61471..7032fc7518 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -199,7 +199,7 @@ void NvgWindow::updateState(const UIState &s) { setProperty("is_metric", s.scene.is_metric); setProperty("speed", cur_speed); setProperty("setSpeed", set_speed); - setProperty("speedUnit", s.scene.is_metric ? "km/h" : "mph"); + setProperty("speedUnit", s.scene.is_metric ? tr("km/h") : tr("mph")); setProperty("hideDM", cs.getAlertSize() != cereal::ControlsState::AlertSize::NONE); setProperty("status", s.status); @@ -266,10 +266,10 @@ void NvgWindow::drawHud(QPainter &p) { p.setPen(QColor(0xa6, 0xa6, 0xa6, 0xff)); } configFont(p, "Inter", 40, "SemiBold"); - QRect max_rect = getTextRect(p, Qt::AlignCenter, "MAX"); + QRect max_rect = getTextRect(p, Qt::AlignCenter, tr("MAX")); max_rect.moveCenter({set_speed_rect.center().x(), 0}); max_rect.moveTop(set_speed_rect.top() + 27); - p.drawText(max_rect, Qt::AlignCenter, "MAX"); + p.drawText(max_rect, Qt::AlignCenter, tr("MAX")); // Draw set speed if (is_cruise_set) { @@ -313,16 +313,16 @@ void NvgWindow::drawHud(QPainter &p) { // "SPEED" configFont(p, "Inter", 28, "SemiBold"); - QRect text_speed_rect = getTextRect(p, Qt::AlignCenter, "SPEED"); + QRect text_speed_rect = getTextRect(p, Qt::AlignCenter, tr("SPEED")); text_speed_rect.moveCenter({sign_rect.center().x(), 0}); text_speed_rect.moveTop(sign_rect_outer.top() + 22); - p.drawText(text_speed_rect, Qt::AlignCenter, "SPEED"); + p.drawText(text_speed_rect, Qt::AlignCenter, tr("SPEED")); // "LIMIT" - QRect text_limit_rect = getTextRect(p, Qt::AlignCenter, "LIMIT"); + QRect text_limit_rect = getTextRect(p, Qt::AlignCenter, tr("LIMIT")); text_limit_rect.moveCenter({sign_rect.center().x(), 0}); text_limit_rect.moveTop(sign_rect_outer.top() + 51); - p.drawText(text_limit_rect, Qt::AlignCenter, "LIMIT"); + p.drawText(text_limit_rect, Qt::AlignCenter, tr("LIMIT")); // Speed limit value configFont(p, "Inter", 70, "Bold"); diff --git a/selfdrive/ui/qt/setup/reset.cc b/selfdrive/ui/qt/setup/reset.cc index 9ffcf7f6cf..582217c1d7 100644 --- a/selfdrive/ui/qt/setup/reset.cc +++ b/selfdrive/ui/qt/setup/reset.cc @@ -26,16 +26,16 @@ void Reset::doReset() { if (rm == 0 || fmt == 0) { std::system("sudo reboot"); } - body->setText("Reset failed. Reboot to try again."); + body->setText(tr("Reset failed. Reboot to try again.")); rebootBtn->show(); } void Reset::confirm() { - const QString confirm_txt = "Are you sure you want to reset your device?"; + const QString confirm_txt = tr("Are you sure you want to reset your device?"); if (body->text() != confirm_txt) { body->setText(confirm_txt); } else { - body->setText("Resetting device..."); + body->setText(tr("Resetting device...")); rejectBtn->hide(); rebootBtn->hide(); confirmBtn->hide(); @@ -50,13 +50,13 @@ Reset::Reset(bool recover, QWidget *parent) : QWidget(parent) { main_layout->setContentsMargins(45, 220, 45, 45); main_layout->setSpacing(0); - QLabel *title = new QLabel("System Reset"); + QLabel *title = new QLabel(tr("System Reset")); title->setStyleSheet("font-size: 90px; font-weight: 600;"); main_layout->addWidget(title, 0, Qt::AlignTop | Qt::AlignLeft); main_layout->addSpacing(60); - body = new QLabel("System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot."); + body = new QLabel(tr("System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.")); body->setWordWrap(true); body->setStyleSheet("font-size: 80px; font-weight: light;"); main_layout->addWidget(body, 1, Qt::AlignTop | Qt::AlignLeft); @@ -65,11 +65,11 @@ Reset::Reset(bool recover, QWidget *parent) : QWidget(parent) { main_layout->addLayout(blayout); blayout->setSpacing(50); - rejectBtn = new QPushButton("Cancel"); + rejectBtn = new QPushButton(tr("Cancel")); blayout->addWidget(rejectBtn); QObject::connect(rejectBtn, &QPushButton::clicked, QCoreApplication::instance(), &QCoreApplication::quit); - rebootBtn = new QPushButton("Reboot"); + rebootBtn = new QPushButton(tr("Reboot")); blayout->addWidget(rebootBtn); #ifdef __aarch64__ QObject::connect(rebootBtn, &QPushButton::clicked, [=]{ @@ -77,7 +77,7 @@ Reset::Reset(bool recover, QWidget *parent) : QWidget(parent) { }); #endif - confirmBtn = new QPushButton("Confirm"); + confirmBtn = new QPushButton(tr("Confirm")); confirmBtn->setStyleSheet("background-color: #465BEA;"); blayout->addWidget(confirmBtn); QObject::connect(confirmBtn, &QPushButton::clicked, this, &Reset::confirm); @@ -85,7 +85,7 @@ Reset::Reset(bool recover, QWidget *parent) : QWidget(parent) { rejectBtn->setVisible(!recover); rebootBtn->setVisible(recover); if (recover) { - body->setText("Unable to mount data partition. Press confirm to reset your device."); + body->setText(tr("Unable to mount data partition. Press confirm to reset your device.")); } setStyleSheet(R"( diff --git a/selfdrive/ui/qt/setup/setup.cc b/selfdrive/ui/qt/setup/setup.cc index 10a2d05f34..69dafcf741 100644 --- a/selfdrive/ui/qt/setup/setup.cc +++ b/selfdrive/ui/qt/setup/setup.cc @@ -70,13 +70,13 @@ QWidget * Setup::low_voltage() { inner_layout->addWidget(triangle, 0, Qt::AlignTop | Qt::AlignLeft); inner_layout->addSpacing(80); - QLabel *title = new QLabel("WARNING: Low Voltage"); + QLabel *title = new QLabel(tr("WARNING: Low Voltage")); title->setStyleSheet("font-size: 90px; font-weight: 500; color: #FF594F;"); inner_layout->addWidget(title, 0, Qt::AlignTop | Qt::AlignLeft); inner_layout->addSpacing(25); - QLabel *body = new QLabel("Power your device in a car with a harness or proceed at your own risk."); + QLabel *body = new QLabel(tr("Power your device in a car with a harness or proceed at your own risk.")); body->setWordWrap(true); body->setAlignment(Qt::AlignTop | Qt::AlignLeft); body->setStyleSheet("font-size: 80px; font-weight: 300;"); @@ -89,14 +89,14 @@ QWidget * Setup::low_voltage() { blayout->setSpacing(50); main_layout->addLayout(blayout, 0); - QPushButton *poweroff = new QPushButton("Power off"); + QPushButton *poweroff = new QPushButton(tr("Power off")); poweroff->setObjectName("navBtn"); blayout->addWidget(poweroff); QObject::connect(poweroff, &QPushButton::clicked, this, [=]() { Hardware::poweroff(); }); - QPushButton *cont = new QPushButton("Continue"); + QPushButton *cont = new QPushButton(tr("Continue")); cont->setObjectName("navBtn"); blayout->addWidget(cont); QObject::connect(cont, &QPushButton::clicked, this, &Setup::nextPage); @@ -114,12 +114,12 @@ QWidget * Setup::getting_started() { vlayout->setContentsMargins(165, 280, 100, 0); main_layout->addLayout(vlayout); - QLabel *title = new QLabel("Getting Started"); + QLabel *title = new QLabel(tr("Getting Started")); title->setStyleSheet("font-size: 90px; font-weight: 500;"); vlayout->addWidget(title, 0, Qt::AlignTop | Qt::AlignLeft); vlayout->addSpacing(90); - QLabel *desc = new QLabel("Before we get on the road, let’s finish installation and cover some details."); + QLabel *desc = new QLabel(tr("Before we get on the road, let’s finish installation and cover some details.")); desc->setWordWrap(true); desc->setStyleSheet("font-size: 80px; font-weight: 300;"); vlayout->addWidget(desc, 0, Qt::AlignTop | Qt::AlignLeft); @@ -144,7 +144,7 @@ QWidget * Setup::network_setup() { main_layout->setContentsMargins(55, 50, 55, 50); // title - QLabel *title = new QLabel("Connect to Wi-Fi"); + QLabel *title = new QLabel(tr("Connect to Wi-Fi")); title->setStyleSheet("font-size: 90px; font-weight: 500;"); main_layout->addWidget(title, 0, Qt::AlignLeft | Qt::AlignTop); @@ -162,7 +162,7 @@ QWidget * Setup::network_setup() { main_layout->addLayout(blayout); blayout->setSpacing(50); - QPushButton *back = new QPushButton("Back"); + QPushButton *back = new QPushButton(tr("Back")); back->setObjectName("navBtn"); QObject::connect(back, &QPushButton::clicked, this, &Setup::prevPage); blayout->addWidget(back); @@ -179,9 +179,9 @@ QWidget * Setup::network_setup() { cont->setEnabled(success); if (success) { const bool cell = networking->wifi->currentNetworkType() == NetworkType::CELL; - cont->setText(cell ? "Continue without Wi-Fi" : "Continue"); + cont->setText(cell ? tr("Continue without Wi-Fi") : tr("Continue")); } else { - cont->setText("Waiting for internet"); + cont->setText(tr("Waiting for internet")); } repaint(); }); @@ -235,7 +235,7 @@ QWidget * Setup::software_selection() { main_layout->setSpacing(0); // title - QLabel *title = new QLabel("Choose Software to Install"); + QLabel *title = new QLabel(tr("Choose Software to Install")); title->setStyleSheet("font-size: 90px; font-weight: 500;"); main_layout->addWidget(title, 0, Qt::AlignLeft | Qt::AlignTop); @@ -245,12 +245,12 @@ QWidget * Setup::software_selection() { QButtonGroup *group = new QButtonGroup(widget); group->setExclusive(true); - QWidget *dashcam = radio_button("Dashcam", group); + QWidget *dashcam = radio_button(tr("Dashcam"), group); main_layout->addWidget(dashcam); main_layout->addSpacing(30); - QWidget *custom = radio_button("Custom Software", group); + QWidget *custom = radio_button(tr("Custom Software"), group); main_layout->addWidget(custom); main_layout->addStretch(); @@ -260,12 +260,12 @@ QWidget * Setup::software_selection() { main_layout->addLayout(blayout); blayout->setSpacing(50); - QPushButton *back = new QPushButton("Back"); + QPushButton *back = new QPushButton(tr("Back")); back->setObjectName("navBtn"); QObject::connect(back, &QPushButton::clicked, this, &Setup::prevPage); blayout->addWidget(back); - QPushButton *cont = new QPushButton("Continue"); + QPushButton *cont = new QPushButton(tr("Continue")); cont->setObjectName("navBtn"); cont->setEnabled(false); cont->setProperty("primary", true); @@ -278,7 +278,7 @@ QWidget * Setup::software_selection() { }); QString url = DASHCAM_URL; if (group->checkedButton() != dashcam) { - url = InputDialog::getText("Enter URL", this, "for Custom Software"); + url = InputDialog::getText(tr("Enter URL"), this, tr("for Custom Software")); } if (!url.isEmpty()) { QTimer::singleShot(1000, this, [=]() { @@ -300,7 +300,7 @@ QWidget * Setup::software_selection() { QWidget * Setup::downloading() { QWidget *widget = new QWidget(); QVBoxLayout *main_layout = new QVBoxLayout(widget); - QLabel *txt = new QLabel("Downloading..."); + QLabel *txt = new QLabel(tr("Downloading...")); txt->setStyleSheet("font-size: 90px; font-weight: 500;"); main_layout->addWidget(txt, 0, Qt::AlignCenter); return widget; @@ -312,13 +312,13 @@ QWidget * Setup::download_failed() { main_layout->setContentsMargins(55, 225, 55, 55); main_layout->setSpacing(0); - QLabel *title = new QLabel("Download Failed"); + QLabel *title = new QLabel(tr("Download Failed")); title->setStyleSheet("font-size: 90px; font-weight: 500;"); main_layout->addWidget(title, 0, Qt::AlignTop | Qt::AlignLeft); main_layout->addSpacing(67); - QLabel *body = new QLabel("Ensure the entered URL is valid, and the device’s internet connection is good."); + QLabel *body = new QLabel(tr("Ensure the entered URL is valid, and the device’s internet connection is good.")); body->setWordWrap(true); body->setAlignment(Qt::AlignTop | Qt::AlignLeft); body->setStyleSheet("font-size: 80px; font-weight: 300; margin-right: 100px;"); @@ -331,14 +331,14 @@ QWidget * Setup::download_failed() { blayout->setSpacing(50); main_layout->addLayout(blayout, 0); - QPushButton *reboot = new QPushButton("Reboot device"); + QPushButton *reboot = new QPushButton(tr("Reboot device")); reboot->setObjectName("navBtn"); blayout->addWidget(reboot); QObject::connect(reboot, &QPushButton::clicked, this, [=]() { Hardware::reboot(); }); - QPushButton *restart = new QPushButton("Start over"); + QPushButton *restart = new QPushButton(tr("Start over")); restart->setObjectName("navBtn"); restart->setProperty("primary", true); blayout->addWidget(restart); diff --git a/selfdrive/ui/qt/setup/updater.cc b/selfdrive/ui/qt/setup/updater.cc index 6e8189f4ba..fd7148c534 100644 --- a/selfdrive/ui/qt/setup/updater.cc +++ b/selfdrive/ui/qt/setup/updater.cc @@ -20,13 +20,13 @@ Updater::Updater(const QString &updater_path, const QString &manifest_path, QWid QVBoxLayout *layout = new QVBoxLayout(prompt); layout->setContentsMargins(100, 250, 100, 100); - QLabel *title = new QLabel("Update Required"); + QLabel *title = new QLabel(tr("Update Required")); title->setStyleSheet("font-size: 80px; font-weight: bold;"); layout->addWidget(title); layout->addSpacing(75); - QLabel *desc = new QLabel("An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB."); + QLabel *desc = new QLabel(tr("An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB.")); desc->setWordWrap(true); desc->setStyleSheet("font-size: 65px;"); layout->addWidget(desc); @@ -37,14 +37,14 @@ Updater::Updater(const QString &updater_path, const QString &manifest_path, QWid hlayout->setSpacing(30); layout->addLayout(hlayout); - QPushButton *connect = new QPushButton("Connect to Wi-Fi"); + QPushButton *connect = new QPushButton(tr("Connect to Wi-Fi")); connect->setObjectName("navBtn"); QObject::connect(connect, &QPushButton::clicked, [=]() { setCurrentWidget(wifi); }); hlayout->addWidget(connect); - QPushButton *install = new QPushButton("Install"); + QPushButton *install = new QPushButton(tr("Install")); install->setObjectName("navBtn"); install->setStyleSheet("background-color: #465BEA;"); QObject::connect(install, &QPushButton::clicked, this, &Updater::installUpdate); @@ -61,7 +61,7 @@ Updater::Updater(const QString &updater_path, const QString &manifest_path, QWid networking->setStyleSheet("Networking { background-color: #292929; border-radius: 13px; }"); layout->addWidget(networking, 1); - QPushButton *back = new QPushButton("Back"); + QPushButton *back = new QPushButton(tr("Back")); back->setObjectName("navBtn"); back->setStyleSheet("padding-left: 60px; padding-right: 60px;"); QObject::connect(back, &QPushButton::clicked, [=]() { @@ -77,7 +77,7 @@ Updater::Updater(const QString &updater_path, const QString &manifest_path, QWid layout->setContentsMargins(150, 330, 150, 150); layout->setSpacing(0); - text = new QLabel("Loading..."); + text = new QLabel(tr("Loading...")); text->setStyleSheet("font-size: 90px; font-weight: 600;"); layout->addWidget(text, 0, Qt::AlignTop); @@ -91,7 +91,7 @@ Updater::Updater(const QString &updater_path, const QString &manifest_path, QWid layout->addStretch(); - reboot = new QPushButton("Reboot"); + reboot = new QPushButton(tr("Reboot")); reboot->setObjectName("navBtn"); reboot->setStyleSheet("padding-left: 60px; padding-right: 60px;"); QObject::connect(reboot, &QPushButton::clicked, [=]() { @@ -161,7 +161,7 @@ void Updater::updateFinished(int exitCode, QProcess::ExitStatus exitStatus) { if (exitCode == 0) { Hardware::reboot(); } else { - text->setText("Update failed"); + text->setText(tr("Update failed")); reboot->show(); } } diff --git a/selfdrive/ui/qt/sidebar.cc b/selfdrive/ui/qt/sidebar.cc index 00e72b352c..accab67bf0 100644 --- a/selfdrive/ui/qt/sidebar.cc +++ b/selfdrive/ui/qt/sidebar.cc @@ -64,26 +64,26 @@ void Sidebar::updateState(const UIState &s) { ItemStatus connectStatus; auto last_ping = deviceState.getLastAthenaPingTime(); if (last_ping == 0) { - connectStatus = ItemStatus{{"CONNECT", "OFFLINE"}, warning_color}; + connectStatus = ItemStatus{{tr("CONNECT"), tr("OFFLINE")}, warning_color}; } else { - connectStatus = nanos_since_boot() - last_ping < 80e9 ? ItemStatus{{"CONNECT", "ONLINE"}, good_color} : ItemStatus{{"CONNECT", "ERROR"}, danger_color}; + connectStatus = nanos_since_boot() - last_ping < 80e9 ? ItemStatus{{tr("CONNECT"), tr("ONLINE")}, good_color} : ItemStatus{{tr("CONNECT"), tr("ERROR")}, danger_color}; } setProperty("connectStatus", QVariant::fromValue(connectStatus)); - ItemStatus tempStatus = {{"TEMP", "HIGH"}, danger_color}; + ItemStatus tempStatus = {{tr("TEMP"), tr("HIGH")}, danger_color}; auto ts = deviceState.getThermalStatus(); if (ts == cereal::DeviceState::ThermalStatus::GREEN) { - tempStatus = {{"TEMP", "GOOD"}, good_color}; + tempStatus = {{tr("TEMP"), tr("GOOD")}, good_color}; } else if (ts == cereal::DeviceState::ThermalStatus::YELLOW) { - tempStatus = {{"TEMP", "OK"}, warning_color}; + tempStatus = {{tr("TEMP"), tr("OK")}, warning_color}; } setProperty("tempStatus", QVariant::fromValue(tempStatus)); - ItemStatus pandaStatus = {{"VEHICLE", "ONLINE"}, good_color}; + ItemStatus pandaStatus = {{tr("VEHICLE"), tr("ONLINE")}, good_color}; if (s.scene.pandaType == cereal::PandaState::PandaType::UNKNOWN) { - pandaStatus = {{"NO", "PANDA"}, danger_color}; + pandaStatus = {{tr("NO"), tr("PANDA")}, danger_color}; } else if (s.scene.started && !sm["liveLocationKalman"].getLiveLocationKalman().getGpsOK()) { - pandaStatus = {{"GPS", "SEARCH"}, warning_color}; + pandaStatus = {{tr("GPS"), tr("SEARCH")}, warning_color}; } setProperty("pandaStatus", QVariant::fromValue(pandaStatus)); } diff --git a/selfdrive/ui/qt/text.cc b/selfdrive/ui/qt/text.cc index ac8e7bcd18..21ec5eedcf 100644 --- a/selfdrive/ui/qt/text.cc +++ b/selfdrive/ui/qt/text.cc @@ -33,12 +33,12 @@ int main(int argc, char *argv[]) { QPushButton *btn = new QPushButton(); #ifdef __aarch64__ - btn->setText("Reboot"); + btn->setText(QObject::tr("Reboot")); QObject::connect(btn, &QPushButton::clicked, [=]() { Hardware::reboot(); }); #else - btn->setText("Exit"); + btn->setText(QObject::tr("Exit")); QObject::connect(btn, &QPushButton::clicked, &a, &QApplication::quit); #endif main_layout->addWidget(btn, 0, 0, Qt::AlignRight | Qt::AlignBottom); diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc index 366aa76f49..f82d9bf496 100644 --- a/selfdrive/ui/qt/util.cc +++ b/selfdrive/ui/qt/util.cc @@ -15,7 +15,7 @@ QString getVersion() { } QString getBrand() { - return Params().getBool("Passive") ? "dashcam" : "openpilot"; + return Params().getBool("Passive") ? QObject::tr("dashcam") : QObject::tr("openpilot"); } QString getBrandVersion() { @@ -63,13 +63,13 @@ QString timeAgo(const QDateTime &date) { s = "now"; } else if (diff < 60 * 60) { int minutes = diff / 60; - s = QString("%1 minute%2 ago").arg(minutes).arg(minutes > 1 ? "s" : ""); + s = QString(QObject::tr("%1 minute%2 ago")).arg(minutes).arg(minutes > 1 ? "s" : ""); } else if (diff < 60 * 60 * 24) { int hours = diff / (60 * 60); - s = QString("%1 hour%2 ago").arg(hours).arg(hours > 1 ? "s" : ""); + s = QString(QObject::tr("%1 hour%2 ago")).arg(hours).arg(hours > 1 ? "s" : ""); } else if (diff < 3600 * 24 * 7) { int days = diff / (60 * 60 * 24); - s = QString("%1 day%2 ago").arg(days).arg(days > 1 ? "s" : ""); + s = QString(QObject::tr("%1 day%2 ago")).arg(days).arg(days > 1 ? "s" : ""); } else { s = date.date().toString(); } diff --git a/selfdrive/ui/qt/widgets/drive_stats.cc b/selfdrive/ui/qt/widgets/drive_stats.cc index 61d47db1c3..31009f03ca 100644 --- a/selfdrive/ui/qt/widgets/drive_stats.cc +++ b/selfdrive/ui/qt/widgets/drive_stats.cc @@ -34,16 +34,16 @@ DriveStats::DriveStats(QWidget* parent) : QFrame(parent) { grid_layout->addWidget(labels.distance = newLabel("0", "number"), row, 1, Qt::AlignLeft); grid_layout->addWidget(labels.hours = newLabel("0", "number"), row, 2, Qt::AlignLeft); - grid_layout->addWidget(newLabel("Drives", "unit"), row + 1, 0, Qt::AlignLeft); + grid_layout->addWidget(newLabel((tr("Drives")), "unit"), row + 1, 0, Qt::AlignLeft); grid_layout->addWidget(labels.distance_unit = newLabel(getDistanceUnit(), "unit"), row + 1, 1, Qt::AlignLeft); - grid_layout->addWidget(newLabel("Hours ", "unit"), row + 1, 2, Qt::AlignLeft); + grid_layout->addWidget(newLabel(tr("Hours"), "unit"), row + 1, 2, Qt::AlignLeft); main_layout->addLayout(grid_layout); }; - add_stats_layouts("ALL TIME", all_); + add_stats_layouts(tr("ALL TIME"), all_); main_layout->addStretch(); - add_stats_layouts("PAST WEEK", week_); + add_stats_layouts(tr("PAST WEEK"), week_); if (auto dongleId = getDongleId()) { QString url = CommaApi::BASE_URL + "/v1.1/devices/" + *dongleId + "/stats"; diff --git a/selfdrive/ui/qt/widgets/drive_stats.h b/selfdrive/ui/qt/widgets/drive_stats.h index 9446294516..5e2d96b240 100644 --- a/selfdrive/ui/qt/widgets/drive_stats.h +++ b/selfdrive/ui/qt/widgets/drive_stats.h @@ -12,7 +12,7 @@ public: private: void showEvent(QShowEvent *event) override; void updateStats(); - inline QString getDistanceUnit() const { return metric_ ? "KM" : "Miles"; } + inline QString getDistanceUnit() const { return metric_ ? tr("KM") : tr("Miles"); } bool metric_; QJsonDocument stats_; diff --git a/selfdrive/ui/qt/widgets/input.cc b/selfdrive/ui/qt/widgets/input.cc index 8a5d492804..755ccfe8c5 100644 --- a/selfdrive/ui/qt/widgets/input.cc +++ b/selfdrive/ui/qt/widgets/input.cc @@ -67,7 +67,7 @@ InputDialog::InputDialog(const QString &title, QWidget *parent, const QString &s vlayout->addWidget(sublabel, 1, Qt::AlignTop | Qt::AlignLeft); } - QPushButton* cancel_btn = new QPushButton("Cancel"); + QPushButton* cancel_btn = new QPushButton(tr("Cancel")); cancel_btn->setFixedSize(386, 125); cancel_btn->setStyleSheet(R"( font-size: 48px; @@ -164,7 +164,7 @@ void InputDialog::handleEnter() { done(QDialog::Accepted); emitText(line->text()); } else { - setMessage("Need at least "+QString::number(minLength)+" characters!", false); + setMessage(tr("Need at least ") + QString::number(minLength) + tr(" characters!"), false); } } @@ -217,12 +217,12 @@ ConfirmationDialog::ConfirmationDialog(const QString &prompt_text, const QString } bool ConfirmationDialog::alert(const QString &prompt_text, QWidget *parent) { - ConfirmationDialog d = ConfirmationDialog(prompt_text, "Ok", "", parent); + ConfirmationDialog d = ConfirmationDialog(prompt_text, tr("Ok"), "", parent); return d.exec(); } bool ConfirmationDialog::confirm(const QString &prompt_text, QWidget *parent) { - ConfirmationDialog d = ConfirmationDialog(prompt_text, "Ok", "Cancel", parent); + ConfirmationDialog d = ConfirmationDialog(prompt_text, tr("Ok"), tr("Cancel"), parent); return d.exec(); } @@ -254,6 +254,6 @@ RichTextDialog::RichTextDialog(const QString &prompt_text, const QString &btn_te } bool RichTextDialog::alert(const QString &prompt_text, QWidget *parent) { - auto d = RichTextDialog(prompt_text, "Ok", parent); + auto d = RichTextDialog(prompt_text, tr("Ok"), parent); return d.exec(); } diff --git a/selfdrive/ui/qt/widgets/offroad_alerts.cc b/selfdrive/ui/qt/widgets/offroad_alerts.cc index 433193df5d..937ea02f86 100644 --- a/selfdrive/ui/qt/widgets/offroad_alerts.cc +++ b/selfdrive/ui/qt/widgets/offroad_alerts.cc @@ -22,12 +22,12 @@ AbstractAlert::AbstractAlert(bool hasRebootBtn, QWidget *parent) : QFrame(parent QHBoxLayout *footer_layout = new QHBoxLayout(); main_layout->addLayout(footer_layout); - QPushButton *dismiss_btn = new QPushButton("Close"); + QPushButton *dismiss_btn = new QPushButton(tr("Close")); dismiss_btn->setFixedSize(400, 125); footer_layout->addWidget(dismiss_btn, 0, Qt::AlignBottom | Qt::AlignLeft); QObject::connect(dismiss_btn, &QPushButton::clicked, this, &AbstractAlert::dismiss); - snooze_btn = new QPushButton("Snooze Update"); + snooze_btn = new QPushButton(tr("Snooze Update")); snooze_btn->setVisible(false); snooze_btn->setFixedSize(550, 125); footer_layout->addWidget(snooze_btn, 0, Qt::AlignBottom | Qt::AlignRight); @@ -38,7 +38,7 @@ AbstractAlert::AbstractAlert(bool hasRebootBtn, QWidget *parent) : QFrame(parent snooze_btn->setStyleSheet(R"(color: white; background-color: #4F4F4F;)"); if (hasRebootBtn) { - QPushButton *rebootBtn = new QPushButton("Reboot and Update"); + QPushButton *rebootBtn = new QPushButton(tr("Reboot and Update")); rebootBtn->setFixedSize(600, 125); footer_layout->addWidget(rebootBtn, 0, Qt::AlignBottom | Qt::AlignRight); QObject::connect(rebootBtn, &QPushButton::clicked, [=]() { Hardware::reboot(); }); diff --git a/selfdrive/ui/qt/widgets/prime.cc b/selfdrive/ui/qt/widgets/prime.cc index 8a208bf3cf..d2529821f4 100644 --- a/selfdrive/ui/qt/widgets/prime.cc +++ b/selfdrive/ui/qt/widgets/prime.cc @@ -83,18 +83,18 @@ PairingPopup::PairingPopup(QWidget *parent) : QDialogBase(parent) { vlayout->addSpacing(30); - QLabel *title = new QLabel("Pair your device to your comma account", this); + QLabel *title = new QLabel(tr("Pair your device to your comma account"), this); title->setStyleSheet("font-size: 75px; color: black;"); title->setWordWrap(true); vlayout->addWidget(title); - QLabel *instructions = new QLabel(R"( + QLabel *instructions = new QLabel(tr(R"(

  1. Go to https://connect.comma.ai on your phone
  2. Click "add new device" and scan the QR code on the right
  3. Bookmark connect.comma.ai to your home screen to use it like an app
- )", this); + )"), this); instructions->setStyleSheet("font-size: 47px; font-weight: bold; color: black;"); instructions->setWordWrap(true); vlayout->addWidget(instructions); @@ -120,19 +120,19 @@ PrimeUserWidget::PrimeUserWidget(QWidget* parent) : QWidget(parent) { primeLayout->setMargin(0); primeWidget->setContentsMargins(60, 50, 60, 50); - QLabel* subscribed = new QLabel("✓ SUBSCRIBED"); + QLabel* subscribed = new QLabel(tr("✓ SUBSCRIBED")); subscribed->setStyleSheet("font-size: 41px; font-weight: bold; color: #86FF4E;"); primeLayout->addWidget(subscribed, 0, Qt::AlignTop); primeLayout->addSpacing(60); - QLabel* commaPrime = new QLabel("comma prime"); + QLabel* commaPrime = new QLabel(tr("comma prime")); commaPrime->setStyleSheet("font-size: 75px; font-weight: bold;"); primeLayout->addWidget(commaPrime, 0, Qt::AlignTop); primeLayout->addSpacing(20); - QLabel* connectUrl = new QLabel("CONNECT.COMMA.AI"); + QLabel* connectUrl = new QLabel(tr("CONNECT.COMMA.AI")); connectUrl->setStyleSheet("font-size: 41px; font-family: Inter SemiBold; color: #A0A0A0;"); primeLayout->addWidget(connectUrl, 0, Qt::AlignTop); @@ -145,7 +145,7 @@ PrimeUserWidget::PrimeUserWidget(QWidget* parent) : QWidget(parent) { pointsLayout->setMargin(0); pointsWidget->setContentsMargins(60, 50, 60, 50); - QLabel* commaPoints = new QLabel("COMMA POINTS"); + QLabel* commaPoints = new QLabel(tr("COMMA POINTS")); commaPoints->setStyleSheet("font-size: 41px; font-family: Inter SemiBold;"); pointsLayout->addWidget(commaPoints, 0, Qt::AlignTop); @@ -181,24 +181,24 @@ PrimeAdWidget::PrimeAdWidget(QWidget* parent) : QFrame(parent) { main_layout->setContentsMargins(80, 90, 80, 60); main_layout->setSpacing(0); - QLabel *upgrade = new QLabel("Upgrade Now"); + QLabel *upgrade = new QLabel(tr("Upgrade Now")); upgrade->setStyleSheet("font-size: 75px; font-weight: bold;"); main_layout->addWidget(upgrade, 0, Qt::AlignTop); main_layout->addSpacing(50); - QLabel *description = new QLabel("Become a comma prime member at connect.comma.ai"); + QLabel *description = new QLabel(tr("Become a comma prime member at connect.comma.ai")); description->setStyleSheet("font-size: 60px; font-weight: light; color: white;"); description->setWordWrap(true); main_layout->addWidget(description, 0, Qt::AlignTop); main_layout->addStretch(); - QLabel *features = new QLabel("PRIME FEATURES:"); + QLabel *features = new QLabel(tr("PRIME FEATURES:")); features->setStyleSheet("font-size: 41px; font-weight: bold; color: #E5E5E5;"); main_layout->addWidget(features, 0, Qt::AlignBottom); main_layout->addSpacing(30); - QVector bullets = {"Remote access", "1 year of storage", "Developer perks"}; + QVector bullets = {tr("Remote access"), tr("1 year of storage"), tr("Developer perks")}; for (auto &b: bullets) { const QString check = " "; QLabel *l = new QLabel(check + b); @@ -227,20 +227,20 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { finishRegistationLayout->setContentsMargins(30, 75, 30, 45); finishRegistationLayout->setSpacing(0); - QLabel* registrationTitle = new QLabel("Finish Setup"); + QLabel* registrationTitle = new QLabel(tr("Finish Setup")); registrationTitle->setStyleSheet("font-size: 75px; font-weight: bold; margin-left: 55px;"); finishRegistationLayout->addWidget(registrationTitle); finishRegistationLayout->addSpacing(30); - QLabel* registrationDescription = new QLabel("Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer."); + QLabel* registrationDescription = new QLabel(tr("Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer.")); registrationDescription->setWordWrap(true); registrationDescription->setStyleSheet("font-size: 55px; font-weight: light; margin-left: 55px;"); finishRegistationLayout->addWidget(registrationDescription); finishRegistationLayout->addStretch(); - QPushButton* pair = new QPushButton("Pair device"); + QPushButton* pair = new QPushButton(tr("Pair device")); pair->setFixedHeight(220); pair->setStyleSheet(R"( QPushButton { diff --git a/selfdrive/ui/qt/widgets/ssh_keys.cc b/selfdrive/ui/qt/widgets/ssh_keys.cc index 46ccf6aee3..1f48c72735 100644 --- a/selfdrive/ui/qt/widgets/ssh_keys.cc +++ b/selfdrive/ui/qt/widgets/ssh_keys.cc @@ -4,16 +4,16 @@ #include "selfdrive/ui/qt/api.h" #include "selfdrive/ui/qt/widgets/input.h" -SshControl::SshControl() : ButtonControl("SSH Keys", "", "Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username.") { +SshControl::SshControl() : ButtonControl(tr("SSH Keys"), "", tr("Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username.")) { username_label.setAlignment(Qt::AlignRight | Qt::AlignVCenter); username_label.setStyleSheet("color: #aaaaaa"); hlayout->insertWidget(1, &username_label); QObject::connect(this, &ButtonControl::clicked, [=]() { - if (text() == "ADD") { - QString username = InputDialog::getText("Enter your GitHub username", this); + if (text() == tr("ADD")) { + QString username = InputDialog::getText(tr("Enter your GitHub username"), this); if (username.length() > 0) { - setText("LOADING"); + setText(tr("LOADING")); setEnabled(false); getUserKeys(username); } @@ -31,10 +31,10 @@ void SshControl::refresh() { QString param = QString::fromStdString(params.get("GithubSshKeys")); if (param.length()) { username_label.setText(QString::fromStdString(params.get("GithubUsername"))); - setText("REMOVE"); + setText(tr("REMOVE")); } else { username_label.setText(""); - setText("ADD"); + setText(tr("ADD")); } setEnabled(true); } @@ -47,13 +47,13 @@ void SshControl::getUserKeys(const QString &username) { params.put("GithubUsername", username.toStdString()); params.put("GithubSshKeys", resp.toStdString()); } else { - ConfirmationDialog::alert(QString("Username '%1' has no keys on GitHub").arg(username), this); + ConfirmationDialog::alert(QString(tr("Username '%1' has no keys on GitHub")).arg(username), this); } } else { if (request->timeout()) { - ConfirmationDialog::alert("Request timed out", this); + ConfirmationDialog::alert(tr("Request timed out"), this); } else { - ConfirmationDialog::alert(QString("Username '%1' doesn't exist on GitHub").arg(username), this); + ConfirmationDialog::alert(QString(tr("Username '%1' doesn't exist on GitHub")).arg(username), this); } } diff --git a/selfdrive/ui/qt/widgets/ssh_keys.h b/selfdrive/ui/qt/widgets/ssh_keys.h index 596d1d83b9..01e2ab83ce 100644 --- a/selfdrive/ui/qt/widgets/ssh_keys.h +++ b/selfdrive/ui/qt/widgets/ssh_keys.h @@ -10,7 +10,7 @@ class SshToggle : public ToggleControl { Q_OBJECT public: - SshToggle() : ToggleControl("Enable SSH", "", "", Hardware::get_ssh_enabled()) { + SshToggle() : ToggleControl(tr("Enable SSH"), "", "", Hardware::get_ssh_enabled()) { QObject::connect(this, &SshToggle::toggleFlipped, [=](bool state) { Hardware::set_ssh_enabled(state); }); diff --git a/selfdrive/ui/tests/.gitignore b/selfdrive/ui/tests/.gitignore index 7765bab17d..26335744f3 100644 --- a/selfdrive/ui/tests/.gitignore +++ b/selfdrive/ui/tests/.gitignore @@ -1,3 +1,4 @@ test playsound test_sound +test_translations diff --git a/selfdrive/ui/tests/create_test_translations.sh b/selfdrive/ui/tests/create_test_translations.sh new file mode 100755 index 0000000000..451a3cbfb0 --- /dev/null +++ b/selfdrive/ui/tests/create_test_translations.sh @@ -0,0 +1,18 @@ +#!/bin/bash + +set -e + +UI_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )"/.. +TEST_TEXT="(WRAPPED_SOURCE_TEXT)" +TEST_TS_FILE=$UI_DIR/translations/main_test_en.ts +TEST_QM_FILE=$UI_DIR/translations/main_test_en.qm + +# translation strings +UNFINISHED="<\/translation>" +TRANSLATED="$TEST_TEXT<\/translation>" + +mkdir -p $UI_DIR/translations +rm -f $TEST_TS_FILE $TEST_QM_FILE +lupdate -recursive "$UI_DIR" -ts $TEST_TS_FILE +sed -i "s/$UNFINISHED/$TRANSLATED/" $TEST_TS_FILE +lrelease $TEST_TS_FILE diff --git a/selfdrive/ui/tests/test_runner.cc b/selfdrive/ui/tests/test_runner.cc index b20ac86c64..ac63139d17 100644 --- a/selfdrive/ui/tests/test_runner.cc +++ b/selfdrive/ui/tests/test_runner.cc @@ -1,10 +1,25 @@ #define CATCH_CONFIG_RUNNER #include "catch2/catch.hpp" -#include + +#include +#include +#include +#include int main(int argc, char **argv) { // unit tests for Qt - QCoreApplication app(argc, argv); + QApplication app(argc, argv); + + QString language_file = "main_test_en"; + qDebug() << "Loading language:" << language_file; + + QTranslator translator; + QString translationsPath = QDir::cleanPath(qApp->applicationDirPath() + "/../translations"); + if (!translator.load(language_file, translationsPath)) { + qDebug() << "Failed to load translation file!"; + } + app.installTranslator(&translator); + const int res = Catch::Session().run(argc, argv); return (res < 0xff ? res : 0xff); } diff --git a/selfdrive/ui/tests/test_translations.cc b/selfdrive/ui/tests/test_translations.cc new file mode 100644 index 0000000000..fecb9da44a --- /dev/null +++ b/selfdrive/ui/tests/test_translations.cc @@ -0,0 +1,51 @@ +#include "catch2/catch.hpp" + +#include "common/params.h" +#include "selfdrive/ui/qt/window.h" + +const QString TEST_TEXT = "(WRAPPED_SOURCE_TEXT)"; // what each string should be translated to +QRegExp RE_NUM("\\d*"); + +QStringList getParentWidgets(QWidget* widget){ + QStringList parentWidgets; + while (widget->parentWidget() != Q_NULLPTR) { + widget = widget->parentWidget(); + parentWidgets.append(widget->metaObject()->className()); + } + return parentWidgets; +} + +template +void checkWidgetTrWrap(MainWindow &w) { + int i = 0; + for (auto widget : w.findChildren()) { + const QString text = widget->text(); + SECTION(text.toStdString() + "-" + std::to_string(i)) { + bool isNumber = RE_NUM.exactMatch(text); + bool wrapped = text.contains(TEST_TEXT); + QString parentWidgets = getParentWidgets(widget).join("->"); + + if (!text.isEmpty() && !isNumber && !wrapped) { + FAIL(("\"" + text + "\" must be wrapped. Parent widgets: " + parentWidgets).toStdString()); + } + + // warn if source string wrapped, but UI adds text + // TODO: add way to ignore this + if (wrapped && text != TEST_TEXT) { + WARN(("\"" + text + "\" is dynamic and needs a custom retranslate function. Parent widgets: " + parentWidgets).toStdString()); + } + } + i++; + } +} + +// Tests all strings in the UI are wrapped with tr() +TEST_CASE("UI: test all strings wrapped") { + Params().remove("HardwareSerial"); + Params().remove("DongleId"); + qputenv("TICI", "1"); + + MainWindow w; + checkWidgetTrWrap(w); + checkWidgetTrWrap(w); +} diff --git a/tools/ubuntu_setup.sh b/tools/ubuntu_setup.sh index 60d41a4771..5bc3630766 100755 --- a/tools/ubuntu_setup.sh +++ b/tools/ubuntu_setup.sh @@ -59,6 +59,7 @@ function install_ubuntu_common_requirements() { qtmultimedia5-dev \ qtlocation5-dev \ qtpositioning5-dev \ + qttools5-dev-tools \ libqt5sql5-sqlite \ libqt5svg5-dev \ libqt5x11extras5-dev \ From f79b068a71607700c4bbcc9e33f1bb2d10bb8e60 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 29 Jun 2022 20:31:22 -0700 Subject: [PATCH 162/302] Honda Civic 2022: remove LKAS fault reinitialization (#24979) * no lkas problem * remove frame --- selfdrive/car/honda/carcontroller.py | 2 +- selfdrive/car/honda/hondacan.py | 4 +--- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index 4d04927b2f..14049c9997 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -241,7 +241,7 @@ class CarController: idx = (self.frame // 10) % 4 hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), hud_control.leadVisible, hud_control.lanesVisible, fcw_display, acc_alert, steer_required) - can_sends.extend(hondacan.create_ui_commands(self.packer, self.CP, CC.enabled, pcm_speed, hud, CS.is_metric, idx, CS.stock_hud, self.frame)) + can_sends.extend(hondacan.create_ui_commands(self.packer, self.CP, CC.enabled, pcm_speed, hud, CS.is_metric, idx, CS.stock_hud)) if self.CP.openpilotLongitudinalControl and self.CP.carFingerprint not in HONDA_BOSCH: self.speed = pcm_speed diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py index 5de29b4f37..7246b98686 100644 --- a/selfdrive/car/honda/hondacan.py +++ b/selfdrive/car/honda/hondacan.py @@ -101,7 +101,7 @@ def create_bosch_supplemental_1(packer, car_fingerprint, idx): return packer.make_can_msg("BOSCH_SUPPLEMENTAL_1", bus, values, idx) -def create_ui_commands(packer, CP, enabled, pcm_speed, hud, is_metric, idx, stock_hud, frame): +def create_ui_commands(packer, CP, enabled, pcm_speed, hud, is_metric, idx, stock_hud): commands = [] bus_pt = get_pt_bus(CP.carFingerprint) radar_disabled = CP.carFingerprint in HONDA_BOSCH and CP.openpilotLongitudinalControl @@ -141,8 +141,6 @@ def create_ui_commands(packer, CP, enabled, pcm_speed, hud, is_metric, idx, stoc if CP.carFingerprint in HONDA_BOSCH_RADARLESS: lkas_hud_values['LANE_LINES'] = 3 lkas_hud_values['DASHED_LANES'] = hud.lanes_visible - # TODO: understand this better, does car need to see it fall after start up? - lkas_hud_values['LKAS_PROBLEM'] = 0 if frame > 200 else 1 if not (CP.flags & HondaFlags.BOSCH_EXT_HUD): lkas_hud_values['SET_ME_X48'] = 0x48 From e643f8e6815eee04511dceecd23b434e5255f15b Mon Sep 17 00:00:00 2001 From: Greg Hogan Date: Thu, 30 Jun 2022 01:52:56 -0700 Subject: [PATCH 163/302] docs: ssh.comma.ai (#25000) --- tools/ssh/README.md | 49 +++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 49 insertions(+) diff --git a/tools/ssh/README.md b/tools/ssh/README.md index 66f030de52..29d3349328 100644 --- a/tools/ssh/README.md +++ b/tools/ssh/README.md @@ -22,3 +22,52 @@ The public keys are only fetched from your GitHub account once. In order to upda The `id_rsa` key in this directory only works while your device is in the setup state with no software installed. After installation, that default key will be removed. See the [community wiki](https://github.com/commaai/openpilot/wiki/SSH) for more detailed instructions and information. + +# Connecting to ssh.comma.ai +SSH into your comma device from anywhere with `ssh.comma.ai`. + +## Setup + +With software version 0.6.1 or newer, enter your GitHub username on your device under Developer Settings. Your GitHub authorized public keys will become your authorized SSH keys for `ssh.comma.ai`. You can add any additional keys in `/system/comma/home/.ssh/authorized_keys.persist`. + +Requires [comma SIM with comma prime](https://comma.ai/shop) activated with comma connect, available on iOS and Android. comma two and EON ship with a pre-inserted comma SIM. + +## Recommended .ssh/config + +With the below ssh configuration, you can type `ssh comma-{dongleid}` to connect to your device through `ssh.comma.ai`. For example, `ssh comma-ffffffffffffffff`. + +``` +Host comma-* + Port 22 + User comma + IdentityFile ~/.ssh/my_github_key + ProxyCommand ssh %h@ssh.comma.ai -W %h:%p +Host ssh.comma.ai + Hostname ssh.comma.ai + Port 22 + IdentityFile ~/.ssh/my_github_key +``` + +## One-off connection + +``` +ssh -i ~/.ssh/my_github_key -o ProxyCommand="ssh -i ~/.ssh/my_github_key -W %h:%p -p %p %h@ssh.comma.ai" comma@ffffffffffffffff +``` +(Replace `ffffffffffffffff` with your dongle_id) + +## ssh.comma.ai host key fingerprint + +``` +Host key fingerprint is SHA256:X22GOmfjGb9J04IA2+egtdaJ7vW9Fbtmpz9/x8/W1X4 ++---[RSA 4096]----+ +| | +| | +| . | +| + o | +| S = + +..| +| + @ = .=| +| . B @ ++=| +| o * B XE| +| .o o OB/| ++----[SHA256]-----+ +``` From 8d53e2c2b4e549119538d1baf36d202dbe33d012 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 30 Jun 2022 16:55:49 +0800 Subject: [PATCH 164/302] Multilang: remove redundant QString() around tr() (#25003) remove qstring --- selfdrive/ui/qt/offroad/onboarding.cc | 2 +- selfdrive/ui/qt/offroad/settings.cc | 2 +- selfdrive/ui/qt/util.cc | 6 +++--- selfdrive/ui/qt/widgets/ssh_keys.cc | 4 ++-- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/selfdrive/ui/qt/offroad/onboarding.cc b/selfdrive/ui/qt/offroad/onboarding.cc index 77e84293b2..f3e50b572b 100644 --- a/selfdrive/ui/qt/offroad/onboarding.cc +++ b/selfdrive/ui/qt/offroad/onboarding.cc @@ -151,7 +151,7 @@ void DeclinePage::showEvent(QShowEvent *event) { QObject::connect(back_btn, &QPushButton::clicked, this, &DeclinePage::getBack); - QPushButton *uninstall_btn = new QPushButton(QString(tr("Decline, uninstall %1")).arg(getBrand())); + QPushButton *uninstall_btn = new QPushButton(tr("Decline, uninstall %1").arg(getBrand())); uninstall_btn->setStyleSheet("background-color: #B73D3D"); buttons->addWidget(uninstall_btn); QObject::connect(uninstall_btn, &QPushButton::clicked, [=]() { diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 392287d65d..547ad168f1 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -179,7 +179,7 @@ void DevicePanel::updateCalibDescription() { if (calib.getCalStatus() != 0) { double pitch = calib.getRpyCalib()[1] * (180 / M_PI); double yaw = calib.getRpyCalib()[2] * (180 / M_PI); - desc += QString(tr(" Your device is pointed %1° %2 and %3° %4.")) + desc += tr(" Your device is pointed %1° %2 and %3° %4.") .arg(QString::number(std::abs(pitch), 'g', 1), pitch > 0 ? tr("down") : tr("up"), QString::number(std::abs(yaw), 'g', 1), yaw > 0 ? tr("left") : tr("right")); } diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc index f82d9bf496..cab7299cd6 100644 --- a/selfdrive/ui/qt/util.cc +++ b/selfdrive/ui/qt/util.cc @@ -63,13 +63,13 @@ QString timeAgo(const QDateTime &date) { s = "now"; } else if (diff < 60 * 60) { int minutes = diff / 60; - s = QString(QObject::tr("%1 minute%2 ago")).arg(minutes).arg(minutes > 1 ? "s" : ""); + s = QObject::tr("%1 minute%2 ago").arg(minutes).arg(minutes > 1 ? "s" : ""); } else if (diff < 60 * 60 * 24) { int hours = diff / (60 * 60); - s = QString(QObject::tr("%1 hour%2 ago")).arg(hours).arg(hours > 1 ? "s" : ""); + s = QObject::tr("%1 hour%2 ago").arg(hours).arg(hours > 1 ? "s" : ""); } else if (diff < 3600 * 24 * 7) { int days = diff / (60 * 60 * 24); - s = QString(QObject::tr("%1 day%2 ago")).arg(days).arg(days > 1 ? "s" : ""); + s = QObject::tr("%1 day%2 ago").arg(days).arg(days > 1 ? "s" : ""); } else { s = date.date().toString(); } diff --git a/selfdrive/ui/qt/widgets/ssh_keys.cc b/selfdrive/ui/qt/widgets/ssh_keys.cc index 1f48c72735..f17604b3e5 100644 --- a/selfdrive/ui/qt/widgets/ssh_keys.cc +++ b/selfdrive/ui/qt/widgets/ssh_keys.cc @@ -47,13 +47,13 @@ void SshControl::getUserKeys(const QString &username) { params.put("GithubUsername", username.toStdString()); params.put("GithubSshKeys", resp.toStdString()); } else { - ConfirmationDialog::alert(QString(tr("Username '%1' has no keys on GitHub")).arg(username), this); + ConfirmationDialog::alert(tr("Username '%1' has no keys on GitHub").arg(username), this); } } else { if (request->timeout()) { ConfirmationDialog::alert(tr("Request timed out"), this); } else { - ConfirmationDialog::alert(QString(tr("Username '%1' doesn't exist on GitHub")).arg(username), this); + ConfirmationDialog::alert(tr("Username '%1' doesn't exist on GitHub").arg(username), this); } } From 867a1cf35a200c10c9ea513140b74be04ce4bb83 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 30 Jun 2022 16:57:47 +0800 Subject: [PATCH 165/302] ui: replace line_vertices_data with QPolygonF (#25001) use QPolygonF use push_front --- selfdrive/ui/qt/onroad.cc | 6 +++--- selfdrive/ui/ui.cc | 20 +++++++------------- selfdrive/ui/ui.h | 12 ++++-------- 3 files changed, 14 insertions(+), 24 deletions(-) diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 7032fc7518..604d3c09a9 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -430,13 +430,13 @@ void NvgWindow::drawLaneLines(QPainter &painter, const UIState *s) { // lanelines for (int i = 0; i < std::size(scene.lane_line_vertices); ++i) { painter.setBrush(QColor::fromRgbF(1.0, 1.0, 1.0, std::clamp(scene.lane_line_probs[i], 0.0, 0.7))); - painter.drawPolygon(scene.lane_line_vertices[i].v, scene.lane_line_vertices[i].cnt); + painter.drawPolygon(scene.lane_line_vertices[i]); } // road edges for (int i = 0; i < std::size(scene.road_edge_vertices); ++i) { painter.setBrush(QColor::fromRgbF(1.0, 0, 0, std::clamp(1.0 - scene.road_edge_stds[i], 0.0, 1.0))); - painter.drawPolygon(scene.road_edge_vertices[i].v, scene.road_edge_vertices[i].cnt); + painter.drawPolygon(scene.road_edge_vertices[i]); } // paint path @@ -455,7 +455,7 @@ void NvgWindow::drawLaneLines(QPainter &painter, const UIState *s) { bg.setColorAt(0.75 / 1.5, QColor::fromHslF(curve_hue / 360., 1.0, 0.68, 0.35)); bg.setColorAt(1.0, QColor::fromHslF(curve_hue / 360., 1.0, 0.68, 0.0)); painter.setBrush(bg); - painter.drawPolygon(scene.track_vertices.v, scene.track_vertices.cnt); + painter.drawPolygon(scene.track_vertices); painter.restore(); } diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index c8fc645cf2..f6193f97a6 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -55,10 +55,13 @@ static void update_leads(UIState *s, const cereal::RadarState::Reader &radar_sta } static void update_line_data(const UIState *s, const cereal::ModelDataV2::XYZTData::Reader &line, - float y_off, float z_off, line_vertices_data *pvd, int max_idx, bool allow_invert=true) { + float y_off, float z_off, QPolygonF *pvd, int max_idx, bool allow_invert=true) { const auto line_x = line.getX(), line_y = line.getY(), line_z = line.getZ(); - std::vector left_points, right_points; + QPolygonF left_points, right_points; + left_points.reserve(max_idx + 1); + right_points.reserve(max_idx + 1); + for (int i = 0; i <= max_idx; i++) { QPointF left, right; bool l = calib_frame_to_full_frame(s, line_x[i], line_y[i] - y_off, line_z[i] + z_off, &left); @@ -69,19 +72,10 @@ static void update_line_data(const UIState *s, const cereal::ModelDataV2::XYZTDa continue; } left_points.push_back(left); - right_points.push_back(right); + right_points.push_front(right); } } - - pvd->cnt = 2 * left_points.size(); - assert(left_points.size() == right_points.size()); - assert(pvd->cnt <= std::size(pvd->v)); - - for (int left_idx = 0; left_idx < left_points.size(); left_idx++){ - int right_idx = 2 * left_points.size() - left_idx - 1; - pvd->v[left_idx] = left_points[left_idx]; - pvd->v[right_idx] = right_points[left_idx]; - } + *pvd = left_points + right_points; } static void update_model(UIState *s, const cereal::ModelDataV2::Reader &model) { diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index 7364b81a40..1aee3df9a1 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -8,6 +8,7 @@ #include #include #include +#include #include #include "cereal/messaging/messaging.h" @@ -84,11 +85,6 @@ const QColor bg_colors [] = { [STATUS_ALERT] = QColor(0xC9, 0x22, 0x31, 0xf1), }; -typedef struct { - QPointF v[TRAJECTORY_SIZE * 2]; - int cnt; -} line_vertices_data; - typedef struct UIScene { bool calibration_valid = false; mat3 view_from_calib = DEFAULT_CALIBRATION; @@ -97,9 +93,9 @@ typedef struct UIScene { // modelV2 float lane_line_probs[4]; float road_edge_stds[2]; - line_vertices_data track_vertices; - line_vertices_data lane_line_vertices[4]; - line_vertices_data road_edge_vertices[2]; + QPolygonF track_vertices; + QPolygonF lane_line_vertices[4]; + QPolygonF road_edge_vertices[2]; // lead QPointF lead_vertices[2]; From b3f4e94169f459fc5cd6ad45fd69baffdef838da Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 30 Jun 2022 16:58:37 +0800 Subject: [PATCH 166/302] remove selfdrive/common (#24997) --- selfdrive/common/tests/.gitignore | 2 -- 1 file changed, 2 deletions(-) delete mode 100644 selfdrive/common/tests/.gitignore diff --git a/selfdrive/common/tests/.gitignore b/selfdrive/common/tests/.gitignore deleted file mode 100644 index 1350b3b825..0000000000 --- a/selfdrive/common/tests/.gitignore +++ /dev/null @@ -1,2 +0,0 @@ -test_util -test_swaglog From 1ac1fe632f8945a24c12413cfad7aa93fac17f9b Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 30 Jun 2022 16:59:08 +0800 Subject: [PATCH 167/302] swaglog.cc/cloudlog_common: pass json object by reference (#24996) * pass json object by reference * space between functions --- common/swaglog.cc | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/common/swaglog.cc b/common/swaglog.cc index 6b0028326a..22682dc54c 100644 --- a/common/swaglog.cc +++ b/common/swaglog.cc @@ -66,8 +66,9 @@ static void log(int levelnum, const char* filename, int lineno, const char* func char levelnum_c = levelnum; zmq_send(s.sock, (levelnum_c + log_s).c_str(), log_s.length() + 1, ZMQ_NOBLOCK); } + static void cloudlog_common(int levelnum, const char* filename, int lineno, const char* func, - char* msg_buf, json11::Json::object msg_j={}) { + char* msg_buf, const json11::Json::object &msg_j={}) { std::lock_guard lk(s.lock); if (!s.initialized) s.initialize(); From 7178800d844469601cb779d8f76b568ff82ac766 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 30 Jun 2022 02:02:53 -0700 Subject: [PATCH 168/302] Multilang prerequisites (#24999) * some supporting code for multilang * for now just english * test for missing language files * test for checking if ts file is up to date * Skip test if causes exception, other test catches this Test test Should also work should now fail revert rmn * add to files_common * fix files_common * newlines * no need to not update * comment * only english * double quotes * switch around --- .github/workflows/selfdrive_tests.yaml | 1 + release/files_common | 7 ++-- selfdrive/ui/tests/test_translations.py | 50 ++++++++++++++++++++++++ selfdrive/ui/translations/languages.json | 3 ++ selfdrive/ui/update_translations.py | 37 ++++++++++++++++++ 5 files changed, 94 insertions(+), 4 deletions(-) create mode 100755 selfdrive/ui/tests/test_translations.py create mode 100644 selfdrive/ui/translations/languages.json create mode 100755 selfdrive/ui/update_translations.py diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index f5edfe5929..0ff0092b02 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -307,6 +307,7 @@ jobs: $UNIT_TEST tools/lib/tests && \ ./selfdrive/ui/tests/create_test_translations.sh && \ QT_QPA_PLATFORM=offscreen ./selfdrive/ui/tests/test_translations && \ + ./selfdrive/ui/tests/test_translations.py && \ ./common/tests/test_util && \ ./common/tests/test_swaglog && \ ./selfdrive/boardd/tests/test_boardd_usbprotocol && \ diff --git a/release/files_common b/release/files_common index 7e8dbd37a6..acf74e2137 100644 --- a/release/files_common +++ b/release/files_common @@ -60,6 +60,8 @@ release/* tools/lib/* tools/joystick/* +tools/replay/*.cc +tools/replay/*.h selfdrive/__init__.py selfdrive/sentry.py @@ -287,6 +289,7 @@ selfdrive/ui/soundd/*.cc selfdrive/ui/soundd/*.h selfdrive/ui/soundd/soundd selfdrive/ui/soundd/.gitignore +selfdrive/ui/translations/* selfdrive/ui/qt/*.cc selfdrive/ui/qt/*.h @@ -295,10 +298,6 @@ selfdrive/ui/qt/offroad/*.h selfdrive/ui/qt/offroad/*.qml selfdrive/ui/qt/widgets/*.cc selfdrive/ui/qt/widgets/*.h - -tools/replay/*.cc -tools/replay/*.h - selfdrive/ui/qt/maps/*.cc selfdrive/ui/qt/maps/*.h diff --git a/selfdrive/ui/tests/test_translations.py b/selfdrive/ui/tests/test_translations.py new file mode 100755 index 0000000000..ccea748e24 --- /dev/null +++ b/selfdrive/ui/tests/test_translations.py @@ -0,0 +1,50 @@ +#!/usr/bin/env python3 +import json +import os +import unittest + +from selfdrive.ui.update_translations import TRANSLATIONS_DIR, LANGUAGES_FILE, update_translations + + +class TestTranslations(unittest.TestCase): + @classmethod + def setUpClass(cls): + with open(LANGUAGES_FILE, "r") as f: + cls.translation_files = json.load(f) + + def test_missing_translation_files(self): + for name, file in self.translation_files.items(): + with self.subTest(name=name, file=file): + if not len(file): + self.skipTest(f"{name} translation has no file") + + self.assertTrue(os.path.exists(os.path.join(TRANSLATIONS_DIR, f"{file}.ts")), + f"{name} has no XML translation file, run selfdrive/ui/update_translations.py") + self.assertTrue(os.path.exists(os.path.join(TRANSLATIONS_DIR, f"{file}.qm")), + f"{name} has no compiled QM translation file, run selfdrive/ui/update_translations.py --release") + + def test_translations_updated(self): + suffix = "_test" + update_translations(suffix=suffix) + + for name, file in self.translation_files.items(): + with self.subTest(name=name, file=file): + cur_tr_file = os.path.join(TRANSLATIONS_DIR, f"{file}.ts") + new_tr_file = os.path.join(TRANSLATIONS_DIR, f"{file}{suffix}.ts") + + if not len(file): + self.skipTest(f"{name} translation has no file") + elif not os.path.exists(cur_tr_file): + self.skipTest(f"{name} missing translation file") # caught by test_missing_translation_files + + with open(cur_tr_file, "r") as f: + cur_translations = f.read() + with open(new_tr_file, "r") as f: + new_translations = f.read() + + self.assertEqual(cur_translations, new_translations, + f"{name} translation file out of date. Run selfdrive/ui/update_translations.py to update the translation files") + + +if __name__ == "__main__": + unittest.main() diff --git a/selfdrive/ui/translations/languages.json b/selfdrive/ui/translations/languages.json new file mode 100644 index 0000000000..f2f9400d64 --- /dev/null +++ b/selfdrive/ui/translations/languages.json @@ -0,0 +1,3 @@ +{ + "English": "" +} diff --git a/selfdrive/ui/update_translations.py b/selfdrive/ui/update_translations.py new file mode 100755 index 0000000000..5d57fa39d2 --- /dev/null +++ b/selfdrive/ui/update_translations.py @@ -0,0 +1,37 @@ +#!/usr/bin/env python3 +import argparse +import os +import json + +from common.basedir import BASEDIR + +UI_DIR = os.path.join(BASEDIR, "selfdrive", "ui") +TRANSLATIONS_DIR = os.path.join(UI_DIR, "translations") +LANGUAGES_FILE = os.path.join(TRANSLATIONS_DIR, "languages.json") + + +def update_translations(release=False, suffix=""): + with open(LANGUAGES_FILE, "r") as f: + translation_files = json.load(f) + + for name, file in translation_files.items(): + if not len(file): + print(f"{name} has no translation file, skipping...") + continue + + tr_file = os.path.join(TRANSLATIONS_DIR, f"{file}{suffix}.ts") + ret = os.system(f"lupdate -recursive {UI_DIR} -ts {tr_file}") + assert ret == 0 + + if release: + ret = os.system(f"lrelease {tr_file}") + assert ret == 0 + + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description="Update translation files for UI", + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument("--release", action="store_true", help="Create compiled QM translation files used by UI") + args = parser.parse_args() + + update_translations(args.release) From e20d2cfa9b80e41c6af3b7879c15c6df1cfb81c1 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 30 Jun 2022 17:05:49 +0800 Subject: [PATCH 169/302] Camerad: small cleanup (#24992) * remove CameraExpInfo * remove release callback --- system/camerad/cameras/camera_common.cc | 7 ++----- system/camerad/cameras/camera_common.h | 10 +--------- 2 files changed, 3 insertions(+), 14 deletions(-) diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index 34dde9389c..506b3fb995 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -66,11 +66,10 @@ private: bool hdr_; }; -void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType init_rgb_type, VisionStreamType init_yuv_type, release_cb init_release_callback) { +void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType init_rgb_type, VisionStreamType init_yuv_type) { vipc_server = v; this->rgb_type = init_rgb_type; this->yuv_type = init_yuv_type; - this->release_callback = init_release_callback; const CameraInfo *ci = &s->ci; camera_state = s; @@ -169,9 +168,7 @@ bool CameraBuf::acquire() { } void CameraBuf::release() { - if (release_callback) { - release_callback((void*)camera_state, cur_buf_idx); - } + // Empty } void CameraBuf::queue(size_t buf_idx) { diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index 6b483372bb..4695d4e2c9 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -48,8 +48,6 @@ const bool env_disable_driver = getenv("DISABLE_DRIVER") != NULL; const bool env_debug_frames = getenv("DEBUG_FRAMES") != NULL; const bool env_log_raw_frames = getenv("LOG_RAW_FRAMES") != NULL; -typedef void (*release_cb)(void *cookie, int buf_idx); - typedef struct CameraInfo { uint32_t frame_width, frame_height; uint32_t frame_stride; @@ -85,11 +83,6 @@ typedef struct FrameMetadata { float processing_time; } FrameMetadata; -typedef struct CameraExpInfo { - int op_id; - float grey_frac; -} CameraExpInfo; - struct MultiCameraState; struct CameraState; class Debayer; @@ -108,7 +101,6 @@ private: SafeQueue safe_queue; int frame_buf_count; - release_cb release_callback; public: cl_command_queue q; @@ -124,7 +116,7 @@ public: CameraBuf() = default; ~CameraBuf(); - void init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType rgb_type, VisionStreamType yuv_type, release_cb release_callback=nullptr); + void init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType rgb_type, VisionStreamType yuv_type); bool acquire(); void release(); void queue(size_t buf_idx); From d13137a83f2036d436c4bc56b4a65fa6962b519d Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 30 Jun 2022 17:29:25 +0800 Subject: [PATCH 170/302] camerad: reduce cpu usage (#24993) wait for 50ms --- system/camerad/cameras/camera_common.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index 506b3fb995..04f3136485 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -126,7 +126,7 @@ CameraBuf::~CameraBuf() { } bool CameraBuf::acquire() { - if (!safe_queue.try_pop(cur_buf_idx, 1)) return false; + if (!safe_queue.try_pop(cur_buf_idx, 50)) return false; if (camera_bufs_metadata[cur_buf_idx].frame_id == -1) { LOGE("no frame data? wtf"); From 30ddadc8b4d510c824221d2010e4aef853741a92 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 30 Jun 2022 13:25:42 +0200 Subject: [PATCH 171/302] test onroad: lower camerad cpu usage --- selfdrive/test/test_onroad.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index f10c79313b..a7ab55fe2a 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -24,7 +24,7 @@ PROCS = { "selfdrive.controls.controlsd": 35.0, "./loggerd": 10.0, "./encoderd": 12.5, - "./camerad": 16.5, + "./camerad": 14.5, "./locationd": 9.1, "selfdrive.controls.plannerd": 11.7, "./_ui": 19.2, From af7d3c115a4780ad734c3f3a8d0084dd506aefec Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 30 Jun 2022 14:22:55 +0200 Subject: [PATCH 172/302] cameraview.cc: prev_frame_id static -> class member --- selfdrive/ui/qt/widgets/cameraview.cc | 7 +++---- selfdrive/ui/qt/widgets/cameraview.h | 1 + 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 0bc90b5307..305f8a3abb 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -243,13 +243,12 @@ void CameraViewWidget::paintGL() { // } // Log duplicate/dropped frames - static int prev_id = 0; - if (frames[frame_idx].first == prev_id) { + if (frames[frame_idx].first == prev_frame_id) { qInfo() << "Drawing same frame twice" << frames[frame_idx].first; - } else if (frames[frame_idx].first != prev_id + 1) { + } else if (frames[frame_idx].first != prev_frame_id + 1) { qInfo() << "Skipped frame" << frames[frame_idx].first; } - prev_id = frames[frame_idx].first; + prev_frame_id = frames[frame_idx].first; glViewport(0, 0, width(), height()); glBindVertexArray(frame_vao); diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index cc11ec2c27..016522b05c 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -78,6 +78,7 @@ protected: std::deque> frames; uint32_t draw_frame_id = 0; + int prev_frame_id = 0; protected slots: void vipcConnected(VisionIpcClient *vipc_client); From ca800da8951f83892a3593b2203e74be6af53844 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 30 Jun 2022 14:25:32 +0200 Subject: [PATCH 173/302] cameraview.cc: qInfo -> qDebug --- selfdrive/ui/qt/widgets/cameraview.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 305f8a3abb..63d15660a0 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -244,9 +244,9 @@ void CameraViewWidget::paintGL() { // Log duplicate/dropped frames if (frames[frame_idx].first == prev_frame_id) { - qInfo() << "Drawing same frame twice" << frames[frame_idx].first; + qDebug() << "Drawing same frame twice" << frames[frame_idx].first; } else if (frames[frame_idx].first != prev_frame_id + 1) { - qInfo() << "Skipped frame" << frames[frame_idx].first; + qDebug() << "Skipped frame" << frames[frame_idx].first; } prev_frame_id = frames[frame_idx].first; From c49f997be505760a18e85a241e6d45b98952c894 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Thu, 30 Jun 2022 17:39:12 +0200 Subject: [PATCH 174/302] Add laikadOffline subtest to process replay. (#24995) * Add subtests to process replay. Adds laikadOffline subtest * Update cpp. * Update ref * Update ref again * Update ref again * update ref * Fix disabling fetching orbits * Add proc name to event exception * update ref * Update setup_env * Fix offline test and update refs --- selfdrive/locationd/laikad.py | 15 ++++--- .../test/process_replay/process_replay.py | 41 +++++++++++++++---- selfdrive/test/process_replay/ref_commit | 2 +- .../test/process_replay/test_processes.py | 4 +- 4 files changed, 47 insertions(+), 15 deletions(-) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 5098b25d38..d51ac10816 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -1,5 +1,6 @@ #!/usr/bin/env python3 import json +import math import os import time from collections import defaultdict @@ -29,11 +30,12 @@ CACHE_VERSION = 0.1 class Laikad: - def __init__(self, valid_const=("GPS", "GLONASS"), auto_update=False, valid_ephem_types=(EphemerisType.ULTRA_RAPID_ORBIT, EphemerisType.NAV), + def __init__(self, valid_const=("GPS", "GLONASS"), auto_fetch_orbits=True, auto_update=False, valid_ephem_types=(EphemerisType.ULTRA_RAPID_ORBIT, EphemerisType.NAV), save_ephemeris=False, last_known_position=None): self.astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types, clear_old_ephemeris=True) self.gnss_kf = GNSSKalman(GENERATED_DIR, cython=True) + self.auto_fetch_orbits = auto_fetch_orbits self.orbit_fetch_executor: Optional[ProcessPoolExecutor] = None self.orbit_fetch_future: Optional[Future] = None @@ -41,6 +43,7 @@ class Laikad: self.last_cached_t = None self.save_ephemeris = save_ephemeris self.load_cache() + self.posfix_functions = {constellation: get_posfix_sympy_fun(constellation) for constellation in (ConstellationId.GPS, ConstellationId.GLONASS)} self.last_pos_fix = last_known_position if last_known_position is not None else [] self.last_pos_residual = [] @@ -85,7 +88,8 @@ class Laikad: report = ublox_msg.measurementReport if report.gpsWeek > 0: latest_msg_t = GPSTime(report.gpsWeek, report.rcvTow) - self.fetch_orbits(latest_msg_t + SECS_IN_MIN, block) + if self.auto_fetch_orbits: + self.fetch_orbits(latest_msg_t + SECS_IN_MIN, block) new_meas = read_raw_ublox(report) processed_measurements = process_measurements(new_meas, self.astro_dog) @@ -146,8 +150,8 @@ class Laikad: def kf_valid(self, t: float) -> List[bool]: filter_time = self.gnss_kf.filter.get_filter_time() - return [filter_time is not None, - filter_time is not None and abs(t - filter_time) < MAX_TIME_GAP, + return [not math.isnan(filter_time), + abs(t - filter_time) < MAX_TIME_GAP, all(np.isfinite(self.gnss_kf.x[GStates.ECEF_POS]))] def init_gnss_localizer(self, est_pos): @@ -275,7 +279,8 @@ def main(sm=None, pm=None): replay = "REPLAY" in os.environ # todo get last_known_position - laikad = Laikad(save_ephemeris=not replay) + use_internet = "LAIKAD_NO_INTERNET" not in os.environ + laikad = Laikad(save_ephemeris=not replay, auto_fetch_orbits=use_internet) while True: sm.update() diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index def61a10a1..fc83b4b61f 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -27,14 +27,14 @@ TIMEOUT = 15 PROC_REPLAY_DIR = os.path.dirname(os.path.abspath(__file__)) FAKEDATA = os.path.join(PROC_REPLAY_DIR, "fakedata/") -ProcessConfig = namedtuple('ProcessConfig', ['proc_name', 'pub_sub', 'ignore', 'init_callback', 'should_recv_callback', 'tolerance', 'fake_pubsubmaster', 'submaster_config'], defaults=({},)) +ProcessConfig = namedtuple('ProcessConfig', ['proc_name', 'pub_sub', 'ignore', 'init_callback', 'should_recv_callback', 'tolerance', 'fake_pubsubmaster', 'submaster_config', 'environ', 'subtest_name'], defaults=({}, {}, "")) def wait_for_event(evt): if not evt.wait(TIMEOUT): if threading.currentThread().getName() == "MainThread": # tested process likely died. don't let test just hang - raise Exception("Timeout reached. Tested process likely crashed.") + raise Exception(f"Timeout reached. Tested process {os.environ['PROC_NAME']} likely crashed.") else: # done testing this process, let it die sys.exit(0) @@ -190,6 +190,7 @@ def get_car_params(msgs, fsm, can_sock, fingerprint): _, CP = get_car(can, sendcan) Params().put("CarParams", CP.to_bytes()) + def controlsd_rcv_callback(msg, CP, cfg, fsm): # no sendcan until controlsd is initialized socks = [s for s in cfg.pub_sub[msg.which()] if @@ -198,6 +199,7 @@ def controlsd_rcv_callback(msg, CP, cfg, fsm): socks.remove("sendcan") return socks, len(socks) > 0 + def radar_rcv_callback(msg, CP, cfg, fsm): if msg.which() != "can": return [], False @@ -240,7 +242,7 @@ def laika_rcv_callback(msg, CP, cfg, fsm): if msg.ubloxGnss.which() == "measurementReport": return ["gnssMeasurements"], True else: - return [], False + return [], True CONFIGS = [ @@ -345,6 +347,19 @@ CONFIGS = [ tolerance=None, fake_pubsubmaster=False, ), + ProcessConfig( + proc_name="laikad", + subtest_name="Offline", + pub_sub={ + "ubloxGnss": ["gnssMeasurements"], + }, + ignore=["logMonoTime"], + init_callback=get_car_params, + should_recv_callback=laika_rcv_callback, + tolerance=NUMPY_TOLERANCE, + fake_pubsubmaster=True, + environ={"LAIKAD_NO_INTERNET": "1"}, + ), ProcessConfig( proc_name="laikad", pub_sub={ @@ -366,7 +381,8 @@ def replay_process(cfg, lr, fingerprint=None): else: return cpp_replay_process(cfg, lr, fingerprint) -def setup_env(simulation=False, CP=None): + +def setup_env(simulation=False, CP=None, cfg=None): params = Params() params.clear_all() params.put_bool("OpenpilotEnabledToggle", True) @@ -380,6 +396,16 @@ def setup_env(simulation=False, CP=None): os.environ['SKIP_FW_QUERY'] = "" os.environ['FINGERPRINT'] = "" + if cfg is not None: + # Clear all custom processConfig environment variables + for cfg in CONFIGS: + for k, _ in cfg.environ.items(): + if k in os.environ: + del os.environ[k] + + os.environ.update(cfg.environ) + os.environ['PROC_NAME'] = cfg.proc_name + if simulation: os.environ["SIMULATION"] = "1" elif "SIMULATION" in os.environ: @@ -396,6 +422,7 @@ def setup_env(simulation=False, CP=None): os.environ['SKIP_FW_QUERY'] = "1" os.environ['FINGERPRINT'] = CP.carFingerprint + def python_replay_process(cfg, lr, fingerprint=None): sub_sockets = [s for _, sub in cfg.pub_sub.items() for s in sub] pub_sockets = [s for s in cfg.pub_sub.keys() if s != 'can'] @@ -413,10 +440,10 @@ def python_replay_process(cfg, lr, fingerprint=None): if fingerprint is not None: os.environ['SKIP_FW_QUERY'] = "1" os.environ['FINGERPRINT'] = fingerprint - setup_env() + setup_env(cfg=cfg) else: CP = [m for m in lr if m.which() == 'carParams'][0].carParams - setup_env(CP=CP) + setup_env(CP=CP, cfg=cfg) assert(type(managed_processes[cfg.proc_name]) is PythonProcess) managed_processes[cfg.proc_name].prepare() @@ -477,7 +504,7 @@ def cpp_replay_process(cfg, lr, fingerprint=None): log_msgs = [] # We need to fake SubMaster alive since we can't inject a fake clock - setup_env(simulation=True) + setup_env(simulation=True, cfg=cfg) managed_processes[cfg.proc_name].prepare() managed_processes[cfg.proc_name].start() diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 946ddce19e..c3e8eca42d 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -a0b5ce7b2e0b9c073e51ac8908402d53e1d99722 \ No newline at end of file +a9adebff7ce27d6233d443217a30337b761898ee \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 25fbd210cc..4e7ba4a6dd 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -200,11 +200,11 @@ if __name__ == "__main__": if cfg.proc_name not in tested_procs: continue - cur_log_fn = os.path.join(FAKEDATA, f"{segment}_{cfg.proc_name}_{cur_commit}.bz2") + cur_log_fn = os.path.join(FAKEDATA, f"{segment}_{cfg.proc_name}{cfg.subtest_name}_{cur_commit}.bz2") if args.update_refs: # reference logs will not exist if routes were just regenerated ref_log_path = get_url(*segment.rsplit("--", 1)) else: - ref_log_fn = os.path.join(FAKEDATA, f"{segment}_{cfg.proc_name}_{ref_commit}.bz2") + ref_log_fn = os.path.join(FAKEDATA, f"{segment}_{cfg.proc_name}{cfg.subtest_name}_{ref_commit}.bz2") ref_log_path = ref_log_fn if os.path.exists(ref_log_fn) else BASE_URL + os.path.basename(ref_log_fn) dat = None if args.upload_only else log_data[segment] From dd43ae2856e144ec13eff462556d8e681aa57789 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Thu, 30 Jun 2022 14:49:17 -0700 Subject: [PATCH 175/302] Full localizer: Use standard naming conventions (#25007) Use standard naming conventions --- selfdrive/locationd/models/loc_kf.py | 32 ++++++++++++++-------------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/selfdrive/locationd/models/loc_kf.py b/selfdrive/locationd/models/loc_kf.py index 6b08828695..b1ed8599f1 100755 --- a/selfdrive/locationd/models/loc_kf.py +++ b/selfdrive/locationd/models/loc_kf.py @@ -25,15 +25,15 @@ class States(): ODO_SCALE_UNUSED = slice(18, 19) # odometer scale ACCELERATION = slice(19, 22) # Acceleration in device frame in m/s**2 FOCAL_SCALE_UNUSED = slice(22, 23) # focal length scale - IMU_OFFSET = slice(23, 26) # imu offset angles in radians + IMU_FROM_DEVICE_EULER = slice(23, 26) # imu offset angles in radians GLONASS_BIAS = slice(26, 27) # GLONASS bias in m expressed as bias + freq_num*freq_slope GLONASS_FREQ_SLOPE = slice(27, 28) # GLONASS bias in m expressed as bias + freq_num*freq_slope CLOCK_ACCELERATION = slice(28, 29) # clock acceleration in light-meters/s**2, ACCELEROMETER_SCALE_UNUSED = slice(29, 30) # scale of mems accelerometer ACCELEROMETER_BIAS = slice(30, 33) # bias of mems accelerometer # TODO the offset is likely a translation of the sensor, not a rotation of the camera - WIDE_CAM_OFFSET = slice(33, 36) # wide camera offset angles in radians (tici only) - # We curently do not use ACCELEROMETER_SCALE to avoid instability due to too many free variables (ACCELEROMETER_SCALE, ACCELEROMETER_BIAS, IMU_OFFSET). + WIDE_FROM_DEVICE_EULER = slice(33, 36) # wide camera offset angles in radians (tici only) + # We curently do not use ACCELEROMETER_SCALE to avoid instability due to too many free variables (ACCELEROMETER_SCALE, ACCELEROMETER_BIAS, IMU_FROM_DEVICE_EULER). # From experiments we see that ACCELEROMETER_BIAS is more correct than ACCELEROMETER_SCALE # Error-state has different slices because it is an ESKF @@ -47,13 +47,13 @@ class States(): ODO_SCALE_ERR_UNUSED = slice(17, 18) ACCELERATION_ERR = slice(18, 21) FOCAL_SCALE_ERR_UNUSED = slice(21, 22) - IMU_OFFSET_ERR = slice(22, 25) + IMU_FROM_DEVICE_EULER_ERR = slice(22, 25) GLONASS_BIAS_ERR = slice(25, 26) GLONASS_FREQ_SLOPE_ERR = slice(26, 27) CLOCK_ACCELERATION_ERR = slice(27, 28) ACCELEROMETER_SCALE_ERR_UNUSED = slice(28, 29) ACCELEROMETER_BIAS_ERR = slice(29, 32) - WIDE_CAM_OFFSET_ERR = slice(32, 35) + WIDE_FROM_DEVICE_EULER_ERR = slice(32, 35) class LocKalman(): @@ -140,15 +140,15 @@ class LocKalman(): cd = state[States.CLOCK_DRIFT, :] roll_bias, pitch_bias, yaw_bias = state[States.GYRO_BIAS, :] acceleration = state[States.ACCELERATION, :] - imu_angles = state[States.IMU_OFFSET, :] - imu_angles[0, 0] = 0 # not observable enough - imu_angles[2, 0] = 0 # not observable enough + imu_from_device_euler = state[States.IMU_FROM_DEVICE_EULER, :] + imu_from_device_euler[0, 0] = 0 # not observable enough + imu_from_device_euler[2, 0] = 0 # not observable enough glonass_bias = state[States.GLONASS_BIAS, :] glonass_freq_slope = state[States.GLONASS_FREQ_SLOPE, :] ca = state[States.CLOCK_ACCELERATION, :] accel_bias = state[States.ACCELEROMETER_BIAS, :] - wide_cam_angles = state[States.WIDE_CAM_OFFSET, :] - wide_cam_angles[0, 0] = 0 # not observable enough + wide_from_device_euler = state[States.WIDE_FROM_DEVICE_EULER, :] + wide_from_device_euler[0, 0] = 0 # not observable enough dt = sp.Symbol('dt') @@ -273,15 +273,15 @@ class LocKalman(): los_vector[2] * (sat_vz - vz) + cd[0]]) - imu_rot = euler_rotate(*imu_angles) - h_gyro_sym = imu_rot * sp.Matrix([vroll + roll_bias, + imu_from_device = euler_rotate(*imu_from_device_euler) + h_gyro_sym = imu_from_device * sp.Matrix([vroll + roll_bias, vpitch + pitch_bias, vyaw + yaw_bias]) pos = sp.Matrix([x, y, z]) # add 1 for stability, prevent division by 0 gravity = quat_rot.T * ((EARTH_GM / ((x**2 + y**2 + z**2 + 1)**(3.0 / 2.0))) * pos) - h_acc_sym = imu_rot * (gravity + acceleration + accel_bias) + h_acc_sym = imu_from_device * (gravity + acceleration + accel_bias) h_acc_stationary_sym = acceleration h_phone_rot_sym = sp.Matrix([vroll, vpitch, vyaw]) h_relative_motion = sp.Matrix(quat_rot.T * v) @@ -297,7 +297,7 @@ class LocKalman(): [h_phone_rot_sym, ObservationKind.CAMERA_ODO_ROTATION, None], [h_acc_stationary_sym, ObservationKind.NO_ACCEL, None]] - wide_cam_rot = euler_rotate(*wide_cam_angles) + wide_from_device = euler_rotate(*wide_from_device_euler) # MSCKF configuration if N > 0: # experimentally found this is correct value for imx298 with 910 focal length @@ -312,7 +312,7 @@ class LocKalman(): track_pos_sym = sp.Matrix([track_x - x, track_y - y, track_z - z]) track_pos_rot_sym = quat_rot.T * track_pos_sym - track_pos_rot_wide_cam_sym = wide_cam_rot * track_pos_rot_sym + track_pos_rot_wide_cam_sym = wide_from_device * track_pos_rot_sym h_track_sym[-2:, :] = sp.Matrix([focal_scale * (track_pos_rot_sym[1] / track_pos_rot_sym[0]), focal_scale * (track_pos_rot_sym[2] / track_pos_rot_sym[0])]) h_track_wide_cam_sym[-2:, :] = sp.Matrix([focal_scale * (track_pos_rot_wide_cam_sym[1] / track_pos_rot_wide_cam_sym[0]), @@ -329,7 +329,7 @@ class LocKalman(): quat_rot = quat_rotate(*q) track_pos_sym = sp.Matrix([track_x - x, track_y - y, track_z - z]) track_pos_rot_sym = quat_rot.T * track_pos_sym - track_pos_rot_wide_cam_sym = wide_cam_rot * track_pos_rot_sym + track_pos_rot_wide_cam_sym = wide_from_device * track_pos_rot_sym h_track_sym[n * 2:n * 2 + 2, :] = sp.Matrix([focal_scale * (track_pos_rot_sym[1] / track_pos_rot_sym[0]), focal_scale * (track_pos_rot_sym[2] / track_pos_rot_sym[0])]) h_track_wide_cam_sym[n * 2: n * 2 + 2, :] = sp.Matrix([focal_scale * (track_pos_rot_wide_cam_sym[1] / track_pos_rot_wide_cam_sym[0]), From f0062f624260bcbdadeec643c993ac597b73c4fc Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 30 Jun 2022 15:01:52 -0700 Subject: [PATCH 176/302] Toyota: fix BSM detection (#24964) * revert to 1 second * Revert "revert to 1 second" This reverts commit 6ab3f75cb73fdfe254431c479b6d337030b0d538. * Revert "remove toyota can fingerprinting exceptions (#22803)" This reverts commit d8f5e8b7a4b6c9132ce2515a9106aeb971ee2579. fix static analysis * Revert "Revert "remove toyota can fingerprinting exceptions (#22803)"" This reverts commit fc359fc9b2db146d77b6533be9e7434f08a665df. * 1 second for all brands * update refs Co-authored-by: Adeeb Shihadeh --- selfdrive/car/car_helpers.py | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 8c0fd7c90d..7f83732153 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -115,7 +115,7 @@ def fingerprint(logcan, sendcan): finger = gen_empty_fingerprint() candidate_cars = {i: all_legacy_fingerprint_cars() for i in [0, 1]} # attempt fingerprint on both bus 0 and 1 frame = 0 - frame_fingerprint = 25 # 0.25s + frame_fingerprint = 100 # 1s car_fingerprint = None done = False diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index c3e8eca42d..b9ba47e8f7 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -a9adebff7ce27d6233d443217a30337b761898ee \ No newline at end of file +a98dfc72bb4c5624c2223ca65d52b151f419460c \ No newline at end of file From 2027d5311d419addfb67ad94d45a198592b2e459 Mon Sep 17 00:00:00 2001 From: Maxime Desroches Date: Thu, 30 Jun 2022 15:03:15 -0700 Subject: [PATCH 177/302] tools: add support for nv12 in compressed_vipc (#24962) reshape for nv12 --- tools/camerastream/compressed_vipc.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/tools/camerastream/compressed_vipc.py b/tools/camerastream/compressed_vipc.py index 290610e45f..d321d6fd2b 100755 --- a/tools/camerastream/compressed_vipc.py +++ b/tools/camerastream/compressed_vipc.py @@ -73,6 +73,10 @@ def decoder(addr, sock_name, vipc_server, vst, nvidia): continue assert len(frames) == 1 img_yuv = frames[0].to_ndarray(format=av.video.format.VideoFormat('yuv420p')).flatten() + uv_offset = H*W + y = img_yuv[:uv_offset] + uv = img_yuv[uv_offset:].reshape(2, -1).ravel('F') + img_yuv = np.hstack((y, uv)) vipc_server.send(vst, img_yuv.data, cnt, int(time_q[0]*1e9), int(time.monotonic()*1e9)) cnt += 1 From 8b32e1b060e8c2c3c084393a569d4e78992ca598 Mon Sep 17 00:00:00 2001 From: Jason Shuler Date: Thu, 30 Jun 2022 18:26:25 -0400 Subject: [PATCH 178/302] GM: Lower LKA loopback CAN Error timing threshold to accommodate dropped packets (#24927) * LKA loopback timing to 10Hz * Typo Co-authored-by: Willem Melching Co-authored-by: Willem Melching --- selfdrive/car/gm/carstate.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index 48b9f25444..3605dab486 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -133,7 +133,9 @@ class CarState(CarStateBase): ] checks = [ - ("ASCMLKASteeringCmd", 50), + ("ASCMLKASteeringCmd", 10), # 10 Hz is the stock inactive rate (every 100ms). + # While active 50 Hz (every 20 ms) is normal + # EPS will tolerate around 200ms when active before faulting ] return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus.LOOPBACK) From 11b5d51da61cac111fb4e5af3b1df6091d860dfc Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 30 Jun 2022 15:36:40 -0700 Subject: [PATCH 179/302] remove mypy ignore from a few scripts --- selfdrive/debug/check_freq.py | 11 +++++++---- selfdrive/debug/check_lag.py | 4 ++-- selfdrive/debug/check_timings.py | 5 +++-- 3 files changed, 12 insertions(+), 8 deletions(-) diff --git a/selfdrive/debug/check_freq.py b/selfdrive/debug/check_freq.py index 424ad67b6d..b6f3c91bd0 100755 --- a/selfdrive/debug/check_freq.py +++ b/selfdrive/debug/check_freq.py @@ -1,9 +1,9 @@ #!/usr/bin/env python3 -# type: ignore - import argparse import numpy as np from collections import defaultdict, deque +from typing import DefaultDict, Deque + from common.realtime import sec_since_boot import cereal.messaging as messaging @@ -19,8 +19,8 @@ if __name__ == "__main__": socket_names = args.socket sockets = {} - rcv_times = defaultdict(lambda: deque(maxlen=100)) - valids = defaultdict(lambda: deque(maxlen=100)) + rcv_times: DefaultDict[str, Deque[float]] = defaultdict(lambda: deque(maxlen=100)) + valids: DefaultDict[str, Deque[bool]] = defaultdict(lambda: deque(maxlen=100)) t = sec_since_boot() for name in socket_names: @@ -31,6 +31,9 @@ if __name__ == "__main__": while True: for socket in poller.poll(100): msg = messaging.recv_one(socket) + if msg is None: + continue + name = msg.which() t = sec_since_boot() diff --git a/selfdrive/debug/check_lag.py b/selfdrive/debug/check_lag.py index c922642982..141156db91 100755 --- a/selfdrive/debug/check_lag.py +++ b/selfdrive/debug/check_lag.py @@ -1,5 +1,5 @@ #!/usr/bin/env python3 -# type: ignore +from typing import Dict import cereal.messaging as messaging from cereal.services import service_list @@ -10,7 +10,7 @@ TO_CHECK = ['carState'] if __name__ == "__main__": sm = messaging.SubMaster(TO_CHECK) - prev_t = {} + prev_t: Dict[str, float] = {} while True: sm.update() diff --git a/selfdrive/debug/check_timings.py b/selfdrive/debug/check_timings.py index 03e39fd70d..69304f97b5 100755 --- a/selfdrive/debug/check_timings.py +++ b/selfdrive/debug/check_timings.py @@ -1,14 +1,15 @@ #!/usr/bin/env python3 -# type: ignore + import sys import time import numpy as np +from typing import DefaultDict, Deque from collections import defaultdict, deque import cereal.messaging as messaging socks = {s: messaging.sub_sock(s, conflate=False) for s in sys.argv[1:]} -ts = defaultdict(lambda: deque(maxlen=100)) +ts: DefaultDict[str, Deque[float]] = defaultdict(lambda: deque(maxlen=100)) if __name__ == "__main__": while True: From 9279c02258e7ab2f60b4e5ea0198bdcb757bf533 Mon Sep 17 00:00:00 2001 From: Jason Shuler Date: Thu, 30 Jun 2022 18:47:26 -0400 Subject: [PATCH 180/302] GM: prep and cleanup for future ports (#24910) * Interface radarOffCan set, comments * pass pcmCruise value to common events * add transType and networkLoc to iface * carstate use transtype to detect EV * ctrl: limit sends by config * Add clarifying comments for new vals * clean up * comment on new line * these have the same frequency * remove 25hz * add to upper comment * update refs * update refs * move into same block move into same block Co-authored-by: Shane Smiskol --- selfdrive/car/gm/carcontroller.py | 94 ++++++++++++------------ selfdrive/car/gm/carstate.py | 8 +- selfdrive/car/gm/interface.py | 19 +++-- selfdrive/test/process_replay/ref_commit | 2 +- 4 files changed, 67 insertions(+), 56 deletions(-) diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index ae2a188e3f..8ad5049e32 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -8,10 +8,12 @@ from selfdrive.car.gm import gmcan from selfdrive.car.gm.values import DBC, CanBus, CarControllerParams VisualAlert = car.CarControl.HUDControl.VisualAlert +NetworkLocation = car.CarParams.NetworkLocation class CarController: def __init__(self, dbc_name, CP, VM): + self.CP = CP self.start_time = 0. self.apply_steer_last = 0 self.apply_gas = 0 @@ -24,9 +26,9 @@ class CarController: self.params = CarControllerParams() - self.packer_pt = CANPacker(DBC[CP.carFingerprint]['pt']) - self.packer_obj = CANPacker(DBC[CP.carFingerprint]['radar']) - self.packer_ch = CANPacker(DBC[CP.carFingerprint]['chassis']) + self.packer_pt = CANPacker(DBC[self.CP.carFingerprint]['pt']) + self.packer_obj = CANPacker(DBC[self.CP.carFingerprint]['radar']) + self.packer_ch = CANPacker(DBC[self.CP.carFingerprint]['chassis']) def update(self, CC, CS): actuators = CC.actuators @@ -60,48 +62,48 @@ class CarController: can_sends.append(gmcan.create_steering_control(self.packer_pt, CanBus.POWERTRAIN, apply_steer, idx, lkas_enabled)) - # Gas/regen and brakes - all at 25Hz - if (self.frame % 4) == 0: - if not CC.longActive: - # Stock ECU sends max regen when not enabled - self.apply_gas = self.params.MAX_ACC_REGEN - self.apply_brake = 0 - else: - self.apply_gas = int(round(interp(actuators.accel, self.params.GAS_LOOKUP_BP, self.params.GAS_LOOKUP_V))) - self.apply_brake = int(round(interp(actuators.accel, self.params.BRAKE_LOOKUP_BP, self.params.BRAKE_LOOKUP_V))) - - idx = (self.frame // 4) % 4 - - at_full_stop = CC.longActive and CS.out.standstill - near_stop = CC.longActive and (CS.out.vEgo < self.params.NEAR_STOP_BRAKE_PHASE) - # GasRegenCmdActive needs to be 1 to avoid cruise faults. It describes the ACC state, not actuation - can_sends.append(gmcan.create_gas_regen_command(self.packer_pt, CanBus.POWERTRAIN, self.apply_gas, idx, CC.enabled, at_full_stop)) - can_sends.append(gmcan.create_friction_brake_command(self.packer_ch, CanBus.CHASSIS, self.apply_brake, idx, near_stop, at_full_stop)) - - # Send dashboard UI commands (ACC status), 25hz - if (self.frame % 4) == 0: - send_fcw = hud_alert == VisualAlert.fcw - can_sends.append(gmcan.create_acc_dashboard_command(self.packer_pt, CanBus.POWERTRAIN, CC.enabled, - hud_v_cruise * CV.MS_TO_KPH, hud_control.leadVisible, send_fcw)) - - # Radar needs to know current speed and yaw rate (50hz), - # and that ADAS is alive (10hz) - time_and_headlights_step = 10 - tt = self.frame * DT_CTRL - - if self.frame % time_and_headlights_step == 0: - idx = (self.frame // time_and_headlights_step) % 4 - can_sends.append(gmcan.create_adas_time_status(CanBus.OBSTACLE, int((tt - self.start_time) * 60), idx)) - can_sends.append(gmcan.create_adas_headlights_status(self.packer_obj, CanBus.OBSTACLE)) - - speed_and_accelerometer_step = 2 - if self.frame % speed_and_accelerometer_step == 0: - idx = (self.frame // speed_and_accelerometer_step) % 4 - can_sends.append(gmcan.create_adas_steering_status(CanBus.OBSTACLE, idx)) - can_sends.append(gmcan.create_adas_accelerometer_speed_status(CanBus.OBSTACLE, CS.out.vEgo, idx)) - - if self.frame % self.params.ADAS_KEEPALIVE_STEP == 0: - can_sends += gmcan.create_adas_keepalive(CanBus.POWERTRAIN) + if self.CP.openpilotLongitudinalControl: + # Gas/regen, brakes, and UI commands - all at 25Hz + if self.frame % 4 == 0: + if not CC.longActive: + # Stock ECU sends max regen when not enabled + self.apply_gas = self.params.MAX_ACC_REGEN + self.apply_brake = 0 + else: + self.apply_gas = int(round(interp(actuators.accel, self.params.GAS_LOOKUP_BP, self.params.GAS_LOOKUP_V))) + self.apply_brake = int(round(interp(actuators.accel, self.params.BRAKE_LOOKUP_BP, self.params.BRAKE_LOOKUP_V))) + + idx = (self.frame // 4) % 4 + + at_full_stop = CC.longActive and CS.out.standstill + near_stop = CC.longActive and (CS.out.vEgo < self.params.NEAR_STOP_BRAKE_PHASE) + # GasRegenCmdActive needs to be 1 to avoid cruise faults. It describes the ACC state, not actuation + can_sends.append(gmcan.create_gas_regen_command(self.packer_pt, CanBus.POWERTRAIN, self.apply_gas, idx, CC.enabled, at_full_stop)) + can_sends.append(gmcan.create_friction_brake_command(self.packer_ch, CanBus.CHASSIS, self.apply_brake, idx, near_stop, at_full_stop)) + + # Send dashboard UI commands (ACC status) + send_fcw = hud_alert == VisualAlert.fcw + can_sends.append(gmcan.create_acc_dashboard_command(self.packer_pt, CanBus.POWERTRAIN, CC.enabled, + hud_v_cruise * CV.MS_TO_KPH, hud_control.leadVisible, send_fcw)) + + # Radar needs to know current speed and yaw rate (50hz), + # and that ADAS is alive (10hz) + if not self.CP.radarOffCan: + tt = self.frame * DT_CTRL + time_and_headlights_step = 10 + if self.frame % time_and_headlights_step == 0: + idx = (self.frame // time_and_headlights_step) % 4 + can_sends.append(gmcan.create_adas_time_status(CanBus.OBSTACLE, int((tt - self.start_time) * 60), idx)) + can_sends.append(gmcan.create_adas_headlights_status(self.packer_obj, CanBus.OBSTACLE)) + + speed_and_accelerometer_step = 2 + if self.frame % speed_and_accelerometer_step == 0: + idx = (self.frame // speed_and_accelerometer_step) % 4 + can_sends.append(gmcan.create_adas_steering_status(CanBus.OBSTACLE, idx)) + can_sends.append(gmcan.create_adas_accelerometer_speed_status(CanBus.OBSTACLE, CS.out.vEgo, idx)) + + if self.CP.networkLocation == NetworkLocation.gateway and self.frame % self.params.ADAS_KEEPALIVE_STEP == 0: + can_sends += gmcan.create_adas_keepalive(CanBus.POWERTRAIN) # Show green icon when LKA torque is applied, and # alarming orange icon when approaching torque limit. @@ -110,7 +112,7 @@ class CarController: lka_active = CS.lkas_status == 1 lka_critical = lka_active and abs(actuators.steer) > 0.9 lka_icon_status = (lka_active, lka_critical) - if self.frame % self.params.CAMERA_KEEPALIVE_STEP == 0 or lka_icon_status != self.lka_icon_status_last: + if self.CP.networkLocation != NetworkLocation.fwdCamera and (self.frame % self.params.CAMERA_KEEPALIVE_STEP == 0 or lka_icon_status != self.lka_icon_status_last): steer_alert = hud_alert in (VisualAlert.steerRequired, VisualAlert.ldw) can_sends.append(gmcan.create_lka_icon_command(CanBus.SW_GMLAN, lka_active, lka_critical, steer_alert)) self.lka_icon_status_last = lka_icon_status diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index 3605dab486..c28abc6036 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -3,7 +3,9 @@ from common.numpy_fast import mean from opendbc.can.can_define import CANDefine from opendbc.can.parser import CANParser from selfdrive.car.interfaces import CarStateBase -from selfdrive.car.gm.values import DBC, CAR, AccState, CanBus, STEER_THRESHOLD +from selfdrive.car.gm.values import DBC, AccState, CanBus, STEER_THRESHOLD + +TransmissionType = car.CarParams.TransmissionType class CarState(CarStateBase): @@ -35,7 +37,7 @@ class CarState(CarStateBase): ret.brakePressed = pt_cp.vl["EBCMBrakePedalPosition"]["BrakePedalPosition"] >= 10 # Regen braking is braking - if self.car_fingerprint == CAR.VOLT: + if self.CP.transmissionType == TransmissionType.direct: ret.brakePressed = ret.brakePressed or pt_cp.vl["EBCMRegenPaddle"]["RegenPaddle"] != 0 ret.gas = pt_cp.vl["AcceleratorPedal2"]["AcceleratorPedal2"] / 254. @@ -120,7 +122,7 @@ class CarState(CarStateBase): ("EBCMBrakePedalPosition", 100), ] - if CP.carFingerprint == CAR.VOLT: + if CP.transmissionType == TransmissionType.direct: signals.append(("RegenPaddle", "EBCMRegenPaddle")) checks.append(("EBCMRegenPaddle", 50)) diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 9c1744dfb4..282844d095 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -9,6 +9,8 @@ from selfdrive.car.interfaces import CarInterfaceBase ButtonType = car.CarState.ButtonEvent.Type EventName = car.CarEvent.EventName +TransmissionType = car.CarParams.TransmissionType +NetworkLocation = car.CarParams.NetworkLocation BUTTONS_DICT = {CruiseButtons.RES_ACCEL: ButtonType.accelCruise, CruiseButtons.DECEL_SET: ButtonType.decelCruise, CruiseButtons.MAIN: ButtonType.altButton3, CruiseButtons.CANCEL: ButtonType.cancel} @@ -45,7 +47,11 @@ class CarInterface(CarInterfaceBase): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "gm" ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.gm)] - ret.pcmCruise = False # stock cruise control is kept off + ret.pcmCruise = False # For ASCM, stock non-adaptive cruise control is kept off + ret.radarOffCan = False # For ASCM, radar exists + ret.transmissionType = TransmissionType.automatic + # NetworkLocation.gateway: OBD-II harness (typically ASCM), NetworkLocation.fwdCamera: non-ASCM + ret.networkLocation = NetworkLocation.gateway # These cars have been put into dashcam only due to both a lack of users and test coverage. # These cars likely still work fine. Once a user confirms each car works and a test route is @@ -77,17 +83,18 @@ class CarInterface(CarInterfaceBase): ret.minEnableSpeed = 18 * CV.MPH_TO_MS if candidate == CAR.VOLT: + ret.transmissionType = TransmissionType.direct ret.mass = 1607. + STD_CARGO_KG ret.wheelbase = 2.69 ret.steerRatio = 17.7 # Stock 15.7, LiveParameters - tire_stiffness_factor = 0.469 # Stock Michelin Energy Saver A/S, LiveParameters - ret.centerToFront = ret.wheelbase * 0.45 # Volt Gen 1, TODO corner weigh + tire_stiffness_factor = 0.469 # Stock Michelin Energy Saver A/S, LiveParameters + ret.centerToFront = ret.wheelbase * 0.45 # Volt Gen 1, TODO corner weigh ret.lateralTuning.pid.kpBP = [0., 40.] ret.lateralTuning.pid.kpV = [0., 0.17] ret.lateralTuning.pid.kiBP = [0.] ret.lateralTuning.pid.kiV = [0.] - ret.lateralTuning.pid.kf = 1. # get_steer_feedforward_volt() + ret.lateralTuning.pid.kf = 1. # get_steer_feedforward_volt() ret.steerActuatorDelay = 0.2 elif candidate == CAR.MALIBU: @@ -160,7 +167,7 @@ class CarInterface(CarInterfaceBase): ret.buttonEvents = [be] - events = self.create_common_events(ret, pcm_enable=False) + events = self.create_common_events(ret, pcm_enable=self.CP.pcmCruise) if ret.vEgo < self.CP.minEnableSpeed: events.add(EventName.belowEngageSpeed) @@ -170,7 +177,7 @@ class CarInterface(CarInterfaceBase): events.add(car.CarEvent.EventName.belowSteerSpeed) # handle button presses - events.events.extend(create_button_enable_events(ret.buttonEvents)) + events.events.extend(create_button_enable_events(ret.buttonEvents, pcm_cruise=self.CP.pcmCruise)) ret.events = events.to_msg() diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index b9ba47e8f7..a1cb2bf362 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -a98dfc72bb4c5624c2223ca65d52b151f419460c \ No newline at end of file +d7c610172f3ff10b68403abc19b260c91c848ebb \ No newline at end of file From 61d21ff00ae6d4b5f510c5880d2ca747272da754 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 30 Jun 2022 15:52:53 -0700 Subject: [PATCH 181/302] update release notes --- RELEASES.md | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index 5d81b43085..5b71fc3375 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,6 +1,5 @@ -Version 0.8.15 (2022-XX-XX) +Version 0.8.15 (2022-07-XX) ======================== -* New driving model * New lateral controller based on physical wheel torque model * Much smoother control, consistent across the speed range * Effective feedforward that uses road roll @@ -10,8 +9,12 @@ Version 0.8.15 (2022-XX-XX) * takes a larger input frame * outputs a driver state for both driver and passenger * automatically determines which side the driver is on (soon) -* Display speed limit while navigating * Reduced power usage: device runs cooler and fan spins less +* Minor UI updates + * New font + * Refreshed max speed design + * Speed limits shown while navigating + * More consistent camera view perspective across cars * AGNOS 5 * Honda Civic 2022 support * Hyundai Tucson 2021 support thanks to bluesforte! From d2c2154a32db0876036f4f6b61b912de0c90fc5a Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 30 Jun 2022 17:23:12 -0700 Subject: [PATCH 182/302] Clean up CarControllers (#25008) * do VW * Do the rest * unused * ford cc formatting * final clean ups * also just return update output --- selfdrive/car/body/carcontroller.py | 4 +-- selfdrive/car/ford/carcontroller.py | 15 +++++---- selfdrive/car/ford/interface.py | 4 +-- selfdrive/car/gm/carcontroller.py | 2 +- selfdrive/car/gm/interface.py | 3 +- selfdrive/car/hyundai/carcontroller.py | 6 ++-- selfdrive/car/hyundai/interface.py | 3 +- selfdrive/car/mazda/carcontroller.py | 31 ++++++++++-------- selfdrive/car/mazda/interface.py | 4 +-- selfdrive/car/nissan/carcontroller.py | 33 ++++++++++--------- selfdrive/car/nissan/interface.py | 11 ++----- selfdrive/car/subaru/carcontroller.py | 21 +++++++----- selfdrive/car/subaru/interface.py | 10 ++---- selfdrive/car/tesla/interface.py | 3 +- selfdrive/car/toyota/interface.py | 3 +- selfdrive/car/volkswagen/carcontroller.py | 40 +++++++++++++---------- selfdrive/car/volkswagen/interface.py | 10 +----- 17 files changed, 97 insertions(+), 106 deletions(-) diff --git a/selfdrive/car/body/carcontroller.py b/selfdrive/car/body/carcontroller.py index 5714445f67..c13acebacb 100644 --- a/selfdrive/car/body/carcontroller.py +++ b/selfdrive/car/body/carcontroller.py @@ -1,8 +1,8 @@ import numpy as np from common.realtime import DT_CTRL -from selfdrive.car.body import bodycan from opendbc.can.packer import CANPacker +from selfdrive.car.body import bodycan from selfdrive.car.body.values import SPEED_FROM_RPM from selfdrive.controls.lib.pid import PIDController @@ -14,7 +14,7 @@ MAX_POS_INTEGRATOR = 0.2 # meters MAX_TURN_INTEGRATOR = 0.1 # meters -class CarController(): +class CarController: def __init__(self, dbc_name, CP, VM): self.frame = 0 self.packer = CANPacker(dbc_name) diff --git a/selfdrive/car/ford/carcontroller.py b/selfdrive/car/ford/carcontroller.py index c2f87a4806..d7666c1d65 100644 --- a/selfdrive/car/ford/carcontroller.py +++ b/selfdrive/car/ford/carcontroller.py @@ -1,8 +1,8 @@ from cereal import car from common.numpy_fast import clip, interp +from opendbc.can.packer import CANPacker from selfdrive.car.ford import fordcan from selfdrive.car.ford.values import CarControllerParams -from opendbc.can.packer import CANPacker VisualAlert = car.CarControl.HUDControl.VisualAlert @@ -17,11 +17,12 @@ def apply_ford_steer_angle_limits(apply_steer, apply_steer_last, vEgo): return apply_steer -class CarController(): +class CarController: def __init__(self, dbc_name, CP, VM): self.CP = CP self.VM = VM self.packer = CANPacker(dbc_name) + self.frame = 0 self.apply_steer_last = 0 self.steer_rate_limited = False @@ -29,7 +30,7 @@ class CarController(): self.lkas_enabled_last = False self.steer_alert_last = False - def update(self, CC, CS, frame): + def update(self, CC, CS): can_sends = [] actuators = CC.actuators @@ -48,7 +49,7 @@ class CarController(): self.steer_rate_limited = new_steer != apply_steer # send steering commands at 20Hz - if (frame % CarControllerParams.LKAS_STEER_STEP) == 0: + if (self.frame % CarControllerParams.LKAS_STEER_STEP) == 0: lca_rq = 1 if CC.latActive else 0 # use LatCtlPath_An_Actl to actuate steering for now until curvature control is implemented @@ -69,15 +70,14 @@ class CarController(): can_sends.append(fordcan.create_tja_command(self.packer, lca_rq, ramp_type, precision, path_offset, path_angle, curvature_rate, curvature)) - send_ui = (self.main_on_last != main_on) or (self.lkas_enabled_last != CC.latActive) or (self.steer_alert_last != steer_alert) # send lkas ui command at 1Hz or if ui state changes - if (frame % CarControllerParams.LKAS_UI_STEP) == 0 or send_ui: + if (self.frame % CarControllerParams.LKAS_UI_STEP) == 0 or send_ui: can_sends.append(fordcan.create_lkas_ui_command(self.packer, main_on, CC.latActive, steer_alert, CS.lkas_status_stock_values)) # send acc ui command at 20Hz or if ui state changes - if (frame % CarControllerParams.ACC_UI_STEP) == 0 or send_ui: + if (self.frame % CarControllerParams.ACC_UI_STEP) == 0 or send_ui: can_sends.append(fordcan.create_acc_ui_command(self.packer, main_on, CC.latActive, CS.acc_tja_status_stock_values)) self.main_on_last = main_on @@ -87,4 +87,5 @@ class CarController(): new_actuators = actuators.copy() new_actuators.steeringAngleDeg = apply_steer + self.frame += 1 return new_actuators, can_sends diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py index c608cc08d9..1af04bee41 100644 --- a/selfdrive/car/ford/interface.py +++ b/selfdrive/car/ford/interface.py @@ -78,6 +78,4 @@ class CarInterface(CarInterfaceBase): return ret def apply(self, c): - ret = self.CC.update(c, self.CS, self.frame) - self.frame += 1 - return ret + return self.CC.update(c, self.CS) diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index 8ad5049e32..f763a58532 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -1,7 +1,7 @@ from cereal import car from common.conversions import Conversions as CV -from common.realtime import DT_CTRL from common.numpy_fast import interp +from common.realtime import DT_CTRL from opendbc.can.packer import CANPacker from selfdrive.car import apply_std_steer_torque_limits from selfdrive.car.gm import gmcan diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 282844d095..e0dd10d4a8 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -184,5 +184,4 @@ class CarInterface(CarInterfaceBase): return ret def apply(self, c): - ret = self.CC.update(c, self.CS) - return ret + return self.CC.update(c, self.CS) diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index fb3579464a..4fbb5ce0e1 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -1,11 +1,11 @@ from cereal import car -from common.realtime import DT_CTRL -from common.numpy_fast import clip, interp from common.conversions import Conversions as CV +from common.numpy_fast import clip, interp +from common.realtime import DT_CTRL +from opendbc.can.packer import CANPacker from selfdrive.car import apply_std_steer_torque_limits from selfdrive.car.hyundai import hda2can, hyundaican from selfdrive.car.hyundai.values import Buttons, CarControllerParams, HDA2_CAR, CAR -from opendbc.can.packer import CANPacker VisualAlert = car.CarControl.HUDControl.VisualAlert LongCtrlState = car.CarControl.Actuators.LongControlState diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 58a67f58ce..97119c77b7 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -349,5 +349,4 @@ class CarInterface(CarInterfaceBase): return ret def apply(self, c): - ret = self.CC.update(c, self.CS) - return ret + return self.CC.update(c, self.CS) diff --git a/selfdrive/car/mazda/carcontroller.py b/selfdrive/car/mazda/carcontroller.py index d003079d63..0e43a11ceb 100644 --- a/selfdrive/car/mazda/carcontroller.py +++ b/selfdrive/car/mazda/carcontroller.py @@ -1,46 +1,48 @@ from cereal import car from opendbc.can.packer import CANPacker +from selfdrive.car import apply_std_steer_torque_limits from selfdrive.car.mazda import mazdacan from selfdrive.car.mazda.values import CarControllerParams, Buttons -from selfdrive.car import apply_std_steer_torque_limits VisualAlert = car.CarControl.HUDControl.VisualAlert -class CarController(): + +class CarController: def __init__(self, dbc_name, CP, VM): self.CP = CP self.apply_steer_last = 0 self.packer = CANPacker(dbc_name) self.steer_rate_limited = False self.brake_counter = 0 + self.frame = 0 - def update(self, c, CS, frame): + def update(self, CC, CS): can_sends = [] apply_steer = 0 self.steer_rate_limited = False - if c.latActive: + if CC.latActive: # calculate steer and also set limits due to driver torque - new_steer = int(round(c.actuators.steer * CarControllerParams.STEER_MAX)) + new_steer = int(round(CC.actuators.steer * CarControllerParams.STEER_MAX)) apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, CarControllerParams) self.steer_rate_limited = new_steer != apply_steer - if c.enabled: - if CS.out.standstill and frame % 5 == 0: + if CC.enabled: + if CS.out.standstill and self.frame % 5 == 0: # Mazda Stop and Go requires a RES button (or gas) press if the car stops more than 3 seconds # Send Resume button at 20hz if we're engaged at standstill to support full stop and go! # TODO: improve the resume trigger logic by looking at actual radar data can_sends.append(mazdacan.create_button_cmd(self.packer, self.CP.carFingerprint, CS.crz_btns_counter, Buttons.RESUME)) - if c.cruiseControl.cancel: + if CC.cruiseControl.cancel: # If brake is pressed, let us wait >70ms before trying to disable crz to avoid # a race condition with the stock system, where the second cancel from openpilot # will disable the crz 'main on'. crz ctrl msg runs at 50hz. 70ms allows us to # read 3 messages and most likely sync state before we attempt cancel. self.brake_counter = self.brake_counter + 1 - if frame % 10 == 0 and not (CS.out.brakePressed and self.brake_counter < 7): + if self.frame % 10 == 0 and not (CS.out.brakePressed and self.brake_counter < 7): # Cancel Stock ACC if it's enabled while OP is disengaged # Send at a rate of 10hz until we sync with stock ACC state can_sends.append(mazdacan.create_button_cmd(self.packer, self.CP.carFingerprint, CS.crz_btns_counter, Buttons.CANCEL)) @@ -50,18 +52,19 @@ class CarController(): self.apply_steer_last = apply_steer # send HUD alerts - if frame % 50 == 0: - ldw = c.hudControl.visualAlert == VisualAlert.ldw - steer_required = c.hudControl.visualAlert == VisualAlert.steerRequired + if self.frame % 50 == 0: + ldw = CC.hudControl.visualAlert == VisualAlert.ldw + steer_required = CC.hudControl.visualAlert == VisualAlert.steerRequired # TODO: find a way to silence audible warnings so we can add more hud alerts steer_required = steer_required and CS.lkas_allowed_speed can_sends.append(mazdacan.create_alert_command(self.packer, CS.cam_laneinfo, ldw, steer_required)) # send steering command can_sends.append(mazdacan.create_steering_control(self.packer, self.CP.carFingerprint, - frame, apply_steer, CS.cam_lkas)) + self.frame, apply_steer, CS.cam_lkas)) - new_actuators = c.actuators.copy() + new_actuators = CC.actuators.copy() new_actuators.steer = apply_steer / CarControllerParams.STEER_MAX + self.frame += 1 return new_actuators, can_sends diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index cbeb910de2..35e3c1bb01 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -90,6 +90,4 @@ class CarInterface(CarInterfaceBase): return ret def apply(self, c): - ret = self.CC.update(c, self.CS, self.frame) - self.frame += 1 - return ret + return self.CC.update(c, self.CS) diff --git a/selfdrive/car/nissan/carcontroller.py b/selfdrive/car/nissan/carcontroller.py index 4ceb142d45..7d9dad6693 100644 --- a/selfdrive/car/nissan/carcontroller.py +++ b/selfdrive/car/nissan/carcontroller.py @@ -1,25 +1,27 @@ from cereal import car from common.numpy_fast import clip, interp -from selfdrive.car.nissan import nissancan from opendbc.can.packer import CANPacker +from selfdrive.car.nissan import nissancan from selfdrive.car.nissan.values import CAR, CarControllerParams - VisualAlert = car.CarControl.HUDControl.VisualAlert -class CarController(): +class CarController: def __init__(self, dbc_name, CP, VM): self.CP = CP self.car_fingerprint = CP.carFingerprint + self.frame = 0 self.lkas_max_torque = 0 self.last_angle = 0 self.packer = CANPacker(dbc_name) - def update(self, c, CS, frame, actuators, cruise_cancel, hud_alert, - left_line, right_line, left_lane_depart, right_lane_depart): + def update(self, CC, CS): + actuators = CC.actuators + hud_control = CC.hudControl + pcm_cancel_cmd = CC.cruiseControl.cancel can_sends = [] @@ -28,9 +30,9 @@ class CarController(): lkas_hud_info_msg = CS.lkas_hud_info_msg apply_angle = actuators.steeringAngleDeg - steer_hud_alert = 1 if hud_alert in (VisualAlert.steerRequired, VisualAlert.ldw) else 0 + steer_hud_alert = 1 if hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) else 0 - if c.latActive: + if CC.latActive: # # windup slower if self.last_angle * apply_angle > 0. and abs(apply_angle) > abs(self.last_angle): angle_rate_lim = interp(CS.out.vEgo, CarControllerParams.ANGLE_DELTA_BP, CarControllerParams.ANGLE_DELTA_V) @@ -57,25 +59,25 @@ class CarController(): self.last_angle = apply_angle - if self.CP.carFingerprint in (CAR.ROGUE, CAR.XTRAIL, CAR.ALTIMA) and cruise_cancel: - can_sends.append(nissancan.create_acc_cancel_cmd(self.packer, self.car_fingerprint, CS.cruise_throttle_msg, frame)) + if self.CP.carFingerprint in (CAR.ROGUE, CAR.XTRAIL, CAR.ALTIMA) and pcm_cancel_cmd: + can_sends.append(nissancan.create_acc_cancel_cmd(self.packer, self.car_fingerprint, CS.cruise_throttle_msg, self.frame)) # TODO: Find better way to cancel! # For some reason spamming the cancel button is unreliable on the Leaf # We now cancel by making propilot think the seatbelt is unlatched, # this generates a beep and a warning message every time you disengage - if self.CP.carFingerprint in (CAR.LEAF, CAR.LEAF_IC) and frame % 2 == 0: - can_sends.append(nissancan.create_cancel_msg(self.packer, CS.cancel_msg, cruise_cancel)) + if self.CP.carFingerprint in (CAR.LEAF, CAR.LEAF_IC) and self.frame % 2 == 0: + can_sends.append(nissancan.create_cancel_msg(self.packer, CS.cancel_msg, pcm_cancel_cmd)) can_sends.append(nissancan.create_steering_control( - self.packer, apply_angle, frame, c.enabled, self.lkas_max_torque)) + self.packer, apply_angle, self.frame, CC.enabled, self.lkas_max_torque)) if lkas_hud_msg and lkas_hud_info_msg: - if frame % 2 == 0: + if self.frame % 2 == 0: can_sends.append(nissancan.create_lkas_hud_msg( - self.packer, lkas_hud_msg, c.enabled, left_line, right_line, left_lane_depart, right_lane_depart)) + self.packer, lkas_hud_msg, CC.enabled, hud_control.leftLaneVisible, hud_control.rightLaneVisible, hud_control.leftLaneDepart, hud_control.rightLaneDepart)) - if frame % 50 == 0: + if self.frame % 50 == 0: can_sends.append(nissancan.create_lkas_hud_info_msg( self.packer, lkas_hud_info_msg, steer_hud_alert )) @@ -83,4 +85,5 @@ class CarController(): new_actuators = actuators.copy() new_actuators.steeringAngleDeg = apply_angle + self.frame += 1 return new_actuators, can_sends diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index 436cef68bf..9c04d975f9 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -1,8 +1,9 @@ #!/usr/bin/env python3 from cereal import car -from selfdrive.car.nissan.values import CAR from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase +from selfdrive.car.nissan.values import CAR + class CarInterface(CarInterfaceBase): @@ -67,10 +68,4 @@ class CarInterface(CarInterfaceBase): return ret def apply(self, c): - hud_control = c.hudControl - ret = self.CC.update(c, self.CS, self.frame, c.actuators, - c.cruiseControl.cancel, hud_control.visualAlert, - hud_control.leftLaneVisible, hud_control.rightLaneVisible, - hud_control.leftLaneDepart, hud_control.rightLaneDepart) - self.frame += 1 - return ret + return self.CC.update(c, self.CS) diff --git a/selfdrive/car/subaru/carcontroller.py b/selfdrive/car/subaru/carcontroller.py index d37b82eed7..dca86c30a6 100644 --- a/selfdrive/car/subaru/carcontroller.py +++ b/selfdrive/car/subaru/carcontroller.py @@ -1,10 +1,10 @@ +from opendbc.can.packer import CANPacker from selfdrive.car import apply_std_steer_torque_limits from selfdrive.car.subaru import subarucan from selfdrive.car.subaru.values import DBC, PREGLOBAL_CARS, CarControllerParams -from opendbc.can.packer import CANPacker -class CarController(): +class CarController: def __init__(self, dbc_name, CP, VM): self.CP = CP self.apply_steer_last = 0 @@ -12,16 +12,20 @@ class CarController(): self.es_lkas_cnt = -1 self.cruise_button_prev = 0 self.steer_rate_limited = False + self.frame = 0 self.p = CarControllerParams(CP) self.packer = CANPacker(DBC[CP.carFingerprint]['pt']) - def update(self, c, CS, frame, actuators, pcm_cancel_cmd, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart): + def update(self, CC, CS): + actuators = CC.actuators + hud_control = CC.hudControl + pcm_cancel_cmd = CC.cruiseControl.cancel can_sends = [] # *** steering *** - if (frame % self.p.STEER_STEP) == 0: + if (self.frame % self.p.STEER_STEP) == 0: apply_steer = int(round(actuators.steer * self.p.STEER_MAX)) @@ -31,13 +35,13 @@ class CarController(): apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.p) self.steer_rate_limited = new_steer != apply_steer - if not c.latActive: + if not CC.latActive: apply_steer = 0 if self.CP.carFingerprint in PREGLOBAL_CARS: - can_sends.append(subarucan.create_preglobal_steering_control(self.packer, apply_steer, frame, self.p.STEER_STEP)) + can_sends.append(subarucan.create_preglobal_steering_control(self.packer, apply_steer, self.frame, self.p.STEER_STEP)) else: - can_sends.append(subarucan.create_steering_control(self.packer, apply_steer, frame, self.p.STEER_STEP)) + can_sends.append(subarucan.create_steering_control(self.packer, apply_steer, self.frame, self.p.STEER_STEP)) self.apply_steer_last = apply_steer @@ -70,10 +74,11 @@ class CarController(): self.es_distance_cnt = CS.es_distance_msg["Counter"] if self.es_lkas_cnt != CS.es_lkas_msg["Counter"]: - can_sends.append(subarucan.create_es_lkas(self.packer, CS.es_lkas_msg, c.enabled, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart)) + can_sends.append(subarucan.create_es_lkas(self.packer, CS.es_lkas_msg, CC.enabled, hud_control.visualAlert, hud_control.leftLaneVisible, hud_control.rightLaneVisible, hud_control.leftLaneDepart, hud_control.rightLaneDepart)) self.es_lkas_cnt = CS.es_lkas_msg["Counter"] new_actuators = actuators.copy() new_actuators.steer = self.apply_steer_last / self.p.STEER_MAX + self.frame += 1 return new_actuators, can_sends diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index 8c5cab86e8..952885a751 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -1,8 +1,9 @@ #!/usr/bin/env python3 from cereal import car -from selfdrive.car.subaru.values import CAR, PREGLOBAL_CARS from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase +from selfdrive.car.subaru.values import CAR, PREGLOBAL_CARS + class CarInterface(CarInterfaceBase): @@ -117,9 +118,4 @@ class CarInterface(CarInterfaceBase): return ret def apply(self, c): - hud_control = c.hudControl - ret = self.CC.update(c, self.CS, self.frame, c.actuators, - c.cruiseControl.cancel, hud_control.visualAlert, - hud_control.leftLaneVisible, hud_control.rightLaneVisible, hud_control.leftLaneDepart, hud_control.rightLaneDepart) - self.frame += 1 - return ret + return self.CC.update(c, self.CS) diff --git a/selfdrive/car/tesla/interface.py b/selfdrive/car/tesla/interface.py index d4eda38e64..5e78c72b60 100755 --- a/selfdrive/car/tesla/interface.py +++ b/selfdrive/car/tesla/interface.py @@ -64,5 +64,4 @@ class CarInterface(CarInterfaceBase): return ret def apply(self, c): - ret = self.CC.update(c, self.CS) - return ret + return self.CC.update(c, self.CS) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index fdb923f693..337c039565 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -274,5 +274,4 @@ class CarInterface(CarInterfaceBase): # pass in a car.CarControl # to be called @ 100hz def apply(self, c): - ret = self.CC.update(c, self.CS) - return ret + return self.CC.update(c, self.CS) diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py index 842eb6d139..4614463c6e 100644 --- a/selfdrive/car/volkswagen/carcontroller.py +++ b/selfdrive/car/volkswagen/carcontroller.py @@ -1,15 +1,17 @@ from cereal import car +from opendbc.can.packer import CANPacker from selfdrive.car import apply_std_steer_torque_limits from selfdrive.car.volkswagen import volkswagencan from selfdrive.car.volkswagen.values import DBC_FILES, CANBUS, MQB_LDW_MESSAGES, BUTTON_STATES, CarControllerParams as P -from opendbc.can.packer import CANPacker VisualAlert = car.CarControl.HUDControl.VisualAlert -class CarController(): + +class CarController: def __init__(self, dbc_name, CP, VM): - self.apply_steer_last = 0 self.CP = CP + self.apply_steer_last = 0 + self.frame = 0 self.packer_pt = CANPacker(DBC_FILES.mqb) @@ -22,14 +24,15 @@ class CarController(): self.steer_rate_limited = False - def update(self, c, CS, frame, ext_bus, actuators, visual_alert, left_lane_visible, right_lane_visible, left_lane_depart, right_lane_depart): - """ Controls thread """ + def update(self, CC, CS, ext_bus): + actuators = CC.actuators + hud_control = CC.hudControl can_sends = [] # **** Steering Controls ************************************************ # - if frame % P.HCA_STEP == 0: + if self.frame % P.HCA_STEP == 0: # Logic to avoid HCA state 4 "refused": # * Don't steer unless HCA is in state 3 "ready" or 5 "active" # * Don't steer at standstill @@ -40,7 +43,7 @@ class CarController(): # torque value. Do that anytime we happen to have 0 torque, or failing that, # when exceeding ~1/3 the 360 second timer. - if c.latActive: + if CC.latActive: new_steer = int(round(actuators.steer * P.STEER_MAX)) apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, P) self.steer_rate_limited = new_steer != apply_steer @@ -66,34 +69,34 @@ class CarController(): apply_steer = 0 self.apply_steer_last = apply_steer - idx = (frame / P.HCA_STEP) % 16 + idx = (self.frame / P.HCA_STEP) % 16 can_sends.append(volkswagencan.create_mqb_steering_control(self.packer_pt, CANBUS.pt, apply_steer, idx, hcaEnabled)) # **** HUD Controls ***************************************************** # - if frame % P.LDW_STEP == 0: - if visual_alert in (VisualAlert.steerRequired, VisualAlert.ldw): + if self.frame % P.LDW_STEP == 0: + if hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw): hud_alert = MQB_LDW_MESSAGES["laneAssistTakeOverSilent"] else: hud_alert = MQB_LDW_MESSAGES["none"] - can_sends.append(volkswagencan.create_mqb_hud_control(self.packer_pt, CANBUS.pt, c.enabled, - CS.out.steeringPressed, hud_alert, left_lane_visible, - right_lane_visible, CS.ldw_stock_values, - left_lane_depart, right_lane_depart)) + can_sends.append(volkswagencan.create_mqb_hud_control(self.packer_pt, CANBUS.pt, CC.enabled, + CS.out.steeringPressed, hud_alert, hud_control.leftLaneVisible, + hud_control.rightLaneVisible, CS.ldw_stock_values, + hud_control.leftLaneDepart, hud_control.rightLaneDepart)) # **** ACC Button Controls ********************************************** # # FIXME: this entire section is in desperate need of refactoring if self.CP.pcmCruise: - if frame > self.graMsgStartFramePrev + P.GRA_VBP_STEP: - if c.cruiseControl.cancel: + if self.frame > self.graMsgStartFramePrev + P.GRA_VBP_STEP: + if CC.cruiseControl.cancel: # Cancel ACC if it's engaged with OP disengaged. self.graButtonStatesToSend = BUTTON_STATES.copy() self.graButtonStatesToSend["cancel"] = True - elif c.enabled and CS.out.cruiseState.standstill: + elif CC.enabled and CS.out.cruiseState.standstill: # Blip the Resume button if we're engaged at standstill. # FIXME: This is a naive implementation, improve with visiond or radar input. self.graButtonStatesToSend = BUTTON_STATES.copy() @@ -103,7 +106,7 @@ class CarController(): self.graMsgBusCounterPrev = CS.graMsgBusCounter if self.graButtonStatesToSend is not None: if self.graMsgSentCount == 0: - self.graMsgStartFramePrev = frame + self.graMsgStartFramePrev = self.frame idx = (CS.graMsgBusCounter + 1) % 16 can_sends.append(volkswagencan.create_mqb_acc_buttons_control(self.packer_pt, ext_bus, self.graButtonStatesToSend, CS, idx)) self.graMsgSentCount += 1 @@ -114,4 +117,5 @@ class CarController(): new_actuators = actuators.copy() new_actuators.steer = self.apply_steer_last / P.STEER_MAX + self.frame += 1 return new_actuators, can_sends diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 6782105c16..c2b077b6db 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -193,12 +193,4 @@ class CarInterface(CarInterfaceBase): return ret def apply(self, c): - hud_control = c.hudControl - ret = self.CC.update(c, self.CS, self.frame, self.ext_bus, c.actuators, - hud_control.visualAlert, - hud_control.leftLaneVisible, - hud_control.rightLaneVisible, - hud_control.leftLaneDepart, - hud_control.rightLaneDepart) - self.frame += 1 - return ret + return self.CC.update(c, self.CS, self.ext_bus) From 38ff2982eb2e72b634af26e2adb0ac7a363999ce Mon Sep 17 00:00:00 2001 From: realfast Date: Thu, 30 Jun 2022 19:27:35 -0500 Subject: [PATCH 183/302] Chrysler: carState signals update (#24760) * carstate update * update refs Co-authored-by: Adeeb Shihadeh --- opendbc | 2 +- selfdrive/car/chrysler/carcontroller.py | 4 +- selfdrive/car/chrysler/carstate.py | 58 ++++++++++++------------ selfdrive/car/chrysler/chryslercan.py | 9 ++-- selfdrive/test/process_replay/ref_commit | 2 +- 5 files changed, 37 insertions(+), 38 deletions(-) diff --git a/opendbc b/opendbc index 47b79c4d5a..7fbf7c2a68 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 47b79c4d5ab5adc0bdd9d228c3d9594da0355c49 +Subproject commit 7fbf7c2a685a90ff01e744cfb410f1a8a3c06278 diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py index 3d6295d77d..49525646ca 100644 --- a/selfdrive/car/chrysler/carcontroller.py +++ b/selfdrive/car/chrysler/carcontroller.py @@ -1,7 +1,7 @@ from cereal import car from opendbc.can.packer import CANPacker from selfdrive.car import apply_toyota_steer_torque_limits -from selfdrive.car.chrysler.chryslercan import create_lkas_hud, create_lkas_command, create_wheel_buttons +from selfdrive.car.chrysler.chryslercan import create_lkas_hud, create_lkas_command, create_cruise_buttons from selfdrive.car.chrysler.values import CAR, CarControllerParams @@ -49,7 +49,7 @@ class CarController: # *** control msgs *** if CC.cruiseControl.cancel: - can_sends.append(create_wheel_buttons(self.packer, CS.button_counter + 1, cancel=True)) + can_sends.append(create_cruise_buttons(self.packer, CS.button_counter + 1, cancel=True)) # LKAS_HEARTBIT is forwarded by Panda so no need to send it here. # frame is 100Hz (0.01s period) diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index 202526df05..444557191a 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -16,13 +16,13 @@ class CarState(CarStateBase): ret = car.CarState.new_message() - self.frame = int(cp.vl["EPS_STATUS"]["COUNTER"]) + self.frame = int(cp.vl["EPS_2"]["COUNTER"]) ret.doorOpen = any([cp.vl["BCM_1"]["DOOR_OPEN_FL"], cp.vl["BCM_1"]["DOOR_OPEN_FR"], cp.vl["BCM_1"]["DOOR_OPEN_RL"], cp.vl["BCM_1"]["DOOR_OPEN_RR"]]) - ret.seatbeltUnlatched = cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_UNLATCHED"] == 1 + ret.seatbeltUnlatched = cp.vl["ORC_1"]["SEATBELT_DRIVER_UNLATCHED"] == 1 # brake pedal ret.brake = 0 @@ -35,10 +35,10 @@ class CarState(CarStateBase): ret.espDisabled = (cp.vl["TRACTION_BUTTON"]["TRACTION_OFF"] == 1) ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FL"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FR"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RL"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RR"], + cp.vl["ESP_6"]["WHEEL_SPEED_FL"], + cp.vl["ESP_6"]["WHEEL_SPEED_FR"], + cp.vl["ESP_6"]["WHEEL_SPEED_RL"], + cp.vl["ESP_6"]["WHEEL_SPEED_RR"], unit=1, ) ret.vEgoRaw = (cp.vl["SPEED_1"]["SPEED_LEFT"] + cp.vl["SPEED_1"]["SPEED_RIGHT"]) / 2. @@ -51,17 +51,17 @@ class CarState(CarStateBase): ret.cruiseState.available = cp.vl["DAS_3"]["ACC_AVAILABLE"] == 1 # ACC is white ret.cruiseState.enabled = cp.vl["DAS_3"]["ACC_ACTIVE"] == 1 # ACC is green - ret.cruiseState.speed = cp.vl["DASHBOARD"]["ACC_SPEED_CONFIG_KPH"] * CV.KPH_TO_MS + ret.cruiseState.speed = cp.vl["DAS_4"]["ACC_SPEED_CONFIG_KPH"] * CV.KPH_TO_MS # CRUISE_STATE is a three bit msg, 0 is off, 1 and 2 are Non-ACC mode, 3 and 4 are ACC mode, find if there are other states too - ret.cruiseState.nonAdaptive = cp.vl["DASHBOARD"]["CRUISE_STATE"] in (1, 2) + ret.cruiseState.nonAdaptive = cp.vl["DAS_4"]["CRUISE_STATE"] in (1, 2) ret.accFaulted = cp.vl["DAS_3"]["ACC_FAULTED"] != 0 ret.steeringAngleDeg = cp.vl["STEERING"]["STEER_ANGLE"] ret.steeringRateDeg = cp.vl["STEERING"]["STEERING_RATE"] - ret.steeringTorque = cp.vl["EPS_STATUS"]["TORQUE_DRIVER"] - ret.steeringTorqueEps = cp.vl["EPS_STATUS"]["TORQUE_MOTOR"] + ret.steeringTorque = cp.vl["EPS_2"]["COLUMN_TORQUE"] + ret.steeringTorqueEps = cp.vl["EPS_2"]["EPS_TORQUE_MOTOR"] ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD - steer_state = cp.vl["EPS_STATUS"]["LKAS_STATE"] + steer_state = cp.vl["EPS_2"]["LKAS_STATE"] ret.steerFaultPermanent = steer_state == 4 or (steer_state == 0 and ret.vEgo > self.CP.minSteerSpeed) ret.genericToggle = bool(cp.vl["STEERING_LEVERS"]["HIGH_BEAM_FLASH"]) @@ -73,7 +73,7 @@ class CarState(CarStateBase): self.lkas_counter = cp_cam.vl["LKAS_COMMAND"]["COUNTER"] self.lkas_car_model = cp_cam.vl["LKAS_HUD"]["CAR_MODEL"] self.lkas_status_ok = cp_cam.vl["LKAS_HEARTBIT"]["LKAS_STATUS_OK"] - self.button_counter = cp.vl["WHEEL_BUTTONS"]["COUNTER"] + self.button_counter = cp.vl["CRUISE_BUTTONS"]["COUNTER"] return ret @@ -90,10 +90,10 @@ class CarState(CarStateBase): ("Accelerator_Position", "ECM_5"), ("SPEED_LEFT", "SPEED_1"), ("SPEED_RIGHT", "SPEED_1"), - ("WHEEL_SPEED_FL", "WHEEL_SPEEDS"), - ("WHEEL_SPEED_RR", "WHEEL_SPEEDS"), - ("WHEEL_SPEED_RL", "WHEEL_SPEEDS"), - ("WHEEL_SPEED_FR", "WHEEL_SPEEDS"), + ("WHEEL_SPEED_FL", "ESP_6"), + ("WHEEL_SPEED_RR", "ESP_6"), + ("WHEEL_SPEED_RL", "ESP_6"), + ("WHEEL_SPEED_FR", "ESP_6"), ("STEER_ANGLE", "STEERING"), ("STEERING_RATE", "STEERING"), ("TURN_SIGNALS", "STEERING_LEVERS"), @@ -101,31 +101,31 @@ class CarState(CarStateBase): ("ACC_ACTIVE", "DAS_3"), ("ACC_FAULTED", "DAS_3"), ("HIGH_BEAM_FLASH", "STEERING_LEVERS"), - ("ACC_SPEED_CONFIG_KPH", "DASHBOARD"), - ("CRUISE_STATE", "DASHBOARD"), - ("TORQUE_DRIVER", "EPS_STATUS"), - ("TORQUE_MOTOR", "EPS_STATUS"), - ("LKAS_STATE", "EPS_STATUS"), - ("COUNTER", "EPS_STATUS",), + ("ACC_SPEED_CONFIG_KPH", "DAS_4"), + ("CRUISE_STATE", "DAS_4"), + ("COLUMN_TORQUE", "EPS_2"), + ("EPS_TORQUE_MOTOR", "EPS_2"), + ("LKAS_STATE", "EPS_2"), + ("COUNTER", "EPS_2",), ("TRACTION_OFF", "TRACTION_BUTTON"), - ("SEATBELT_DRIVER_UNLATCHED", "SEATBELT_STATUS"), - ("COUNTER", "WHEEL_BUTTONS"), + ("SEATBELT_DRIVER_UNLATCHED", "ORC_1"), + ("COUNTER", "CRUISE_BUTTONS"), ] checks = [ # sig_address, frequency ("ESP_1", 50), - ("EPS_STATUS", 100), + ("EPS_2", 100), ("SPEED_1", 100), - ("WHEEL_SPEEDS", 50), + ("ESP_6", 50), ("STEERING", 100), ("DAS_3", 50), ("GEAR", 50), ("ECM_5", 50), - ("WHEEL_BUTTONS", 50), - ("DASHBOARD", 15), + ("CRUISE_BUTTONS", 50), + ("DAS_4", 15), ("STEERING_LEVERS", 10), - ("SEATBELT_STATUS", 2), + ("ORC_1", 2), ("BCM_1", 1), ("TRACTION_BUTTON", 1), ] diff --git a/selfdrive/car/chrysler/chryslercan.py b/selfdrive/car/chrysler/chryslercan.py index 896a6b15da..53b79cab73 100644 --- a/selfdrive/car/chrysler/chryslercan.py +++ b/selfdrive/car/chrysler/chryslercan.py @@ -48,10 +48,9 @@ def create_lkas_command(packer, apply_steer, moving_fast, frame): return packer.make_can_msg("LKAS_COMMAND", 0, values) -def create_wheel_buttons(packer, frame, cancel=False): - # WHEEL_BUTTONS (571) Message sent to cancel ACC. +def create_cruise_buttons(packer, frame, cancel=False): values = { - "ACC_CANCEL": cancel, - "COUNTER": frame % 0x10 + "ACC_Cancel": cancel, + "COUNTER": frame % 0x10, } - return packer.make_can_msg("WHEEL_BUTTONS", 0, values) + return packer.make_can_msg("CRUISE_BUTTONS", 0, values) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index a1cb2bf362..90444b1fa7 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -d7c610172f3ff10b68403abc19b260c91c848ebb \ No newline at end of file +806984d4206056fb132625c5dad6c0ca1835a2d6 \ No newline at end of file From ab8592187f36ea9fda6767e86a0651366c12c487 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 30 Jun 2022 17:55:22 -0700 Subject: [PATCH 184/302] Chrysler Pacifica 2019 is supported (#25010) 19 is secretly supported --- docs/CARS.md | 2 +- selfdrive/car/chrysler/values.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index fb163b44e0..25de6a2549 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -154,7 +154,7 @@ How We Rate The Cars |Audi|Q3 2020-21|ACC + Lane Assist|||||| |Cadillac|Escalade ESV 2016[1](#footnotes)|ACC + LKAS|||||| |Chrysler|Pacifica 2017-18|Adaptive Cruise|||||| -|Chrysler|Pacifica 2020|Adaptive Cruise|||||| +|Chrysler|Pacifica 2019-20|Adaptive Cruise|||||| |Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise|||||| |Chrysler|Pacifica Hybrid 2019-22|Adaptive Cruise|||||| |Genesis|G90 2018|All|||||| diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index bdd80757f4..6faa76a479 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -39,7 +39,7 @@ CAR_INFO: Dict[str, Optional[Union[ChryslerCarInfo, List[ChryslerCarInfo]]]] = { CAR.PACIFICA_2018_HYBRID: None, # same platforms CAR.PACIFICA_2019_HYBRID: ChryslerCarInfo("Chrysler Pacifica Hybrid 2019-22"), CAR.PACIFICA_2018: ChryslerCarInfo("Chrysler Pacifica 2017-18"), - CAR.PACIFICA_2020: ChryslerCarInfo("Chrysler Pacifica 2020"), + CAR.PACIFICA_2020: ChryslerCarInfo("Chrysler Pacifica 2019-20"), CAR.JEEP_CHEROKEE: ChryslerCarInfo("Jeep Grand Cherokee 2016-18", video_link="https://www.youtube.com/watch?v=eLR9o2JkuRk"), CAR.JEEP_CHEROKEE_2019: ChryslerCarInfo("Jeep Grand Cherokee 2019-20", video_link="https://www.youtube.com/watch?v=jBe4lWnRSu4"), } From c21ee5b76411de1bea1b95a0d71b48be879d7734 Mon Sep 17 00:00:00 2001 From: TheWizard1328 Date: Thu, 30 Jun 2022 21:06:49 -0600 Subject: [PATCH 185/302] Chrysler: add missing 2022 Pacifica Hybrid fingerprint (#24685) * Added 2022 PacHy info Didn't really need to add this but thought it would be useful. * Added 2022 PacHy info * Added 2022 PacHy info Added 2022 PacHy FP * add to current platform * generate docs * should only need this Co-authored-by: Shane Smiskol --- selfdrive/car/chrysler/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 6faa76a479..d624bd2727 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -88,7 +88,7 @@ FINGERPRINTS = { }, # Based on "8190c7275a24557b|2020-02-24--09-57-23" { - 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 640: 1, 650: 8, 653: 8, 654: 8, 655: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 683: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 711: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 793: 8, 794: 8, 795: 8, 796: 8, 797: 8, 798: 8, 799: 8, 800: 8, 801: 8, 802: 8, 803: 8, 804: 8, 805: 8, 807: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 886: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1258: 8, 1259: 8, 1260: 8, 1262: 8, 1284: 8, 1568: 8, 1570: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 1898: 8, 1899: 8, 1900: 8, 1902: 8, 2015: 8, 2016: 8, 2017: 8, 2018: 8, 2019: 8, 2020: 8, 2023: 8, 2024: 8, 2026: 8, 2027: 8, 2028: 8, 2031: 8 + 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 640: 1, 650: 8, 653: 8, 654: 8, 655: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 683: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 711: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 793: 8, 794: 8, 795: 8, 796: 8, 797: 8, 798: 8, 799: 8, 800: 8, 801: 8, 802: 8, 803: 8, 804: 8, 805: 8, 807: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 886: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1258: 8, 1259: 8, 1260: 8, 1262: 8, 1284: 8, 1536: 8, 1568: 8, 1570: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 1898: 8, 1899: 8, 1900: 8, 1902: 8, 2015: 8, 2016: 8, 2017: 8, 2018: 8, 2019: 8, 2020: 8, 2023: 8, 2024: 8, 2026: 8, 2027: 8, 2028: 8, 2031: 8 }], CAR.JEEP_CHEROKEE: [{ 55: 8, 168: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 788: 3, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 874: 2, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 975: 8, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 1543: 8, 1562: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 From b51a90b5a87e0b6388191f7cc5857af8d72e79de Mon Sep 17 00:00:00 2001 From: Yu Yamaguchi Date: Fri, 1 Jul 2022 15:35:37 +0900 Subject: [PATCH 186/302] Mazda: add missing FW version for CX-5 2022 (#24925) --- selfdrive/car/mazda/values.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 5c80303dbc..f5d63418f1 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -65,6 +65,7 @@ FW_VERSIONS = { ], (Ecu.engine, 0x7e0, None): [ b'PX2G-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'SH54-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -77,6 +78,7 @@ FW_VERSIONS = { ], (Ecu.transmission, 0x7e1, None): [ b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'SH51-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], }, CAR.CX5: { From 20ccfed9c1d75de2a589294a5407e15304fd3f4a Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Fri, 1 Jul 2022 16:43:36 +0200 Subject: [PATCH 187/302] laikad: Improve logging, fix warning and more exception handling (#25005) * change logs and add some debugging. Add test * Less logging and better check for exceptions when parsing orbits * Fix debug log and fix kf initialization --- selfdrive/locationd/laikad.py | 28 ++++++++++++++++--------- selfdrive/locationd/laikad_helpers.py | 2 +- selfdrive/locationd/test/test_laikad.py | 12 +++++++++++ 3 files changed, 31 insertions(+), 11 deletions(-) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index d51ac10816..427eb3dbe0 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -31,7 +31,14 @@ CACHE_VERSION = 0.1 class Laikad: def __init__(self, valid_const=("GPS", "GLONASS"), auto_fetch_orbits=True, auto_update=False, valid_ephem_types=(EphemerisType.ULTRA_RAPID_ORBIT, EphemerisType.NAV), - save_ephemeris=False, last_known_position=None): + save_ephemeris=False): + """ + valid_const: GNSS constellation which can be used + auto_fetch_orbits: If true fetch orbits from internet when needed + auto_update: If true download AstroDog will download all files needed. This can be ephemeris or correction data like ionosphere. + valid_ephem_types: Valid ephemeris types to be used by AstroDog + save_ephemeris: If true saves and loads nav and orbit ephemeris to cache. + """ self.astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types, clear_old_ephemeris=True) self.gnss_kf = GNSSKalman(GENERATED_DIR, cython=True) @@ -45,7 +52,7 @@ class Laikad: self.load_cache() self.posfix_functions = {constellation: get_posfix_sympy_fun(constellation) for constellation in (ConstellationId.GPS, ConstellationId.GLONASS)} - self.last_pos_fix = last_known_position if last_known_position is not None else [] + self.last_pos_fix = [] self.last_pos_residual = [] self.last_pos_fix_t = None @@ -64,12 +71,16 @@ class Laikad: self.last_fetch_orbits_t = cache['last_fetch_orbits_t'] except json.decoder.JSONDecodeError: cloudlog.exception("Error parsing cache") + timestamp = self.last_fetch_orbits_t.as_datetime() if self.last_fetch_orbits_t is not None else 'Nan' + cloudlog.debug(f"Loaded nav and orbits cache with timestamp: {timestamp}. Unique orbit and nav sats: {list(cache['orbits'].keys())} {list(cache['nav'].keys())} " + + f"Total: {sum([len(v) for v in cache['orbits']])} and {sum([len(v) for v in cache['nav']])}") def cache_ephemeris(self, t: GPSTime): if self.save_ephemeris and (self.last_cached_t is None or t - self.last_cached_t > SECS_IN_MIN): put_nonblocking(EPHEMERIS_CACHE, json.dumps( {'version': CACHE_VERSION, 'last_fetch_orbits_t': self.last_fetch_orbits_t, 'orbits': self.astro_dog.orbits, 'nav': self.astro_dog.nav}, cls=CacheSerializer)) + cloudlog.debug("Cache saved") self.last_cached_t = t def get_est_pos(self, t, processed_measurements): @@ -130,9 +141,8 @@ class Laikad: # Check time and outputs are valid valid = self.kf_valid(t) if not all(valid): - if not valid[0]: - cloudlog.info("Kalman filter uninitialized") - elif not valid[1]: + + if not valid[1]: cloudlog.error("Time gap of over 10s detected, gnss kalman reset") elif not valid[2]: cloudlog.error("Gnss kalman filter state is nan") @@ -140,7 +150,6 @@ class Laikad: cloudlog.info(f"Reset kalman filter with {est_pos}") self.init_gnss_localizer(est_pos) else: - cloudlog.info("Could not reset kalman filter") return if len(measurements) > 0: kf_add_observations(self.gnss_kf, t, measurements) @@ -189,8 +198,8 @@ def get_orbit_data(t: GPSTime, valid_const, auto_update, valid_ephem_types): try: astro_dog.get_orbit_data(t, only_predictions=True) data = (astro_dog.orbits, astro_dog.orbit_fetched_times) - except RuntimeError as e: - cloudlog.warning(f"No orbit data found. {e}") + except (RuntimeError, ValueError, IOError) as e: + cloudlog.warning(f"No orbit data found or parsing failure: {e}") cloudlog.info(f"Done parsing orbits. Took {time.monotonic() - start_time:.1f}s") return data @@ -241,7 +250,7 @@ def kf_add_observations(gnss_kf: GNSSKalman, t: float, measurements: List[GNSSMe ekf_data[ObservationKind.PSEUDORANGE_RATE_GPS] = ekf_data[ObservationKind.PSEUDORANGE_GPS] ekf_data[ObservationKind.PSEUDORANGE_RATE_GLONASS] = ekf_data[ObservationKind.PSEUDORANGE_GLONASS] for kind, data in ekf_data.items(): - if len(data) >0: + if len(data) > 0: gnss_kf.predict_and_observe(t, kind, data) @@ -278,7 +287,6 @@ def main(sm=None, pm=None): pm = messaging.PubMaster(['gnssMeasurements']) replay = "REPLAY" in os.environ - # todo get last_known_position use_internet = "LAIKAD_NO_INTERNET" not in os.environ laikad = Laikad(save_ephemeris=not replay, auto_fetch_orbits=use_internet) while True: diff --git a/selfdrive/locationd/laikad_helpers.py b/selfdrive/locationd/laikad_helpers.py index 81f5ac3dd6..f13e8e73bb 100644 --- a/selfdrive/locationd/laikad_helpers.py +++ b/selfdrive/locationd/laikad_helpers.py @@ -86,4 +86,4 @@ def get_posfix_sympy_fun(constellation): res = [res] + [sympy.diff(res, v) for v in var] - return sympy.lambdify([x, y, z, bc, bg, pr, sat_x, sat_y, sat_z, weight], res) + return sympy.lambdify([x, y, z, bc, bg, pr, sat_x, sat_y, sat_z, weight], res, modules=["numpy"]) diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py index c353da9624..26c1d28820 100755 --- a/selfdrive/locationd/test/test_laikad.py +++ b/selfdrive/locationd/test/test_laikad.py @@ -120,6 +120,18 @@ class TestLaikad(unittest.TestCase): self.assertEqual(correct_msgs_expected, len(correct_msgs)) self.assertEqual(correct_msgs_expected, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid])) + def test_kf_becomes_valid(self): + laikad = Laikad(auto_update=False) + m = self.logs[0] + self.assertFalse(all(laikad.kf_valid(m.logMonoTime * 1e-9))) + kf_valid = False + for m in self.logs: + laikad.process_ublox_msg(m.ubloxGnss, m.logMonoTime, block=True) + kf_valid = all(laikad.kf_valid(m.logMonoTime * 1e-9)) + if kf_valid: + break + self.assertTrue(kf_valid) + def test_laika_online_nav_only(self): laikad = Laikad(auto_update=True, valid_ephem_types=EphemerisType.NAV) # Disable fetch_orbits to test NAV only From c8e5912b6173c64fae18f79109eb72e8499908c9 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 1 Jul 2022 16:43:44 +0200 Subject: [PATCH 188/302] bump laika --- laika_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/laika_repo b/laika_repo index 27a0d8a776..6e87f536db 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 27a0d8a776fc8c1eaf8608d17ce81a00136f8bd0 +Subproject commit 6e87f536dbe8cf80040f724c89798e66ca17cf9d From 12f8237bfbdea668ae96ce6389cbe33ce1bea7f3 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Fri, 1 Jul 2022 16:50:18 +0200 Subject: [PATCH 189/302] process replay: Fix setting environment vars (#25015) Fix setting environments in process replay --- selfdrive/test/process_replay/process_replay.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index fc83b4b61f..9c45281b0c 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -398,8 +398,8 @@ def setup_env(simulation=False, CP=None, cfg=None): if cfg is not None: # Clear all custom processConfig environment variables - for cfg in CONFIGS: - for k, _ in cfg.environ.items(): + for config in CONFIGS: + for k, _ in config.environ.items(): if k in os.environ: del os.environ[k] From f10283072e4519ad95566dd0d54dbc7f52566f6d Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Fri, 1 Jul 2022 16:49:56 +0200 Subject: [PATCH 190/302] Laikad: dont log when filter is not initialized --- selfdrive/locationd/laikad.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 427eb3dbe0..da00c7aa6f 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -141,8 +141,9 @@ class Laikad: # Check time and outputs are valid valid = self.kf_valid(t) if not all(valid): - - if not valid[1]: + if not valid[0]: # Filter not initialized + pass + elif not valid[1]: cloudlog.error("Time gap of over 10s detected, gnss kalman reset") elif not valid[2]: cloudlog.error("Gnss kalman filter state is nan") From cdc7a6dbea75f10316e45833be6bade9f2e1694d Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 1 Jul 2022 17:26:41 +0200 Subject: [PATCH 191/302] enable laikad (#25013) * enable laikad * increase logprint for onroad test --- selfdrive/controls/controlsd.py | 2 +- selfdrive/manager/process_config.py | 2 +- selfdrive/test/test_onroad.py | 1 + 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 67eaf1588b..cceb47947a 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -38,7 +38,7 @@ REPLAY = "REPLAY" in os.environ SIMULATION = "SIMULATION" in os.environ NOSENSOR = "NOSENSOR" in os.environ IGNORE_PROCESSES = {"uploader", "deleter", "loggerd", "logmessaged", "tombstoned", "statsd", - "logcatd", "proclogd", "clocksd", "updated", "timezoned", "manage_athenad"} | \ + "logcatd", "proclogd", "clocksd", "updated", "timezoned", "manage_athenad", "laikad"} | \ {k for k, v in managed_processes.items() if not v.enabled} ThermalStatus = log.DeviceState.ThermalStatus diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index 7e4029664d..dec51966a4 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -41,6 +41,7 @@ procs = [ PythonProcess("controlsd", "selfdrive.controls.controlsd"), PythonProcess("deleter", "selfdrive.loggerd.deleter", offroad=True), PythonProcess("dmonitoringd", "selfdrive.monitoring.dmonitoringd", enabled=(not PC or WEBCAM), callback=driverview), + PythonProcess("laikad", "selfdrive.locationd.laikad"), PythonProcess("navd", "selfdrive.navd.navd"), PythonProcess("pandad", "selfdrive.boardd.pandad", offroad=True), PythonProcess("paramsd", "selfdrive.locationd.paramsd"), @@ -57,7 +58,6 @@ procs = [ # Experimental PythonProcess("rawgpsd", "selfdrive.sensord.rawgps.rawgpsd", enabled=os.path.isfile("/persist/comma/use-quectel-rawgps")), - PythonProcess("laikad", "selfdrive.locationd.laikad", enabled=os.path.isfile("/persist/comma/use-laikad")), ] managed_processes = {p.name: p for p in procs} diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index a7ab55fe2a..8007afb84c 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -118,6 +118,7 @@ class TestOnroad(unittest.TestCase): os.environ['REPLAY'] = "1" os.environ['SKIP_FW_QUERY'] = "1" os.environ['FINGERPRINT'] = "TOYOTA COROLLA TSS2 2019" + os.environ['LOGPRINT'] = 'debug' params = Params() params.clear_all() From 8d6799d95a0a0ab9b2b0bc4ed6998abf6cabf266 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Fri, 1 Jul 2022 17:44:10 +0200 Subject: [PATCH 192/302] Laikad: Allow fetching orbits every minute (#25016) * Allow fetching orbits every minute * Small cleanup --- selfdrive/locationd/laikad.py | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index da00c7aa6f..0df48dd893 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -13,7 +13,7 @@ import numpy as np from cereal import log, messaging from common.params import Params, put_nonblocking from laika import AstroDog -from laika.constants import SECS_IN_HR, SECS_IN_MIN +from laika.constants import SECS_IN_MIN from laika.ephemeris import Ephemeris, EphemerisType, convert_ublox_ephem from laika.gps_time import GPSTime from laika.helpers import ConstellationId @@ -171,7 +171,7 @@ class Laikad: self.gnss_kf.init_state(x_initial, covs_diag=p_initial_diag) def fetch_orbits(self, t: GPSTime, block): - if t not in self.astro_dog.orbit_fetched_times and (self.last_fetch_orbits_t is None or t - self.last_fetch_orbits_t > SECS_IN_HR): + if t not in self.astro_dog.orbit_fetched_times and (self.last_fetch_orbits_t is None or t - self.last_fetch_orbits_t > SECS_IN_MIN): astro_dog_vars = self.astro_dog.valid_const, self.astro_dog.auto_update, self.astro_dog.valid_ephem_types ret = None @@ -195,14 +195,12 @@ def get_orbit_data(t: GPSTime, valid_const, auto_update, valid_ephem_types): astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types) cloudlog.info(f"Start to download/parse orbits for time {t.as_datetime()}") start_time = time.monotonic() - data = None try: astro_dog.get_orbit_data(t, only_predictions=True) - data = (astro_dog.orbits, astro_dog.orbit_fetched_times) + cloudlog.info(f"Done parsing orbits. Took {time.monotonic() - start_time:.1f}s") + return astro_dog.orbits, astro_dog.orbit_fetched_times except (RuntimeError, ValueError, IOError) as e: cloudlog.warning(f"No orbit data found or parsing failure: {e}") - cloudlog.info(f"Done parsing orbits. Took {time.monotonic() - start_time:.1f}s") - return data def create_measurement_msg(meas: GNSSMeasurement): From fcc5b3d70c14b05e642eda93a528f7583f986468 Mon Sep 17 00:00:00 2001 From: Jason Shuler Date: Fri, 1 Jul 2022 16:45:32 -0400 Subject: [PATCH 193/302] GM: values.py cleanup & minor updates (#24908) * Comment update on static limits * Astra FP cleanup * DBC autogen & customizable * Add new Escalade FP, disable bad * Add DROPPED CanBus value * Update/cleanup CarInfo * DBC -> defaultdict * Fix DBC typing issue * Revert Escalade fix * clean up * comment spacing * revert this for now Co-authored-by: Shane Smiskol --- selfdrive/car/gm/values.py | 43 ++++++++++++++++++-------------------- 1 file changed, 20 insertions(+), 23 deletions(-) diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index 8ef33e8297..328ca7c286 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -1,4 +1,5 @@ -from dataclasses import dataclass +from collections import defaultdict +from dataclasses import dataclass, field from enum import Enum from typing import Dict, List, Union @@ -9,9 +10,9 @@ Ecu = car.CarParams.Ecu class CarControllerParams: - STEER_MAX = 300 # Safety limit, not LKA max. Trucks use 600. - STEER_STEP = 2 # control frames per command - STEER_DELTA_UP = 7 + STEER_MAX = 300 # GM limit is 3Nm. Used by carcontroller to generate LKA output + STEER_STEP = 2 # Control frames per command (50hz) + STEER_DELTA_UP = 7 # Delta rates require review due to observed EPS weakness STEER_DELTA_DOWN = 17 MIN_STEER_SPEED = 3. # m/s STEER_DRIVER_ALLOWANCE = 50 @@ -24,19 +25,20 @@ class CarControllerParams: CAMERA_KEEPALIVE_STEP = 100 # Volt gasbrake lookups - MAX_GAS = 3072 # Safety limit, not ACC max. Stock ACC >4096 from standstill. - ZERO_GAS = 2048 # Coasting - MAX_BRAKE = 350 # ~ -3.5 m/s^2 with regen + # TODO: These values should be confirmed on non-Volt vehicles + MAX_GAS = 3072 # Safety limit, not ACC max. Stock ACC >4096 from standstill. + ZERO_GAS = 2048 # Coasting + MAX_BRAKE = 350 # ~ -3.5 m/s^2 with regen + MAX_ACC_REGEN = 1404 # Max ACC regen is slightly less than max paddle regen # Allow small margin below -3.5 m/s^2 from ISO 15622:2018 since we # perform the closed loop control, and might need some # to apply some more braking if we're on a downhill slope. # Our controller should still keep the 2 second average above # -3.5 m/s^2 as per planner limits - ACCEL_MAX = 2. # m/s^2 - ACCEL_MIN = -4. # m/s^2 + ACCEL_MAX = 2. # m/s^2 + ACCEL_MIN = -4. # m/s^2 - MAX_ACC_REGEN = 1404 # Max ACC regen is slightly less than max paddle regen GAS_LOOKUP_BP = [-1., 0., ACCEL_MAX] GAS_LOOKUP_V = [MAX_ACC_REGEN, ZERO_GAS, MAX_GAS] BRAKE_LOOKUP_BP = [ACCEL_MIN, -1.] @@ -67,16 +69,17 @@ class Footnote(Enum): class GMCarInfo(CarInfo): package: str = "Adaptive Cruise" harness: Enum = Harness.none + footnotes: List[Enum] = field(default_factory=lambda: [Footnote.OBD_II]) CAR_INFO: Dict[str, Union[GMCarInfo, List[GMCarInfo]]] = { CAR.HOLDEN_ASTRA: GMCarInfo("Holden Astra 2017", harness=Harness.custom), - CAR.VOLT: GMCarInfo("Chevrolet Volt 2017-18", footnotes=[Footnote.OBD_II], min_enable_speed=0, harness=Harness.custom), + CAR.VOLT: GMCarInfo("Chevrolet Volt 2017-18", min_enable_speed=0, harness=Harness.custom), CAR.CADILLAC_ATS: GMCarInfo("Cadillac ATS Premium Performance 2018"), CAR.MALIBU: GMCarInfo("Chevrolet Malibu Premier 2017", harness=Harness.custom), - CAR.ACADIA: GMCarInfo("GMC Acadia 2018", video_link="https://www.youtube.com/watch?v=0ZN6DdsBUZo", footnotes=[Footnote.OBD_II]), + CAR.ACADIA: GMCarInfo("GMC Acadia 2018", video_link="https://www.youtube.com/watch?v=0ZN6DdsBUZo"), CAR.BUICK_REGAL: GMCarInfo("Buick Regal Essence 2018"), - CAR.ESCALADE_ESV: GMCarInfo("Cadillac Escalade ESV 2016", "ACC + LKAS", footnotes=[Footnote.OBD_II]), + CAR.ESCALADE_ESV: GMCarInfo("Cadillac Escalade ESV 2016", "ACC + LKAS"), } @@ -100,10 +103,12 @@ class CanBus: CHASSIS = 2 SW_GMLAN = 3 LOOPBACK = 128 + DROPPED = 192 FINGERPRINTS = { + CAR.HOLDEN_ASTRA: [ # Astra BK MY17, ASCM unplugged - CAR.HOLDEN_ASTRA: [{ + { 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 401: 8, 413: 8, 417: 8, 419: 8, 422: 1, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 458: 5, 479: 8, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 647: 5, 707: 8, 715: 8, 723: 8, 753: 5, 761: 7, 806: 1, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1009: 8, 1011: 6, 1017: 8, 1019: 3, 1020: 8, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 8, 1280: 4, 1300: 8, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1908: 7, 1912: 7, 1919: 7, }], CAR.VOLT: [ @@ -145,12 +150,4 @@ FINGERPRINTS = { }], } -DBC = { - CAR.HOLDEN_ASTRA: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), - CAR.VOLT: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), - CAR.MALIBU: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), - CAR.ACADIA: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), - CAR.CADILLAC_ATS: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), - CAR.BUICK_REGAL: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), - CAR.ESCALADE_ESV: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), -} +DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis')) From e11bb76a6408c0ceeacd0b4dd7e6ccb7a133387a Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 1 Jul 2022 19:11:28 -0700 Subject: [PATCH 194/302] car docs: remove steering torque hard-coding (#25019) remove good torque hardcoding --- selfdrive/car/docs_definitions.py | 4 ++-- selfdrive/car/hyundai/values.py | 1 - selfdrive/car/mazda/values.py | 4 ++-- selfdrive/car/subaru/values.py | 2 +- selfdrive/car/toyota/values.py | 1 - selfdrive/car/volkswagen/values.py | 1 - 6 files changed, 5 insertions(+), 8 deletions(-) diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index 618c986d18..1efa23037f 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -55,7 +55,6 @@ class CarInfo: footnotes: Optional[List[Enum]] = None min_steer_speed: Optional[float] = None min_enable_speed: Optional[float] = None - good_torque: bool = False harness: Optional[Enum] = None def init(self, CP: car.CarParams, non_tested_cars: List[str], all_footnotes: Dict[Enum, int]): @@ -82,10 +81,11 @@ class CarInfo: Column.LONGITUDINAL: Star.FULL if CP.openpilotLongitudinalControl and not CP.radarOffCan else Star.EMPTY, Column.FSR_LONGITUDINAL: Star.FULL if min_enable_speed <= 0. else Star.EMPTY, Column.FSR_STEERING: Star.FULL if min_steer_speed <= 0. else Star.EMPTY, - Column.STEERING_TORQUE: Star.FULL if self.good_torque else Star.EMPTY, # TODO: remove hardcoding and use maxLateralAccel + # Column.STEERING_TORQUE set below Column.MAINTAINED: Star.FULL if CP.carFingerprint not in non_tested_cars and self.harness is not Harness.none else Star.EMPTY, } + # Set steering torque star from max lateral acceleration if not math.isnan(CP.maxLateralAccel): if CP.maxLateralAccel >= GREAT_TORQUE_THRESHOLD: self.row[Column.STEERING_TORQUE] = Star.FULL diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 645d2f523b..0717ed1fbe 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -89,7 +89,6 @@ class HyundaiCarInfo(CarInfo): # TODO: we can probably remove LKAS. LKAS is standard on many # HKG and for others, it's likely packaged together with SCC package: str = "SCC + LKAS" - good_torque: bool = True CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index f5d63418f1..09b9b7732b 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -40,8 +40,8 @@ CAR_INFO: Dict[str, Union[MazdaCarInfo, List[MazdaCarInfo]]] = { CAR.CX9: MazdaCarInfo("Mazda CX-9 2016-17"), CAR.MAZDA3: MazdaCarInfo("Mazda 3 2017"), CAR.MAZDA6: MazdaCarInfo("Mazda 6 2017"), - CAR.CX9_2021: MazdaCarInfo("Mazda CX-9 2021", good_torque=True), - CAR.CX5_2022: MazdaCarInfo("Mazda CX-5 2022", good_torque=True), + CAR.CX9_2021: MazdaCarInfo("Mazda CX-9 2021"), + CAR.CX5_2022: MazdaCarInfo("Mazda CX-5 2022"), } diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 9badc3ca50..45358eb3a4 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -41,7 +41,7 @@ class SubaruCarInfo(CarInfo): CAR_INFO: Dict[str, Union[SubaruCarInfo, List[SubaruCarInfo]]] = { - CAR.ASCENT: SubaruCarInfo("Subaru Ascent 2019-20", "All", good_torque=True), + CAR.ASCENT: SubaruCarInfo("Subaru Ascent 2019-20", "All"), CAR.IMPREZA: [ SubaruCarInfo("Subaru Impreza 2017-19"), SubaruCarInfo("Subaru Crosstrek 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index c7a26257f3..43d923338e 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -99,7 +99,6 @@ class Footnote(Enum): class ToyotaCarInfo(CarInfo): package: str = "All" harness: Enum = Harness.toyota - good_torque: bool = True CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 0148a138a2..6e64f705b0 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -114,7 +114,6 @@ class Footnote(Enum): @dataclass class VWCarInfo(CarInfo): package: str = "Driver Assistance" - good_torque: bool = True harness: Enum = Harness.vw From 0c95493dc0cbc5d3dec59a50ac5476573041942d Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Fri, 1 Jul 2022 19:14:21 -0700 Subject: [PATCH 195/302] Torque control: max torque warning (#25018) * New steer torque warning * typo --- selfdrive/controls/controlsd.py | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index cceb47947a..3ee47c620b 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -317,7 +317,7 @@ class Controls: self.events.add(EventName.commIssue) elif not self.sm.all_freq_ok(): self.events.add(EventName.commIssueAvgFreq) - else: # invalid or can_rcv_error. + else: # invalid or can_rcv_error. self.events.add(EventName.commIssue) logs = { @@ -598,7 +598,14 @@ class Controls: lac_log.saturated = abs(actuators.steer) >= 0.9 # Send a "steering required alert" if saturation count has reached the limit - if lac_log.active and lac_log.saturated and not CS.steeringPressed: + if lac_log.active and not CS.steeringPressed and self.CP.lateralTuning.which() == 'torque': + undershooting = abs(lac_log.desiredLateralAccel) / abs(1e-3 + lac_log.actualLateralAccel) > 1.2 + turning = abs(lac_log.desiredLateralAccel) > 1.0 + good_speed = CS.vEgo > 5 + max_torque = abs(self.last_actuators.steer) > 0.99 + if undershooting and turning and good_speed and max_torque: + self.events.add(EventName.steerSaturated) + elif lac_log.active and lac_log.saturated and not CS.steeringPressed: dpath_points = lat_plan.dPathPoints if len(dpath_points): # Check if we deviated from the path From 5f794fe49a1e0f2849e6a979c7bd12ca5ddb060a Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 4 Jul 2022 19:55:00 +0800 Subject: [PATCH 196/302] settings.cc: remove function network_panel (#25030) remove function network_panel --- selfdrive/ui/qt/offroad/settings.cc | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 547ad168f1..a03af23951 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -279,10 +279,6 @@ void SoftwarePanel::updateLabels() { osVersionLbl->setText(QString::fromStdString(Hardware::get_os_version()).trimmed()); } -QWidget *network_panel(QWidget *parent) { - return new Networking(parent); -} - void SettingsWindow::showEvent(QShowEvent *event) { panel_widget->setCurrentIndex(0); nav_btns->buttons()[0]->setChecked(true); @@ -328,7 +324,7 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) { QList> panels = { {tr("Device"), device}, - {tr("Network"), network_panel(this)}, + {tr("Network"), new Networking(this)}, {tr("Toggles"), new TogglesPanel(this)}, {tr("Software"), new SoftwarePanel(this)}, }; From 735387d5eea7e76d1940a82b0b5dcaddf1eb264a Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 4 Jul 2022 13:57:25 +0200 Subject: [PATCH 197/302] bump opendbc --- opendbc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc b/opendbc index 7fbf7c2a68..9c7248ceb2 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 7fbf7c2a685a90ff01e744cfb410f1a8a3c06278 +Subproject commit 9c7248ceb269928e3741103f978e9e4de2b38156 From d4cc13c88a8a9a9215777709fe2eccade1fd0ccd Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 4 Jul 2022 17:13:30 +0200 Subject: [PATCH 198/302] controlsd: avoid lag on first iteration due to get_short_branch (#25031) * controlsd: avoid lag on first iteration due to get_short_branch * always cache --- selfdrive/controls/controlsd.py | 4 ++++ selfdrive/controls/lib/events.py | 2 +- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 3ee47c620b..9e3af9eb63 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -12,6 +12,7 @@ import cereal.messaging as messaging from common.conversions import Conversions as CV from panda import ALTERNATIVE_EXPERIENCE from system.swaglog import cloudlog +from system.version import get_short_branch from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.car.car_helpers import get_car, get_startup_event, get_one_can from selfdrive.controls.lib.lane_planner import CAMERA_OFFSET @@ -62,6 +63,9 @@ class Controls: def __init__(self, sm=None, pm=None, can_sock=None, CI=None): config_realtime_process(4, Priority.CTRL_HIGH) + # Ensure the current branch is cached, otherwise the first iteration of controlsd lags + self.branch = get_short_branch("") + # Setup sockets self.pm = pm if self.pm is None: diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index cc63d4995d..95ccb7b7ec 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -222,7 +222,7 @@ def user_soft_disable_alert(alert_text_2: str) -> AlertCallbackType: return func def startup_master_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: - branch = get_short_branch("") + branch = get_short_branch("") # Ensure get_short_branch is cached to avoid lags on startup if "REPLAY" in os.environ: branch = "replay" From 39007810927faa309d06e6ad9586302341547f64 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 5 Jul 2022 16:55:32 +0200 Subject: [PATCH 199/302] add casync support to agnos updater (#23654) * add casync option to agnos updater * open if necessary * add python implementation * last chunk can be small * check flags * cleaner check * add remote and file stores * remote caibx file * print stats * use python implementation * clean up imports * add progress * fix logging * fix duplicate chunks * add comments * json stats * cleanup tmp * normal image is still sparse * Update system/hardware/tici/agnos.py Co-authored-by: Adeeb Shihadeh * Update system/hardware/tici/agnos.py Co-authored-by: Adeeb Shihadeh * add some types * remove comment * create Chunk type * make readers a class * try agnos 5.2 * add download retries * catch all exceptions * sleep between retry * revert agnos.json changes Co-authored-by: Adeeb Shihadeh --- system/hardware/tici/agnos.py | 95 ++++++++++++---- system/hardware/tici/casync.py | 192 +++++++++++++++++++++++++++++++++ 2 files changed, 265 insertions(+), 22 deletions(-) create mode 100755 system/hardware/tici/casync.py diff --git a/system/hardware/tici/agnos.py b/system/hardware/tici/agnos.py index e664654c65..527422aca7 100755 --- a/system/hardware/tici/agnos.py +++ b/system/hardware/tici/agnos.py @@ -1,13 +1,16 @@ #!/usr/bin/env python3 +import hashlib import json import lzma -import hashlib -import requests +import os import struct import subprocess import time -import os -from typing import Dict, Generator, Union +from typing import Dict, Generator, List, Tuple, Union + +import requests + +import system.hardware.tici.casync as casync SPARSE_CHUNK_FMT = struct.Struct('H2xI4x') @@ -74,6 +77,7 @@ def unsparsify(f: StreamingDecompressor) -> Generator[bytes, None, None]: else: raise Exception("Unhandled sparse chunk type") + # noop wrapper with same API as unsparsify() for non sparse images def noop(f: StreamingDecompressor) -> Generator[bytes, None, None]: while not f.eof: @@ -99,8 +103,8 @@ def get_partition_path(target_slot_number: int, partition: dict) -> str: return path -def verify_partition(target_slot_number: int, partition: Dict[str, Union[str, int]]) -> bool: - full_check = partition['full_check'] +def verify_partition(target_slot_number: int, partition: Dict[str, Union[str, int]], force_full_check: bool = False) -> bool: + full_check = partition['full_check'] or force_full_check path = get_partition_path(target_slot_number, partition) if not isinstance(partition['size'], int): return False @@ -135,21 +139,10 @@ def clear_partition_hash(target_slot_number: int, partition: dict) -> None: os.sync() -def flash_partition(target_slot_number: int, partition: dict, cloudlog): - cloudlog.info(f"Downloading and writing {partition['name']}") - - if verify_partition(target_slot_number, partition): - cloudlog.info(f"Already flashed {partition['name']}") - return - +def extract_compressed_image(target_slot_number: int, partition: dict, cloudlog): + path = get_partition_path(target_slot_number, partition) downloader = StreamingDecompressor(partition['url']) - # Clear hash before flashing in case we get interrupted - full_check = partition['full_check'] - if not full_check: - clear_partition_hash(target_slot_number, partition) - - path = get_partition_path(target_slot_number, partition) with open(path, 'wb+') as out: # Flash partition last_p = 0 @@ -172,9 +165,67 @@ def flash_partition(target_slot_number: int, partition: dict, cloudlog): if out.tell() != partition['size']: raise Exception("Uncompressed size mismatch") - # Write hash after successfull flash os.sync() - if not full_check: + + +def extract_casync_image(target_slot_number: int, partition: dict, cloudlog): + path = get_partition_path(target_slot_number, partition) + seed_path = path[:-1] + ('b' if path[-1] == 'a' else 'a') + + target = casync.parse_caibx(partition['casync_caibx']) + + sources: List[Tuple[str, casync.ChunkReader, casync.ChunkDict]] = [] + + # First source is the current partition. Index file for current version is provided in the manifest + if 'casync_seed_caibx' in partition: + sources += [('seed', casync.FileChunkReader(seed_path), casync.build_chunk_dict(casync.parse_caibx(partition['casync_seed_caibx'])))] + + # Second source is the target partition, this allows for resuming + sources += [('target', casync.FileChunkReader(path), casync.build_chunk_dict(target))] + + # Finally we add the remote source to download any missing chunks + sources += [('remote', casync.RemoteChunkReader(partition['casync_store']), casync.build_chunk_dict(target))] + + last_p = 0 + + def progress(cur): + nonlocal last_p + p = int(cur / partition['size'] * 100) + if p != last_p: + last_p = p + print(f"Installing {partition['name']}: {p}", flush=True) + + stats = casync.extract(target, sources, path, progress) + cloudlog.error(f'casync done {json.dumps(stats)}') + + os.sync() + if not verify_partition(target_slot_number, partition, force_full_check=True): + raise Exception(f"Raw hash mismatch '{partition['hash_raw'].lower()}'") + + +def flash_partition(target_slot_number: int, partition: dict, cloudlog): + cloudlog.info(f"Downloading and writing {partition['name']}") + + if verify_partition(target_slot_number, partition): + cloudlog.info(f"Already flashed {partition['name']}") + return + + # Clear hash before flashing in case we get interrupted + full_check = partition['full_check'] + if not full_check: + clear_partition_hash(target_slot_number, partition) + + path = get_partition_path(target_slot_number, partition) + + if 'casync_caibx' in partition: + extract_casync_image(target_slot_number, partition, cloudlog) + else: + extract_compressed_image(target_slot_number, partition, cloudlog) + + # Write hash after successfull flash + if not full_check: + with open(path, 'wb+') as out: + out.seek(partition['size']) out.write(partition['hash_raw'].lower().encode()) @@ -228,8 +279,8 @@ def verify_agnos_update(manifest_path: str, target_slot_number: int) -> bool: if __name__ == "__main__": - import logging import argparse + import logging parser = argparse.ArgumentParser(description="Flash and verify AGNOS update", formatter_class=argparse.ArgumentDefaultsHelpFormatter) diff --git a/system/hardware/tici/casync.py b/system/hardware/tici/casync.py new file mode 100755 index 0000000000..e77f473636 --- /dev/null +++ b/system/hardware/tici/casync.py @@ -0,0 +1,192 @@ +#!/usr/bin/env python3 +import io +import lzma +import os +import struct +import sys +import time +from abc import ABC, abstractmethod +from collections import defaultdict, namedtuple +from typing import Callable, Dict, List, Optional, Tuple + +import requests +from Crypto.Hash import SHA512 + +CA_FORMAT_INDEX = 0x96824d9c7b129ff9 +CA_FORMAT_TABLE = 0xe75b9e112f17417d +CA_FORMAT_TABLE_TAIL_MARKER = 0xe75b9e112f17417 +FLAGS = 0xb000000000000000 + +CA_HEADER_LEN = 48 +CA_TABLE_HEADER_LEN = 16 +CA_TABLE_ENTRY_LEN = 40 +CA_TABLE_MIN_LEN = CA_TABLE_HEADER_LEN + CA_TABLE_ENTRY_LEN + +CHUNK_DOWNLOAD_TIMEOUT = 10 +CHUNK_DOWNLOAD_RETRIES = 3 + +CAIBX_DOWNLOAD_TIMEOUT = 120 + +Chunk = namedtuple('Chunk', ['sha', 'offset', 'length']) +ChunkDict = Dict[bytes, Chunk] + + +class ChunkReader(ABC): + @abstractmethod + def read(self, chunk: Chunk) -> bytes: + ... + + +class FileChunkReader(ChunkReader): + """Reads chunks from a local file""" + def __init__(self, fn: str) -> None: + + super().__init__() + self.f = open(fn, 'rb') + + def read(self, chunk: Chunk) -> bytes: + self.f.seek(chunk.offset) + return self.f.read(chunk.length) + + +class RemoteChunkReader(ChunkReader): + """Reads lzma compressed chunks from a remote store""" + + def __init__(self, url: str) -> None: + super().__init__() + self.url = url + + def read(self, chunk: Chunk) -> bytes: + sha_hex = chunk.sha.hex() + url = os.path.join(self.url, sha_hex[:4], sha_hex + ".cacnk") + + for i in range(CHUNK_DOWNLOAD_RETRIES): + try: + resp = requests.get(url, timeout=CHUNK_DOWNLOAD_TIMEOUT) + break + except Exception: + if i == CHUNK_DOWNLOAD_RETRIES - 1: + raise + time.sleep(CHUNK_DOWNLOAD_TIMEOUT) + + resp.raise_for_status() + + decompressor = lzma.LZMADecompressor(format=lzma.FORMAT_AUTO) + return decompressor.decompress(resp.content) + + +def parse_caibx(caibx_path: str) -> List[Chunk]: + """Parses the chunks from a caibx file. Can handle both local and remote files. + Returns a list of chunks with hash, offset and length""" + if os.path.isfile(caibx_path): + caibx = open(caibx_path, 'rb') + else: + resp = requests.get(caibx_path, timeout=CAIBX_DOWNLOAD_TIMEOUT) + resp.raise_for_status() + caibx = io.BytesIO(resp.content) + + caibx.seek(0, os.SEEK_END) + caibx_len = caibx.tell() + caibx.seek(0, os.SEEK_SET) + + # Parse header + length, magic, flags, min_size, _, max_size = struct.unpack("= min_size + + chunks.append(Chunk(sha, offset, length)) + offset = new_offset + + return chunks + + +def build_chunk_dict(chunks: List[Chunk]) -> ChunkDict: + """Turn a list of chunks into a dict for faster lookups based on hash""" + return {c.sha: c for c in chunks} + + +def extract(target: List[Chunk], + sources: List[Tuple[str, ChunkReader, ChunkDict]], + out_path: str, + progress: Optional[Callable[[int], None]] = None): + stats: Dict[str, int] = defaultdict(int) + + with open(out_path, 'wb') as out: + for cur_chunk in target: + + # Find source for desired chunk + for name, chunk_reader, store_chunks in sources: + if cur_chunk.sha in store_chunks: + bts = chunk_reader.read(store_chunks[cur_chunk.sha]) + + # Check length + if len(bts) != cur_chunk.length: + continue + + # Check hash + if SHA512.new(bts, truncate="256").digest() != cur_chunk.sha: + continue + + # Write to output + out.seek(cur_chunk.offset) + out.write(bts) + + stats[name] += cur_chunk.length + + if progress is not None: + progress(sum(stats.values())) + + break + else: + raise RuntimeError("Desired chunk not found in provided stores") + + return stats + + +def print_stats(stats: Dict[str, int]): + total_bytes = sum(stats.values()) + print(f"Total size: {total_bytes / 1024 / 1024:.2f} MB") + for name, total in stats.items(): + print(f" {name}: {total / 1024 / 1024:.2f} MB ({total / total_bytes * 100:.1f}%)") + + +def extract_simple(caibx_path, out_path, store_path): + # (name, callback, chunks) + target = parse_caibx(caibx_path) + sources = [ + # (store_path, RemoteChunkReader(store_path), build_chunk_dict(target)), + (store_path, FileChunkReader(store_path), build_chunk_dict(target)), + ] + + return extract(target, sources, out_path) + + +if __name__ == "__main__": + caibx = sys.argv[1] + out = sys.argv[2] + store = sys.argv[3] + + stats = extract_simple(caibx, out, store) + print_stats(stats) From 06a8ac627c0b8cf00b3bd4ea7186f5c876f71561 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 5 Jul 2022 18:06:08 +0200 Subject: [PATCH 200/302] casync: build_chunk_dict optimize for resuming (#25038) --- system/hardware/tici/casync.py | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/system/hardware/tici/casync.py b/system/hardware/tici/casync.py index e77f473636..b857c04795 100755 --- a/system/hardware/tici/casync.py +++ b/system/hardware/tici/casync.py @@ -123,8 +123,13 @@ def parse_caibx(caibx_path: str) -> List[Chunk]: def build_chunk_dict(chunks: List[Chunk]) -> ChunkDict: - """Turn a list of chunks into a dict for faster lookups based on hash""" - return {c.sha: c for c in chunks} + """Turn a list of chunks into a dict for faster lookups based on hash. + Keep first chunk since it's more likely to be already downloaded.""" + r = {} + for c in chunks: + if c.sha not in r: + r[c.sha] = c + return r def extract(target: List[Chunk], From 0bf1462ad0a459f8a2cc863f58089540789922f1 Mon Sep 17 00:00:00 2001 From: martinl Date: Tue, 5 Jul 2022 20:33:20 +0300 Subject: [PATCH 201/302] Update path for github workflow hardware unit tests (#25035) * Update hardware path for github workflow unit tests * Update release/files_common Co-authored-by: Adeeb Shihadeh --- .github/workflows/selfdrive_tests.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 0ff0092b02..35a08d4fe9 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -302,7 +302,7 @@ jobs: selfdrive/locationd/test/_test_locationd_lib.py && \ $UNIT_TEST selfdrive/athena && \ $UNIT_TEST selfdrive/thermald && \ - $UNIT_TEST selfdrive/hardware/tici && \ + $UNIT_TEST system/hardware/tici && \ $UNIT_TEST selfdrive/modeld && \ $UNIT_TEST tools/lib/tests && \ ./selfdrive/ui/tests/create_test_translations.sh && \ From d4f4809992c5c73e36ec1041445e6a11b2c68448 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 5 Jul 2022 14:28:54 -0700 Subject: [PATCH 202/302] always show avg power --- tools/zookeeper/power_monitor.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/tools/zookeeper/power_monitor.py b/tools/zookeeper/power_monitor.py index f88741813e..fa1f442bbc 100755 --- a/tools/zookeeper/power_monitor.py +++ b/tools/zookeeper/power_monitor.py @@ -27,8 +27,10 @@ if __name__ == "__main__": while duration is None or time.monotonic() - start_time < duration: fltr.update(z.read_power()) if rk.frame % rate == 0: - print(f"{fltr.x:.2f} W") measurements.append(fltr.x) + t = datetime.timedelta(seconds=time.monotonic() - start_time) + avg = sum(measurements) / len(measurements) + print(f"Now: {fltr.x:.2f} W, Avg: {avg:.2f} W over {t}") rk.keep_time() except KeyboardInterrupt: pass From 88a30004e0bf96601e5b8fc4c084219c52a46e15 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 5 Jul 2022 16:40:47 -0700 Subject: [PATCH 203/302] Chrysler: prep for Ram port (#25040) * Chrysler: prep for Ram port * bump opendbc * opendbc master * bump panda --- opendbc | 2 +- panda | 2 +- release/files_common | 4 +--- selfdrive/car/chrysler/carstate.py | 20 ++++++++++---------- selfdrive/car/chrysler/chryslercan.py | 6 +++--- selfdrive/car/chrysler/values.py | 14 +++++++------- 6 files changed, 23 insertions(+), 25 deletions(-) diff --git a/opendbc b/opendbc index 9c7248ceb2..b2895650c7 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 9c7248ceb269928e3741103f978e9e4de2b38156 +Subproject commit b2895650c744e24d48cee2f13563dcd5b030a271 diff --git a/panda b/panda index 2652453892..6c0d0b43c2 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 265245389208e1e6ada86b169e879c0a2e30426c +Subproject commit 6c0d0b43c239b89baa83b4a1885d0ce21ab2335e diff --git a/release/files_common b/release/files_common index acf74e2137..e32277dfd8 100644 --- a/release/files_common +++ b/release/files_common @@ -35,7 +35,6 @@ common/filter_simple.py common/stat_live.py common/spinner.py common/text_window.py -common/SConscript common/kalman/.gitignore common/kalman/* @@ -217,7 +216,6 @@ selfdrive/locationd/generated/gps.h selfdrive/locationd/laikad.py selfdrive/locationd/laikad_helpers.py -selfdrive/locationd/locationd.cc selfdrive/locationd/locationd.h selfdrive/locationd/locationd.cc selfdrive/locationd/paramsd.py @@ -475,7 +473,7 @@ opendbc/can/parser_pyx.pyx opendbc/comma_body.dbc -opendbc/chrysler_pacifica_2017_hybrid.dbc +opendbc/chrysler_pacifica_2017_hybrid_generated.dbc opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc opendbc/gm_global_a_powertrain_generated.dbc diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index 444557191a..aa46ea0d94 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -64,14 +64,14 @@ class CarState(CarStateBase): steer_state = cp.vl["EPS_2"]["LKAS_STATE"] ret.steerFaultPermanent = steer_state == 4 or (steer_state == 0 and ret.vEgo > self.CP.minSteerSpeed) - ret.genericToggle = bool(cp.vl["STEERING_LEVERS"]["HIGH_BEAM_FLASH"]) + ret.genericToggle = bool(cp.vl["STEERING_LEVERS"]["HIGH_BEAM_PRESSED"]) if self.CP.enableBsm: - ret.leftBlindspot = cp.vl["BLIND_SPOT_WARNINGS"]["BLIND_SPOT_LEFT"] == 1 - ret.rightBlindspot = cp.vl["BLIND_SPOT_WARNINGS"]["BLIND_SPOT_RIGHT"] == 1 + ret.leftBlindspot = cp.vl["BSM_1"]["LEFT_STATUS"] == 1 + ret.rightBlindspot = cp.vl["BSM_1"]["RIGHT_STATUS"] == 1 self.lkas_counter = cp_cam.vl["LKAS_COMMAND"]["COUNTER"] - self.lkas_car_model = cp_cam.vl["LKAS_HUD"]["CAR_MODEL"] + self.lkas_car_model = cp_cam.vl["DAS_6"]["CAR_MODEL"] self.lkas_status_ok = cp_cam.vl["LKAS_HEARTBIT"]["LKAS_STATUS_OK"] self.button_counter = cp.vl["CRUISE_BUTTONS"]["COUNTER"] @@ -100,7 +100,7 @@ class CarState(CarStateBase): ("ACC_AVAILABLE", "DAS_3"), ("ACC_ACTIVE", "DAS_3"), ("ACC_FAULTED", "DAS_3"), - ("HIGH_BEAM_FLASH", "STEERING_LEVERS"), + ("HIGH_BEAM_PRESSED", "STEERING_LEVERS"), ("ACC_SPEED_CONFIG_KPH", "DAS_4"), ("CRUISE_STATE", "DAS_4"), ("COLUMN_TORQUE", "EPS_2"), @@ -132,10 +132,10 @@ class CarState(CarStateBase): if CP.enableBsm: signals += [ - ("BLIND_SPOT_RIGHT", "BLIND_SPOT_WARNINGS"), - ("BLIND_SPOT_LEFT", "BLIND_SPOT_WARNINGS"), + ("RIGHT_STATUS", "BSM_1"), + ("LEFT_STATUS", "BSM_1"), ] - checks.append(("BLIND_SPOT_WARNINGS", 2)) + checks.append(("BSM_1", 2)) return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) @@ -144,13 +144,13 @@ class CarState(CarStateBase): signals = [ # sig_name, sig_address ("COUNTER", "LKAS_COMMAND"), - ("CAR_MODEL", "LKAS_HUD"), + ("CAR_MODEL", "DAS_6"), ("LKAS_STATUS_OK", "LKAS_HEARTBIT") ] checks = [ ("LKAS_COMMAND", 100), ("LKAS_HEARTBIT", 10), - ("LKAS_HUD", 4), + ("DAS_6", 4), ] return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2) diff --git a/selfdrive/car/chrysler/chryslercan.py b/selfdrive/car/chrysler/chryslercan.py index 53b79cab73..adcd411d31 100644 --- a/selfdrive/car/chrysler/chryslercan.py +++ b/selfdrive/car/chrysler/chryslercan.py @@ -35,14 +35,14 @@ def create_lkas_hud(packer, gear, lkas_active, hud_alert, hud_count, lkas_car_mo "LKAS_ALERTS": alerts, # byte 3, last 4 bits } - return packer.make_can_msg("LKAS_HUD", 0, values) # 0x2a6 + return packer.make_can_msg("DAS_6", 0, values) # 0x2a6 def create_lkas_command(packer, apply_steer, moving_fast, frame): # LKAS_COMMAND 0x292 (658) Lane-keeping signal to turn the wheel. values = { - "LKAS_STEERING_TORQUE": apply_steer, - "LKAS_HIGH_TORQUE": int(moving_fast), + "STEERING_TORQUE": apply_steer, + "LKAS_CONTROL_BIT": int(moving_fast), "COUNTER": frame % 0x10, } return packer.make_can_msg("LKAS_COMMAND", 0, values) diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index d624bd2727..5537b383d3 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -101,13 +101,13 @@ FINGERPRINTS = { DBC = { - CAR.PACIFICA_2017_HYBRID: dbc_dict('chrysler_pacifica_2017_hybrid', 'chrysler_pacifica_2017_hybrid_private_fusion'), - CAR.PACIFICA_2018: dbc_dict('chrysler_pacifica_2017_hybrid', 'chrysler_pacifica_2017_hybrid_private_fusion'), - CAR.PACIFICA_2020: dbc_dict('chrysler_pacifica_2017_hybrid', 'chrysler_pacifica_2017_hybrid_private_fusion'), - CAR.PACIFICA_2018_HYBRID: dbc_dict('chrysler_pacifica_2017_hybrid', 'chrysler_pacifica_2017_hybrid_private_fusion'), - CAR.PACIFICA_2019_HYBRID: dbc_dict('chrysler_pacifica_2017_hybrid', 'chrysler_pacifica_2017_hybrid_private_fusion'), - CAR.JEEP_CHEROKEE: dbc_dict('chrysler_pacifica_2017_hybrid', 'chrysler_pacifica_2017_hybrid_private_fusion'), - CAR.JEEP_CHEROKEE_2019: dbc_dict('chrysler_pacifica_2017_hybrid', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.PACIFICA_2017_HYBRID: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.PACIFICA_2018: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.PACIFICA_2020: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.PACIFICA_2018_HYBRID: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.PACIFICA_2019_HYBRID: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.JEEP_CHEROKEE: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.JEEP_CHEROKEE_2019: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), } STEER_THRESHOLD = 120 From eaa8b08510057c089520f4ba410218be261c9158 Mon Sep 17 00:00:00 2001 From: martinl Date: Wed, 6 Jul 2022 02:42:53 +0300 Subject: [PATCH 204/302] Subaru: XV is supported (#25034) * Subaru: add XV to supported models * Update docs --- docs/CARS.md | 6 ++++-- selfdrive/car/subaru/values.py | 2 ++ 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 25de6a2549..0cf384df18 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -71,7 +71,7 @@ How We Rate The Cars |Toyota|RAV4 2019-21|All|||||| |Toyota|RAV4 Hybrid 2019-21|All|||||| -# Silver - 67 cars +# Silver - 68 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -120,6 +120,7 @@ How We Rate The Cars |Subaru|Crosstrek 2020-21|EyeSight|||||| |Subaru|Forester 2019-21|All|||||| |Subaru|Impreza 2020-21|EyeSight|||||| +|Subaru|XV 2020-21|EyeSight|||||| |Toyota|Alphard 2019-20|All|||||| |Toyota|Alphard Hybrid 2021|All|||||| |Toyota|Camry 2018-20|All||[4](#footnotes)|||| @@ -143,7 +144,7 @@ How We Rate The Cars |Volkswagen|Passat 2015-19[6](#footnotes)|Driver Assistance|||||| |Volkswagen|Polo 2020|Driver Assistance|||||| -# Bronze - 78 cars +# Bronze - 79 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -199,6 +200,7 @@ How We Rate The Cars |Mazda|CX-9 2021|All|||||| |Subaru|Crosstrek 2018-19|EyeSight|||||| |Subaru|Impreza 2017-19|EyeSight|||||| +|Subaru|XV 2018-19|EyeSight|||||| |Škoda|Kamiq 2021[5](#footnotes)|Driver Assistance|||||| |Škoda|Karoq 2019|Driver Assistance|||||| |Škoda|Kodiaq 2018-19|Driver Assistance|||||| diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 45358eb3a4..ea923b1b50 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -45,10 +45,12 @@ CAR_INFO: Dict[str, Union[SubaruCarInfo, List[SubaruCarInfo]]] = { CAR.IMPREZA: [ SubaruCarInfo("Subaru Impreza 2017-19"), SubaruCarInfo("Subaru Crosstrek 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), + SubaruCarInfo("Subaru XV 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), ], CAR.IMPREZA_2020: [ SubaruCarInfo("Subaru Impreza 2020-21"), SubaruCarInfo("Subaru Crosstrek 2020-21"), + SubaruCarInfo("Subaru XV 2020-21"), ], CAR.FORESTER: SubaruCarInfo("Subaru Forester 2019-21", "All"), CAR.FORESTER_PREGLOBAL: SubaruCarInfo("Subaru Forester 2017-18"), From f21b56f25af5ee0930dc8f991aac4e9c438b3cda Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 5 Jul 2022 20:04:48 -0700 Subject: [PATCH 205/302] regen migration: use Panda safety parameters (#25043) no magic numbers --- selfdrive/test/process_replay/regen.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py index d2f239c249..793e548705 100755 --- a/selfdrive/test/process_replay/regen.py +++ b/selfdrive/test/process_replay/regen.py @@ -15,6 +15,8 @@ from cereal.visionipc import VisionIpcServer, VisionStreamType from common.params import Params from common.realtime import Ratekeeper, DT_MDL, DT_DMON, sec_since_boot from common.transformations.camera import eon_f_frame_size, eon_d_frame_size, tici_f_frame_size, tici_d_frame_size +from panda.python import Panda +from selfdrive.car.toyota.values import EPS_SCALE from selfdrive.manager.process import ensure_running from selfdrive.manager.process_config import managed_processes from selfdrive.test.process_replay.process_replay import FAKEDATA, setup_env, check_enabled @@ -30,8 +32,8 @@ def replay_panda_states(s, msgs): # TODO: new safety params from flags, remove after getting new routes for Toyota safety_param_migration = { - "TOYOTA PRIUS 2017": 578, - "TOYOTA RAV4 2017": 329 + "TOYOTA PRIUS 2017": EPS_SCALE["TOYOTA PRIUS 2017"] | Panda.FLAG_TOYOTA_STOCK_LONGITUDINAL, + "TOYOTA RAV4 2017": EPS_SCALE["TOYOTA RAV4 2017"] | Panda.FLAG_TOYOTA_ALT_BRAKE, } # Migrate safety param base on carState From 972e24ee263d7c86b865632f4bb110bbde1b16ac Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Wed, 6 Jul 2022 00:06:25 -0500 Subject: [PATCH 206/302] Add new LEXUS_RX_TSS2 engine f/w (#25041) `@ibby1137#8978` 2022 Lexus RX350L AWD DongleID|route abc09032f402f271|2022-07-05--17-34-41 --- selfdrive/car/toyota/values.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 43d923338e..283c137c91 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1761,13 +1761,14 @@ FW_VERSIONS = { b'\x01896630EB0000\x00\x00\x00\x00', b'\x01896630EC9000\x00\x00\x00\x00', b'\x01896630ED0000\x00\x00\x00\x00', + b'\x01896630ED0100\x00\x00\x00\x00', b'\x01896630ED6000\x00\x00\x00\x00', b'\x018966348W5100\x00\x00\x00\x00', b'\x018966348W9000\x00\x00\x00\x00', b'\x01896634D12000\x00\x00\x00\x00', b'\x01896634D12100\x00\x00\x00\x00', b'\x01896634D43000\x00\x00\x00\x00', - b'\x01896630ED0100\x00\x00\x00\x00', + b'\x01896634D44000\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'\x01F15260E031\x00\x00\x00\x00\x00\x00', From 73a6348be7f20fd2c4e303ca7ff7490b71bff59f Mon Sep 17 00:00:00 2001 From: haram-KONA <88036668+haram-KONA@users.noreply.github.com> Date: Wed, 6 Jul 2022 14:08:36 +0900 Subject: [PATCH 207/302] car docs: add video for Hyundai Kona Hybrid 2020 (#25029) * Update values.py Added the following video link "https://www.youtube.com/watch?v=0dwpAHiZgFo" * Update values.py * Update selfdrive/car/hyundai/values.py * Update selfdrive/car/hyundai/values.py Co-authored-by: Shane Smiskol --- selfdrive/car/hyundai/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 0717ed1fbe..f6efedb248 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -105,7 +105,7 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { CAR.IONIQ_PHEV: HyundaiCarInfo("Hyundai Ioniq Plug-in Hybrid 2020-21", harness=Harness.hyundai_h), CAR.KONA: HyundaiCarInfo("Hyundai Kona 2020", harness=Harness.hyundai_b), CAR.KONA_EV: HyundaiCarInfo("Hyundai Kona Electric 2018-21", harness=Harness.hyundai_g), - CAR.KONA_HEV: HyundaiCarInfo("Hyundai Kona Hybrid 2020", harness=Harness.hyundai_i), + CAR.KONA_HEV: HyundaiCarInfo("Hyundai Kona Hybrid 2020", video_link="https://youtu.be/0dwpAHiZgFo", harness=Harness.hyundai_i), CAR.SANTA_FE: HyundaiCarInfo("Hyundai Santa Fe 2019-20", "All", harness=Harness.hyundai_d), CAR.SANTA_FE_2022: HyundaiCarInfo("Hyundai Santa Fe 2021-22", "All", harness=Harness.hyundai_l), CAR.SANTA_FE_HEV_2022: HyundaiCarInfo("Hyundai Santa Fe Hybrid 2022", "All", harness=Harness.hyundai_l), From 38427e6fbbe1eb09c8a335f8c9aa90460d6bbfde Mon Sep 17 00:00:00 2001 From: BirdZhang <0312birdzhang@gmail.com> Date: Wed, 6 Jul 2022 13:11:21 +0800 Subject: [PATCH 208/302] Toyota: add missing esp FW version for 2021 Toyota Corolla (#25026) 2021 Toyota Levin hybrid (aka Corolla) --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 283c137c91..86283bc48f 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -816,6 +816,7 @@ FW_VERSIONS = { b'F152676303\x00\x00\x00\x00\x00\x00', b'F152676304\x00\x00\x00\x00\x00\x00', b'F152612D00\x00\x00\x00\x00\x00\x00', + b'F152612842\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301100\x00\x00\x00\x00', From f797567ef8c574027eec8da72a2c76cfb2fdafe1 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 5 Jul 2022 22:19:20 -0700 Subject: [PATCH 209/302] long planner: run when using stock longitudinal (#25017) * Squashed commit of the following: commit e27a5b4e2bfeab4e6a47440b1d4eb180ee4acf49 Author: Shane Smiskol Date: Fri Jul 1 14:10:06 2022 -0700 remove this test remove this test commit c3c10af82222ea4641d94c53a3a07b486cca8452 Author: Shane Smiskol Date: Fri Jul 1 14:08:15 2022 -0700 only planner changes commit 50e0f1d8704c15acfce8987faf3515c99e8af4f4 Merge: e088fde67 fcc5b3d70 Author: Shane Smiskol Date: Fri Jul 1 14:05:36 2022 -0700 Merge remote-tracking branch 'upstream/master' into enable-planner2 commit e088fde67edcc32ccfeea23b4ae9e44845240429 Author: Shane Smiskol Date: Thu Jun 30 13:58:38 2022 -0700 no walrus commit b7b425e530e949b9cc427833562473cc241d1367 Merge: f8634266b c49f997be Author: Shane Smiskol Date: Thu Jun 30 13:54:30 2022 -0700 Merge remote-tracking branch 'upstream/master' into enable-planner commit f8634266b49c3f692b255e6cfac66cccc438ae20 Author: Shane Smiskol Date: Wed Jun 29 16:07:35 2022 -0700 stricter test, speeds[-1] is 0.14 when starting here commit c9e446ad2183feba9d03ee39f9801091ab791c08 Merge: e6c4106ea 879a7c320 Author: Shane Smiskol Date: Wed Jun 29 16:01:32 2022 -0700 Merge remote-tracking branch 'upstream/master' into enable-planner commit e6c4106ea185c68a6c7b3d59d5bde664df8bdc9c Author: Shane Smiskol Date: Sat Jun 25 03:28:41 2022 -0700 fix test commit 0520c7f21613b57b804e08a8e8d10950ac059074 Author: Shane Smiskol Date: Sat Jun 25 03:26:16 2022 -0700 add test for resuming commit 04db5f80bff4a002f5241765a625d7cf57b74364 Merge: e23b37d3f d8bfe2f00 Author: Shane Smiskol Date: Wed Jun 22 20:15:50 2022 -0700 Merge remote-tracking branch 'upstream/master' into enable-planner commit e23b37d3fe8dd3dd07b46a32a4f0564fabade1aa Author: Shane Smiskol Date: Tue Jun 21 12:46:04 2022 -0700 0.1 should be pretty safe commit e7dc3960da3d713753f28732f50dbd25811fad28 Author: Shane Smiskol Date: Tue Jun 21 12:39:30 2022 -0700 try 0.2 commit ff0597ec92a0d2c52915316961ec123b0183c5cf Author: Shane Smiskol Date: Tue Jun 21 11:34:00 2022 -0700 Always run planner if not opLong commit 13997c55271f79fd3ca62d6db45ec3790b09aa60 Merge: d2f51ee55 95d8517a8 Author: Shane Smiskol Date: Tue Jun 21 11:29:22 2022 -0700 Merge remote-tracking branch 'upstream/master' into enable-planner commit d2f51ee55fd3bde38275371e76714d7741bc6f6b Author: Shane Smiskol Date: Tue Jun 21 11:27:45 2022 -0700 same for non-HDA2 commit 6a63bd60f09a0abd9185049cd173100d3ef6fefa Author: Shane Smiskol Date: Mon Jun 20 23:37:07 2022 -0700 mazda: ensure no resume if cancelling commit 5771cdecab7999765d9f5203c75a67f1555cf975 Author: Shane Smiskol Date: Mon Jun 20 23:27:58 2022 -0700 maintain original button msg rate commit 6c1fe0606fd0a0819ffeaac92526e43b3110f2f4 Author: Shane Smiskol Date: Wed Jun 15 23:45:26 2022 -0700 rename to resume commit 00b1df652f1679137c769f9db61eed7dd14e1542 Author: Shane Smiskol Date: Wed Jun 15 21:57:54 2022 -0700 remove comments commit 325ea9bbd5e0dd946961ede0cdcc446ad5e5bbdb Author: Shane Smiskol Date: Wed Jun 15 21:56:20 2022 -0700 vw commit 2c9061042b36fe1d6b029a4216655be69a980849 Author: Shane Smiskol Date: Wed Jun 15 21:54:37 2022 -0700 do rest but vw commit 3dc51f663dfdd4ea1fd72d239bcd5db8c7da4b47 Author: Shane Smiskol Date: Wed Jun 15 16:34:48 2022 -0700 only spam resume when future is > vEgoStarting commit 5f32cd1fcb402bee425d866a9dc76b6feea3d241 Author: Shane Smiskol Date: Wed Jun 15 16:09:43 2022 -0700 always log leads, we hide them in ui * reset when not CS.enabled remove comment * update refs --- selfdrive/controls/lib/longitudinal_planner.py | 4 ++-- selfdrive/controls/radard.py | 16 ++++++---------- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 9 insertions(+), 13 deletions(-) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index d4a6aaef8f..cf51136770 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -66,11 +66,11 @@ class Planner: v_cruise_kph = min(v_cruise_kph, V_CRUISE_MAX) v_cruise = v_cruise_kph * CV.KPH_TO_MS - long_control_state = sm['controlsState'].longControlState + long_control_off = sm['controlsState'].longControlState == LongCtrlState.off force_slow_decel = sm['controlsState'].forceDecel # Reset current state when not engaged, or user is controlling the speed - reset_state = long_control_state == LongCtrlState.off + reset_state = long_control_off if self.CP.openpilotLongitudinalControl else not sm['controlsState'].enabled # No change cost when user is controlling the speed, or when standstill prev_accel_constraint = not (reset_state or sm['carState'].standstill) diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index b2c9914457..3d958139d6 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -102,7 +102,7 @@ class RadarD(): self.ready = False - def update(self, sm, rr, enable_lead): + def update(self, sm, rr): self.current_time = 1e-9*max(sm.logMonoTime.values()) if sm.updated['carState']: @@ -169,11 +169,10 @@ class RadarD(): radarState.radarErrors = list(rr.errors) radarState.carStateMonoTime = sm.logMonoTime['carState'] - if enable_lead: - leads_v3 = sm['modelV2'].leadsV3 - if len(leads_v3) > 1: - radarState.leadOne = get_lead(self.v_ego, self.ready, clusters, leads_v3[0], low_speed_override=True) - radarState.leadTwo = get_lead(self.v_ego, self.ready, clusters, leads_v3[1], low_speed_override=False) + leads_v3 = sm['modelV2'].leadsV3 + if len(leads_v3) > 1: + radarState.leadOne = get_lead(self.v_ego, self.ready, clusters, leads_v3[0], low_speed_override=True) + radarState.leadTwo = get_lead(self.v_ego, self.ready, clusters, leads_v3[1], low_speed_override=False) return dat @@ -203,9 +202,6 @@ def radard_thread(sm=None, pm=None, can_sock=None): rk = Ratekeeper(1.0 / CP.radarTimeStep, print_delay_threshold=None) RD = RadarD(CP.radarTimeStep, RI.delay) - # TODO: always log leads once we can hide them conditionally - enable_lead = CP.openpilotLongitudinalControl or not CP.radarOffCan - while 1: can_strings = messaging.drain_sock_raw(can_sock, wait_for_one=True) rr = RI.update(can_strings) @@ -215,7 +211,7 @@ def radard_thread(sm=None, pm=None, can_sock=None): sm.update(0) - dat = RD.update(sm, rr, enable_lead) + dat = RD.update(sm, rr) dat.radarState.cumLagMs = -rk.remaining*1000. pm.send('radarState', dat) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 90444b1fa7..999081b4df 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -806984d4206056fb132625c5dad6c0ca1835a2d6 \ No newline at end of file +a57bbbffbee434e59e08b98b667dc13b6b505f08 \ No newline at end of file From 59c28611a4c385c487d5d0c8a219fe20eaeadeaf Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 5 Jul 2022 23:01:57 -0700 Subject: [PATCH 210/302] bump opendbc --- opendbc | 2 +- selfdrive/car/chrysler/carstate.py | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/opendbc b/opendbc index b2895650c7..1e9693ce09 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit b2895650c744e24d48cee2f13563dcd5b030a271 +Subproject commit 1e9693ce0916b896568dcd5558a670e67843c299 diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index aa46ea0d94..61fe1f7ec6 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -51,9 +51,9 @@ class CarState(CarStateBase): ret.cruiseState.available = cp.vl["DAS_3"]["ACC_AVAILABLE"] == 1 # ACC is white ret.cruiseState.enabled = cp.vl["DAS_3"]["ACC_ACTIVE"] == 1 # ACC is green - ret.cruiseState.speed = cp.vl["DAS_4"]["ACC_SPEED_CONFIG_KPH"] * CV.KPH_TO_MS + ret.cruiseState.speed = cp.vl["DAS_4"]["ACC_SET_SPEED_KPH"] * CV.KPH_TO_MS # CRUISE_STATE is a three bit msg, 0 is off, 1 and 2 are Non-ACC mode, 3 and 4 are ACC mode, find if there are other states too - ret.cruiseState.nonAdaptive = cp.vl["DAS_4"]["CRUISE_STATE"] in (1, 2) + ret.cruiseState.nonAdaptive = cp.vl["DAS_4"]["ACC_STATE"] in (1, 2) ret.accFaulted = cp.vl["DAS_3"]["ACC_FAULTED"] != 0 ret.steeringAngleDeg = cp.vl["STEERING"]["STEER_ANGLE"] @@ -101,8 +101,8 @@ class CarState(CarStateBase): ("ACC_ACTIVE", "DAS_3"), ("ACC_FAULTED", "DAS_3"), ("HIGH_BEAM_PRESSED", "STEERING_LEVERS"), - ("ACC_SPEED_CONFIG_KPH", "DAS_4"), - ("CRUISE_STATE", "DAS_4"), + ("ACC_SET_SPEED_KPH", "DAS_4"), + ("ACC_STATE", "DAS_4"), ("COLUMN_TORQUE", "EPS_2"), ("EPS_TORQUE_MOTOR", "EPS_2"), ("LKAS_STATE", "EPS_2"), From 50434d612ee7becc09aef762a6c8fb8d8111af6d Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 6 Jul 2022 12:08:51 +0200 Subject: [PATCH 211/302] casync: reuse requests session in RemoteChunkReader (#25045) --- system/hardware/tici/casync.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/system/hardware/tici/casync.py b/system/hardware/tici/casync.py index b857c04795..d0d0da3c6a 100755 --- a/system/hardware/tici/casync.py +++ b/system/hardware/tici/casync.py @@ -55,6 +55,7 @@ class RemoteChunkReader(ChunkReader): def __init__(self, url: str) -> None: super().__init__() self.url = url + self.session = requests.Session() def read(self, chunk: Chunk) -> bytes: sha_hex = chunk.sha.hex() @@ -62,7 +63,7 @@ class RemoteChunkReader(ChunkReader): for i in range(CHUNK_DOWNLOAD_RETRIES): try: - resp = requests.get(url, timeout=CHUNK_DOWNLOAD_TIMEOUT) + resp = self.session.get(url, timeout=CHUNK_DOWNLOAD_TIMEOUT) break except Exception: if i == CHUNK_DOWNLOAD_RETRIES - 1: From 4080f729bea6092813331fb6d92c80e2f4c4f928 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 6 Jul 2022 13:04:25 +0200 Subject: [PATCH 212/302] casync: compute seed caibx url on the fly (#25046) * compute seed hash on the fly * more logging * partition name in url * fix comment --- system/hardware/tici/agnos.py | 41 ++++++++++++++++++++++++----------- 1 file changed, 28 insertions(+), 13 deletions(-) diff --git a/system/hardware/tici/agnos.py b/system/hardware/tici/agnos.py index 527422aca7..bd8ce2bf02 100755 --- a/system/hardware/tici/agnos.py +++ b/system/hardware/tici/agnos.py @@ -13,6 +13,7 @@ import requests import system.hardware.tici.casync as casync SPARSE_CHUNK_FMT = struct.Struct('H2xI4x') +CAIBX_URL = "https://commadist.azureedge.net/agnosupdate/" class StreamingDecompressor: @@ -103,28 +104,37 @@ def get_partition_path(target_slot_number: int, partition: dict) -> str: return path +def get_raw_hash(path: str, partition_size: int) -> str: + raw_hash = hashlib.sha256() + pos, chunk_size = 0, 1024 * 1024 + + with open(path, 'rb+') as out: + while pos < partition_size: + n = min(chunk_size, partition_size - pos) + raw_hash.update(out.read(n)) + pos += n + + return raw_hash.hexdigest().lower() + + def verify_partition(target_slot_number: int, partition: Dict[str, Union[str, int]], force_full_check: bool = False) -> bool: full_check = partition['full_check'] or force_full_check path = get_partition_path(target_slot_number, partition) + if not isinstance(partition['size'], int): return False + partition_size: int = partition['size'] if not isinstance(partition['hash_raw'], str): return False - partition_hash: str = partition['hash_raw'] - with open(path, 'rb+') as out: - if full_check: - raw_hash = hashlib.sha256() - pos, chunk_size = 0, 1024 * 1024 - while pos < partition_size: - n = min(chunk_size, partition_size - pos) - raw_hash.update(out.read(n)) - pos += n + partition_hash: str = partition['hash_raw'] - return raw_hash.hexdigest().lower() == partition_hash.lower() - else: + if full_check: + return get_raw_hash(path, partition_size) == partition_hash.lower() + else: + with open(path, 'rb+') as out: out.seek(partition_size) return out.read(64) == partition_hash.lower().encode() @@ -177,8 +187,13 @@ def extract_casync_image(target_slot_number: int, partition: dict, cloudlog): sources: List[Tuple[str, casync.ChunkReader, casync.ChunkDict]] = [] # First source is the current partition. Index file for current version is provided in the manifest - if 'casync_seed_caibx' in partition: - sources += [('seed', casync.FileChunkReader(seed_path), casync.build_chunk_dict(casync.parse_caibx(partition['casync_seed_caibx'])))] + raw_hash = get_raw_hash(seed_path, partition['size']) + caibx_url = f"{CAIBX_URL}{partition['name']}-{raw_hash}.caibx" + try: + cloudlog.info(f"casync fetching {caibx_url}") + sources += [('seed', casync.FileChunkReader(seed_path), casync.build_chunk_dict(casync.parse_caibx(caibx_url)))] + except requests.RequestException: + cloudlog.error(f"casync failed to load {caibx_url}") # Second source is the target partition, this allows for resuming sources += [('target', casync.FileChunkReader(path), casync.build_chunk_dict(target))] From 6065871ad504f1b590d8de053b25ce1cf01f29ba Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 6 Jul 2022 14:03:31 +0200 Subject: [PATCH 213/302] add casync to release files --- release/files_common | 1 + 1 file changed, 1 insertion(+) diff --git a/release/files_common b/release/files_common index e32277dfd8..b46266fa91 100644 --- a/release/files_common +++ b/release/files_common @@ -196,6 +196,7 @@ system/hardware/tici/hardware.h system/hardware/tici/hardware.py system/hardware/tici/pins.py system/hardware/tici/agnos.py +system/hardware/tici/casync.py system/hardware/tici/agnos.json system/hardware/tici/amplifier.py system/hardware/tici/updater From e336f254b1744f87119059189711b326ce8b7884 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Wed, 6 Jul 2022 15:50:28 +0200 Subject: [PATCH 214/302] bump laika --- laika_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/laika_repo b/laika_repo index 6e87f536db..828612e1b8 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 6e87f536dbe8cf80040f724c89798e66ca17cf9d +Subproject commit 828612e1b8848ccf70072d5513c0b7977f1707da From b88d7c89fae448068aeaca65706d99aa145c8a74 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Wed, 6 Jul 2022 19:01:19 +0200 Subject: [PATCH 215/302] laikad: Filter unwanted pseudoranges (#25051) Filter unwanted pseudoranges --- selfdrive/locationd/laikad.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 0df48dd893..40519da7bc 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -103,6 +103,9 @@ class Laikad: self.fetch_orbits(latest_msg_t + SECS_IN_MIN, block) new_meas = read_raw_ublox(report) + # Filter measurements with unexpected pseudoranges for GPS and GLONASS satellites + new_meas = [m for m in new_meas if 1e7 < m.observables['C1C'] < 3e7] + processed_measurements = process_measurements(new_meas, self.astro_dog) est_pos = self.get_est_pos(t, processed_measurements) From 3e5e27f043bca856ff3f4aaa83355d964ca42fa5 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 6 Jul 2022 18:51:51 -0700 Subject: [PATCH 216/302] Add missing 2019 RAV4 Hybrid engine FW version (#25057) add missing engine fw --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 86283bc48f..9324e6baf5 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1317,6 +1317,7 @@ FW_VERSIONS = { b'\x018966342X6000\x00\x00\x00\x00', b'\x01896634A25000\x00\x00\x00\x00', b'\x018966342W5000\x00\x00\x00\x00', + b'\x018966342W7000\x00\x00\x00\x00', b'\x028966342W4001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', b'\x02896634A13000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02896634A13001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', From ea241bf3dc1d6dec2610bec9fceb1b8659014436 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 6 Jul 2022 19:42:58 -0700 Subject: [PATCH 217/302] FW fingerprinting: log all FW versions (#25042) * get_fw_versions returns all fw versions with request's brand * keep track of everything received * debug * need to regen or write a hack in build_fw_dict * to be safe, still replace old responses within same brands (hyundai responds to two queries, can fix later) to be safe, still replace old responses within same brands (hyundai responds to two queries, can fix later) * update test_fw_query_on_routes * clean up * better name * slightly cleaner * fix test_startup unit test del * fix imports * fix test_fw_fingerprint fix test_fw_fingerprint fix * fingerprint on all FW_VERSIONS, not just brands with requests * support old routes in test_fw_query_on_routes * regen and update refs * similar function style to before * better comment * space switch name * try to exact match first * useless else * fix debug script * simpler dictionary * bump cereal to master --- cereal | 2 +- selfdrive/car/fw_versions.py | 45 ++++++++++++------- selfdrive/car/tests/test_fw_fingerprint.py | 10 ++--- selfdrive/controls/tests/test_startup.py | 23 +++++----- selfdrive/debug/test_fw_query_on_routes.py | 43 +++++++++++------- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/test/process_replay/regen.py | 16 ++++++- .../test/process_replay/test_processes.py | 26 +++++------ 8 files changed, 101 insertions(+), 66 deletions(-) diff --git a/cereal b/cereal index df08568318..cda60ec965 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit df08568318da97ed6f87747caee0a5b2c30086c4 +Subproject commit cda60ec9652c05de4ccfcad1fae7936e708434a3 diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 758485c393..b79f61d94d 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -194,12 +194,13 @@ def chunks(l, n=128): yield l[i:i + n] -def build_fw_dict(fw_versions): +def build_fw_dict(fw_versions, filter_brand=None): fw_versions_dict = {} for fw in fw_versions: - addr = fw.address - sub_addr = fw.subAddress if fw.subAddress != 0 else None - fw_versions_dict[(addr, sub_addr)] = fw.fwVersion + if filter_brand is None or fw.brand == filter_brand: + addr = fw.address + sub_addr = fw.subAddress if fw.subAddress != 0 else None + fw_versions_dict[(addr, sub_addr)] = fw.fwVersion return fw_versions_dict @@ -284,18 +285,27 @@ def match_fw_to_car_exact(fw_versions_dict): def match_fw_to_car(fw_versions, allow_fuzzy=True): - fw_versions_dict = build_fw_dict(fw_versions) - matches = match_fw_to_car_exact(fw_versions_dict) + versions = get_interface_attr('FW_VERSIONS', ignore_none=True) + + # Try exact matching first + exact_matches = [True] + if allow_fuzzy: + exact_matches.append(False) + + for exact_match in exact_matches: + # For each brand, attempt to fingerprint using FW returned from its queries + for brand in versions.keys(): + fw_versions_dict = build_fw_dict(fw_versions, filter_brand=brand) - exact_match = True - if allow_fuzzy and len(matches) == 0: - matches = match_fw_to_car_fuzzy(fw_versions_dict) + if exact_match: + matches = match_fw_to_car_exact(fw_versions_dict) + else: + matches = match_fw_to_car_fuzzy(fw_versions_dict) - # Fuzzy match found - if len(matches) == 1: - exact_match = False + if len(matches) == 1: + return exact_match, matches - return exact_match, matches + return True, [] def get_present_ecus(logcan, sendcan): @@ -372,20 +382,21 @@ def get_fw_versions(logcan, sendcan, extra=None, timeout=0.1, debug=False, progr if addrs: query = IsoTpParallelQuery(sendcan, logcan, r.bus, addrs, r.request, r.response, r.rx_offset, debug=debug) t = 2 * timeout if i == 0 else timeout - fw_versions.update({addr: (version, r.request, r.rx_offset) for addr, version in query.get_data(t).items()}) + fw_versions.update({(r.brand, addr): (version, r) for addr, version in query.get_data(t).items()}) except Exception: cloudlog.warning(f"FW query exception: {traceback.format_exc()}") # Build capnp list to put into CarParams car_fw = [] - for addr, (version, request, rx_offset) in fw_versions.items(): + for (brand, addr), (version, request) in fw_versions.items(): f = car.CarParams.CarFw.new_message() f.ecu = ecu_types[addr] f.fwVersion = version f.address = addr[0] - f.responseAddress = uds.get_rx_addr_for_tx_addr(addr[0], rx_offset) - f.request = request + f.responseAddress = uds.get_rx_addr_for_tx_addr(addr[0], request.rx_offset) + f.request = request.request + f.brand = brand if addr[1] is not None: f.subAddress = addr[1] diff --git a/selfdrive/car/tests/test_fw_fingerprint.py b/selfdrive/car/tests/test_fw_fingerprint.py index ed7e420e1a..49fa66d36d 100755 --- a/selfdrive/car/tests/test_fw_fingerprint.py +++ b/selfdrive/car/tests/test_fw_fingerprint.py @@ -12,6 +12,7 @@ CarFw = car.CarParams.CarFw Ecu = car.CarParams.Ecu ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} +VERSIONS = get_interface_attr("FW_VERSIONS", ignore_none=True) class TestFwFingerprint(unittest.TestCase): @@ -20,14 +21,14 @@ class TestFwFingerprint(unittest.TestCase): self.assertEqual(len(candidates), 1, f"got more than one candidate: {candidates}") self.assertEqual(candidates[0], expected) - @parameterized.expand([(k, v) for k, v in FW_VERSIONS.items()]) - def test_fw_fingerprint(self, car_model, ecus): + @parameterized.expand([(b, c, e[c]) for b, e in VERSIONS.items() for c in e]) + def test_fw_fingerprint(self, brand, car_model, ecus): CP = car.CarParams.new_message() for _ in range(200): fw = [] for ecu, fw_versions in ecus.items(): ecu_name, addr, sub_addr = ecu - fw.append({"ecu": ecu_name, "fwVersion": random.choice(fw_versions), + fw.append({"ecu": ecu_name, "fwVersion": random.choice(fw_versions), 'brand': brand, "address": addr, "subAddress": 0 if sub_addr is None else sub_addr}) CP.carFw = fw _, matches = match_fw_to_car(CP.carFw) @@ -60,10 +61,9 @@ class TestFwFingerprint(unittest.TestCase): def test_fw_request_ecu_whitelist(self): passed = True brands = set(r.brand for r in REQUESTS) - versions = get_interface_attr('FW_VERSIONS') for brand in brands: whitelisted_ecus = [ecu for r in REQUESTS for ecu in r.whitelist_ecus if r.brand == brand] - brand_ecus = set([fw[0] for car_fw in versions[brand].values() for fw in car_fw]) + brand_ecus = set([fw[0] for car_fw in VERSIONS[brand].values() for fw in car_fw]) # each ecu in brand's fw versions needs to be whitelisted at least once ecus_not_whitelisted = set(brand_ecus) - set(whitelisted_ecus) diff --git a/selfdrive/controls/tests/test_startup.py b/selfdrive/controls/tests/test_startup.py index 9d13453045..a94311c8c7 100755 --- a/selfdrive/controls/tests/test_startup.py +++ b/selfdrive/controls/tests/test_startup.py @@ -42,27 +42,27 @@ class TestStartup(unittest.TestCase): # TODO: test EventName.startup for release branches # officially supported car - (EventName.startupMaster, TOYOTA.COROLLA, COROLLA_FW_VERSIONS), - (EventName.startupMaster, TOYOTA.COROLLA, COROLLA_FW_VERSIONS), + (EventName.startupMaster, TOYOTA.COROLLA, COROLLA_FW_VERSIONS, "toyota"), + (EventName.startupMaster, TOYOTA.COROLLA, COROLLA_FW_VERSIONS, "toyota"), # dashcamOnly car - (EventName.startupNoControl, MAZDA.CX5, CX5_FW_VERSIONS), - (EventName.startupNoControl, MAZDA.CX5, CX5_FW_VERSIONS), + (EventName.startupNoControl, MAZDA.CX5, CX5_FW_VERSIONS, "mazda"), + (EventName.startupNoControl, MAZDA.CX5, CX5_FW_VERSIONS, "mazda"), # unrecognized car with no fw - (EventName.startupNoFw, None, None), - (EventName.startupNoFw, None, None), + (EventName.startupNoFw, None, None, ""), + (EventName.startupNoFw, None, None, ""), # unrecognized car - (EventName.startupNoCar, None, COROLLA_FW_VERSIONS[:1]), - (EventName.startupNoCar, None, COROLLA_FW_VERSIONS[:1]), + (EventName.startupNoCar, None, COROLLA_FW_VERSIONS[:1], "toyota"), + (EventName.startupNoCar, None, COROLLA_FW_VERSIONS[:1], "toyota"), # fuzzy match - (EventName.startupMaster, TOYOTA.COROLLA, COROLLA_FW_VERSIONS_FUZZY), - (EventName.startupMaster, TOYOTA.COROLLA, COROLLA_FW_VERSIONS_FUZZY), + (EventName.startupMaster, TOYOTA.COROLLA, COROLLA_FW_VERSIONS_FUZZY, "toyota"), + (EventName.startupMaster, TOYOTA.COROLLA, COROLLA_FW_VERSIONS_FUZZY, "toyota"), ]) @with_processes(['controlsd']) - def test_startup_alert(self, expected_event, car_model, fw_versions): + def test_startup_alert(self, expected_event, car_model, fw_versions, brand): # TODO: this should be done without any real sockets controls_sock = messaging.sub_sock("controlsState") @@ -82,6 +82,7 @@ class TestStartup(unittest.TestCase): f.ecu = ecu f.address = addr f.fwVersion = version + f.brand = brand if subaddress is not None: f.subAddress = subaddress diff --git a/selfdrive/debug/test_fw_query_on_routes.py b/selfdrive/debug/test_fw_query_on_routes.py index 011dd6c9a3..789baeca4b 100755 --- a/selfdrive/debug/test_fw_query_on_routes.py +++ b/selfdrive/debug/test_fw_query_on_routes.py @@ -8,24 +8,15 @@ import traceback from tqdm import tqdm from tools.lib.logreader import LogReader from tools.lib.route import Route +from selfdrive.car.interfaces import get_interface_attr from selfdrive.car.car_helpers import interface_names from selfdrive.car.fw_versions import match_fw_to_car_exact, match_fw_to_car_fuzzy, build_fw_dict -from selfdrive.car.toyota.values import FW_VERSIONS as TOYOTA_FW_VERSIONS -from selfdrive.car.honda.values import FW_VERSIONS as HONDA_FW_VERSIONS -from selfdrive.car.hyundai.values import FW_VERSIONS as HYUNDAI_FW_VERSIONS -from selfdrive.car.volkswagen.values import FW_VERSIONS as VW_FW_VERSIONS -from selfdrive.car.mazda.values import FW_VERSIONS as MAZDA_FW_VERSIONS -from selfdrive.car.subaru.values import FW_VERSIONS as SUBARU_FW_VERSIONS NO_API = "NO_API" in os.environ -SUPPORTED_CARS = set(interface_names['toyota']) -SUPPORTED_CARS |= set(interface_names['honda']) -SUPPORTED_CARS |= set(interface_names['hyundai']) -SUPPORTED_CARS |= set(interface_names['volkswagen']) -SUPPORTED_CARS |= set(interface_names['mazda']) -SUPPORTED_CARS |= set(interface_names['subaru']) -SUPPORTED_CARS |= set(interface_names['nissan']) +VERSIONS = get_interface_attr('FW_VERSIONS', ignore_none=True) +SUPPORTED_BRANDS = VERSIONS.keys() +SUPPORTED_CARS = [brand for brand in SUPPORTED_BRANDS for brand in interface_names[brand]] try: from xx.pipeline.c.CarState import migration @@ -97,9 +88,24 @@ if __name__ == "__main__": print("not in supported cars") break - fw_versions_dict = build_fw_dict(car_fw) - exact_matches = match_fw_to_car_exact(fw_versions_dict) - fuzzy_matches = match_fw_to_car_fuzzy(fw_versions_dict) + # Older routes only have carFw from their brand + old_route = not any([len(fw.brand) for fw in car_fw]) + brands = SUPPORTED_BRANDS if not old_route else [None] + + # Exact match + exact_matches, fuzzy_matches = [], [] + for brand in brands: + fw_versions_dict = build_fw_dict(car_fw, filter_brand=brand) + exact_matches = match_fw_to_car_exact(fw_versions_dict) + if len(exact_matches) == 1: + break + + # Fuzzy match + for brand in brands: + fw_versions_dict = build_fw_dict(car_fw, filter_brand=brand) + fuzzy_matches = match_fw_to_car_fuzzy(fw_versions_dict) + if len(fuzzy_matches) == 1: + break if (len(exact_matches) == 1) and (list(exact_matches)[0] == live_fingerprint): good_exact += 1 @@ -126,12 +132,15 @@ if __name__ == "__main__": print("Mismatches") found = False - for car_fws in [TOYOTA_FW_VERSIONS, HONDA_FW_VERSIONS, HYUNDAI_FW_VERSIONS, VW_FW_VERSIONS, MAZDA_FW_VERSIONS, SUBARU_FW_VERSIONS]: + for brand in SUPPORTED_BRANDS: + car_fws = VERSIONS[brand] if live_fingerprint in car_fws: found = True expected = car_fws[live_fingerprint] for (_, expected_addr, expected_sub_addr), v in expected.items(): for version in car_fw: + if version.brand != brand and len(version.brand): + continue sub_addr = None if version.subAddress == 0 else version.subAddress addr = version.address diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 999081b4df..0eeae1e3e3 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -a57bbbffbee434e59e08b98b667dc13b6b505f08 \ No newline at end of file +b904e52e9de4ff7b2bd7f6af8b19abaf4957e6cc \ No newline at end of file diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py index 793e548705..1a2d436f1a 100755 --- a/selfdrive/test/process_replay/regen.py +++ b/selfdrive/test/process_replay/regen.py @@ -179,8 +179,22 @@ def replay_cameras(lr, frs, disable_tqdm=False): return vs, p +def migrate_carparams(lr): + all_msgs = [] + for msg in lr: + if msg.which() == 'carParams': + CP = messaging.new_message('carParams') + CP.carParams = msg.carParams.as_builder() + for car_fw in CP.carParams.carFw: + car_fw.brand = CP.carParams.carName + msg = CP.as_reader() + all_msgs.append(msg) + + return all_msgs + + def regen_segment(lr, frs=None, outdir=FAKEDATA, disable_tqdm=False): - lr = list(lr) + lr = migrate_carparams(list(lr)) if frs is None: frs = dict() diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 4e7ba4a6dd..9cbf4439ac 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -35,19 +35,19 @@ original_segments = [ ] segments = [ - ("BODY", "bd6a637565e91581|2022-04-04--22-05-08--0"), - ("HYUNDAI", "fakedata|2022-01-20--17-49-04--0"), - ("TOYOTA", "fakedata|2022-04-29--15-57-12--0"), - ("TOYOTA2", "fakedata|2022-04-29--16-08-01--0"), - ("TOYOTA3", "fakedata|2022-04-29--16-17-39--0"), - ("HONDA", "fakedata|2022-01-20--17-56-40--0"), - ("HONDA2", "fakedata|2022-04-29--16-31-55--0"), - ("CHRYSLER", "fakedata|2022-01-20--18-00-11--0"), - ("SUBARU", "fakedata|2022-01-20--18-01-57--0"), - ("GM", "fakedata|2022-01-20--18-03-41--0"), - ("NISSAN", "fakedata|2022-01-20--18-05-29--0"), - ("VOLKSWAGEN", "fakedata|2022-01-20--18-07-15--0"), - ("MAZDA", "fakedata|2022-01-20--18-09-32--0"), + ("BODY", "regen660D86654BA|2022-07-06--14-27-15--0"), + ("HYUNDAI", "regen657E25856BB|2022-07-06--14-26-51--0"), + ("TOYOTA", "regenBA97410FBEC|2022-07-06--14-26-49--0"), + ("TOYOTA2", "regenDEDB1D9C991|2022-07-06--14-54-08--0"), + ("TOYOTA3", "regenDDC1FE60734|2022-07-06--14-32-06--0"), + ("HONDA", "regen17B09D158B8|2022-07-06--14-31-46--0"), + ("HONDA2", "regen041739C3E9A|2022-07-06--15-08-02--0"), + ("CHRYSLER", "regenBB2F9C1425C|2022-07-06--14-31-41--0"), + ("SUBARU", "regen732B69F33B1|2022-07-06--14-36-18--0"), + ("GM", "regen01D09D915B5|2022-07-06--14-36-20--0"), + ("NISSAN", "regenEA6FB2773F5|2022-07-06--14-58-23--0"), + ("VOLKSWAGEN", "regen007098CA0EF|2022-07-06--15-01-26--0"), + ("MAZDA", "regen61BA413D53B|2022-07-06--14-39-42--0"), ] # dashcamOnly makes don't need to be tested until a full port is done From 479b66c992fb2898418d866a1c61d993a9217d3d Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 6 Jul 2022 19:57:44 -0700 Subject: [PATCH 218/302] VW FPv2: reduce number of ECU queries (#24939) * only send valid/needed queries * just do volkswagen * clean up * add parameter name clean up * add test for whitelist * rename * Update selfdrive/car/fw_versions.py Co-authored-by: Jason Young <46612682+jyoung8607@users.noreply.github.com> * fix test * log response addresses * bump cereal * handle response pending with IsoTpParallelQuery * remove response pending stuff * temporarily disregard cache for easier testing * revert this Co-authored-by: Jason Young <46612682+jyoung8607@users.noreply.github.com> --- selfdrive/car/fw_versions.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index b79f61d94d..03dcece10c 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -148,12 +148,14 @@ REQUESTS: List[Request] = [ "volkswagen", [VOLKSWAGEN_VERSION_REQUEST_MULTI], [VOLKSWAGEN_VERSION_RESPONSE], + whitelist_ecus=[Ecu.srs, Ecu.eps, Ecu.fwdRadar], rx_offset=VOLKSWAGEN_RX_OFFSET, ), Request( "volkswagen", [VOLKSWAGEN_VERSION_REQUEST_MULTI], [VOLKSWAGEN_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.transmission], ), # Mazda Request( From 9b0acacf5e387593ce94dbad88000b5473511e22 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 6 Jul 2022 23:42:07 -0700 Subject: [PATCH 219/302] Ram 1500 (#24878) * RamInit * bump submodules * lil cleanup * clean up carstate formatting and platform grouping make tuple * give it a gold torque star (looks around 2.4 from rough data) * Dasm Fault * bump panda * more cleanup * cleanup car state * more cleanup * some fixes * remove more stuff * fix angle signal scaling and fix lkas control bit * bump panda * update those * same limits as pacifica * cleanup hud alert building * better fault logic * fix rate * set ahb * bring that back * update refs Co-authored-by: Jonathan Co-authored-by: Shane Smiskol Co-authored-by: Comma Device --- RELEASES.md | 1 + docs/CARS.md | 3 +- panda | 2 +- release/files_common | 1 + selfdrive/car/chrysler/carcontroller.py | 73 +++++------- selfdrive/car/chrysler/carstate.py | 135 +++++++++++++++------- selfdrive/car/chrysler/chryslercan.py | 79 +++++++------ selfdrive/car/chrysler/interface.py | 22 +++- selfdrive/car/chrysler/radar_interface.py | 9 +- selfdrive/car/chrysler/values.py | 36 +++--- selfdrive/car/tests/routes.py | 1 + selfdrive/car/torque_data/override.yaml | 3 +- selfdrive/test/process_replay/ref_commit | 2 +- 13 files changed, 226 insertions(+), 141 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index 5b71fc3375..fedff5dbff 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -19,6 +19,7 @@ Version 0.8.15 (2022-07-XX) * Honda Civic 2022 support * Hyundai Tucson 2021 support thanks to bluesforte! * Lexus NX Hybrid 2020 support thanks to AlexandreSato! +* Ram 1500 2019-21 support thanks to realfast! Version 0.8.14 (2022-06-01) ======================== diff --git a/docs/CARS.md b/docs/CARS.md index 0cf384df18..a1e89efe12 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -144,7 +144,7 @@ How We Rate The Cars |Volkswagen|Passat 2015-19[6](#footnotes)|Driver Assistance|||||| |Volkswagen|Polo 2020|Driver Assistance|||||| -# Bronze - 79 cars +# Bronze - 80 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -198,6 +198,7 @@ How We Rate The Cars |Lexus|RX Hybrid 2016-19|All|[3](#footnotes)||||| |Mazda|CX-5 2022|All|||||| |Mazda|CX-9 2021|All|||||| +|Ram|1500 2019-21|Adaptive Cruise|||||| |Subaru|Crosstrek 2018-19|EyeSight|||||| |Subaru|Impreza 2017-19|EyeSight|||||| |Subaru|XV 2018-19|EyeSight|||||| diff --git a/panda b/panda index 6c0d0b43c2..fae3ee2e81 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 6c0d0b43c239b89baa83b4a1885d0ce21ab2335e +Subproject commit fae3ee2e8161d34a7c1939503e583db9b85e5402 diff --git a/release/files_common b/release/files_common index b46266fa91..260e37e29a 100644 --- a/release/files_common +++ b/release/files_common @@ -474,6 +474,7 @@ opendbc/can/parser_pyx.pyx opendbc/comma_body.dbc +opendbc/chrysler_ram_dt_generated.dbc opendbc/chrysler_pacifica_2017_hybrid_generated.dbc opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py index 49525646ca..606cb51176 100644 --- a/selfdrive/car/chrysler/carcontroller.py +++ b/selfdrive/car/chrysler/carcontroller.py @@ -1,8 +1,7 @@ -from cereal import car from opendbc.can.packer import CANPacker from selfdrive.car import apply_toyota_steer_torque_limits from selfdrive.car.chrysler.chryslercan import create_lkas_hud, create_lkas_command, create_cruise_buttons -from selfdrive.car.chrysler.values import CAR, CarControllerParams +from selfdrive.car.chrysler.values import RAM_CARS, CarControllerParams class CarController: @@ -10,61 +9,51 @@ class CarController: self.CP = CP self.apply_steer_last = 0 self.frame = 0 - self.prev_lkas_frame = -1 - self.hud_count = 0 - self.car_fingerprint = CP.carFingerprint - self.gone_fast_yet = False self.steer_rate_limited = False - self.packer = CANPacker(dbc_name) - - def update(self, CC, CS): - # this seems needed to avoid steering faults and to force the sync with the EPS counter - if self.prev_lkas_frame == CS.lkas_counter: - return car.CarControl.Actuators.new_message(), [] - - actuators = CC.actuators - - # steer torque - new_steer = int(round(actuators.steer * CarControllerParams.STEER_MAX)) - apply_steer = apply_toyota_steer_torque_limits(new_steer, self.apply_steer_last, - CS.out.steeringTorqueEps, CarControllerParams) - self.steer_rate_limited = new_steer != apply_steer - - moving_fast = CS.out.vEgo > self.CP.minSteerSpeed # for status message - if CS.out.vEgo > (self.CP.minSteerSpeed - 0.5): # for command high bit - self.gone_fast_yet = True - elif self.car_fingerprint in (CAR.PACIFICA_2019_HYBRID, CAR.PACIFICA_2020, CAR.JEEP_CHEROKEE_2019): - if CS.out.vEgo < (self.CP.minSteerSpeed - 3.0): - self.gone_fast_yet = False # < 14.5m/s stock turns off this bit, but fine down to 13.5 - lkas_active = moving_fast and CC.enabled - - if not lkas_active: - apply_steer = 0 + self.hud_count = 0 + self.last_lkas_falling_edge = 0 + self.lkas_active_prev = False - self.apply_steer_last = apply_steer + self.packer = CANPacker(dbc_name) + def update(self, CC, CS, low_speed_alert): can_sends = [] + # EPS faults if LKAS re-enables too quickly + lkas_active = CC.latActive and not low_speed_alert and (self.frame - self.last_lkas_falling_edge > 200) + # *** control msgs *** if CC.cruiseControl.cancel: - can_sends.append(create_cruise_buttons(self.packer, CS.button_counter + 1, cancel=True)) + bus = 2 if self.CP.carFingerprint in RAM_CARS else 0 + can_sends.append(create_cruise_buttons(self.packer, CS.button_counter + 1, bus, cancel=True)) - # LKAS_HEARTBIT is forwarded by Panda so no need to send it here. - # frame is 100Hz (0.01s period) - if self.frame % 25 == 0: # 0.25s period + # HUD alerts + if self.frame % 25 == 0: if CS.lkas_car_model != -1: - can_sends.append(create_lkas_hud(self.packer, CS.out.gearShifter, lkas_active, - CC.hudControl.visualAlert, self.hud_count, CS.lkas_car_model)) + can_sends.append(create_lkas_hud(self.packer, self.CP, lkas_active, CC.hudControl.visualAlert, self.hud_count, CS.lkas_car_model, CS.auto_high_beam)) self.hud_count += 1 - can_sends.append(create_lkas_command(self.packer, int(apply_steer), self.gone_fast_yet, CS.lkas_counter)) + # steering + if self.frame % 2 == 0: + # steer torque + new_steer = int(round(CC.actuators.steer * CarControllerParams.STEER_MAX)) + apply_steer = apply_toyota_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, CarControllerParams) + if not lkas_active: + apply_steer = 0 + self.steer_rate_limited = new_steer != apply_steer + self.apply_steer_last = apply_steer + + idx = self.frame // 2 + can_sends.append(create_lkas_command(self.packer, self.CP, int(apply_steer), lkas_active, idx)) self.frame += 1 - self.prev_lkas_frame = CS.lkas_counter + if not lkas_active and self.lkas_active_prev: + self.last_lkas_falling_edge = self.frame + self.lkas_active_prev = lkas_active - new_actuators = actuators.copy() - new_actuators.steer = apply_steer / CarControllerParams.STEER_MAX + new_actuators = CC.actuators.copy() + new_actuators.steer = self.apply_steer_last / CarControllerParams.STEER_MAX return new_actuators, can_sends diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index 61fe1f7ec6..71b7e34623 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -3,21 +3,29 @@ from common.conversions import Conversions as CV from opendbc.can.parser import CANParser from opendbc.can.can_define import CANDefine from selfdrive.car.interfaces import CarStateBase -from selfdrive.car.chrysler.values import DBC, STEER_THRESHOLD +from selfdrive.car.chrysler.values import DBC, STEER_THRESHOLD, RAM_CARS class CarState(CarStateBase): def __init__(self, CP): super().__init__(CP) + self.CP = CP can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.shifter_values = can_define.dv["GEAR"]["PRNDL"] + + self.auto_high_beam = 0 + self.button_counter = 0 + self.lkas_car_model = -1 + + if CP.carFingerprint in RAM_CARS: + self.shifter_values = can_define.dv["Transmission_Status"]["Gear_State"] + else: + self.shifter_values = can_define.dv["GEAR"]["PRNDL"] def update(self, cp, cp_cam): ret = car.CarState.new_message() - self.frame = int(cp.vl["EPS_2"]["COUNTER"]) - + # lock info ret.doorOpen = any([cp.vl["BCM_1"]["DOOR_OPEN_FL"], cp.vl["BCM_1"]["DOOR_OPEN_FR"], cp.vl["BCM_1"]["DOOR_OPEN_RL"], @@ -32,8 +40,15 @@ class CarState(CarStateBase): ret.gas = cp.vl["ECM_5"]["Accelerator_Position"] ret.gasPressed = ret.gas > 1e-5 - ret.espDisabled = (cp.vl["TRACTION_BUTTON"]["TRACTION_OFF"] == 1) - + # car speed + if self.CP.carFingerprint in RAM_CARS: + ret.vEgoRaw = cp.vl["ESP_8"]["Vehicle_Speed"] * CV.KPH_TO_MS + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["Transmission_Status"]["Gear_State"], None)) + else: + ret.vEgoRaw = (cp.vl["SPEED_1"]["SPEED_LEFT"] + cp.vl["SPEED_1"]["SPEED_RIGHT"]) / 2. + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["GEAR"]["PRNDL"], None)) + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = not ret.vEgoRaw > 0.001 ret.wheelSpeeds = self.get_wheel_speeds( cp.vl["ESP_6"]["WHEEL_SPEED_FL"], cp.vl["ESP_6"]["WHEEL_SPEED_FR"], @@ -41,55 +56,73 @@ class CarState(CarStateBase): cp.vl["ESP_6"]["WHEEL_SPEED_RR"], unit=1, ) - ret.vEgoRaw = (cp.vl["SPEED_1"]["SPEED_LEFT"] + cp.vl["SPEED_1"]["SPEED_RIGHT"]) / 2. - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = not ret.vEgoRaw > 0.001 + # button presses ret.leftBlinker = cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 1 ret.rightBlinker = cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 2 - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["GEAR"]["PRNDL"], None)) - - ret.cruiseState.available = cp.vl["DAS_3"]["ACC_AVAILABLE"] == 1 # ACC is white - ret.cruiseState.enabled = cp.vl["DAS_3"]["ACC_ACTIVE"] == 1 # ACC is green - ret.cruiseState.speed = cp.vl["DAS_4"]["ACC_SET_SPEED_KPH"] * CV.KPH_TO_MS - # CRUISE_STATE is a three bit msg, 0 is off, 1 and 2 are Non-ACC mode, 3 and 4 are ACC mode, find if there are other states too - ret.cruiseState.nonAdaptive = cp.vl["DAS_4"]["ACC_STATE"] in (1, 2) - ret.accFaulted = cp.vl["DAS_3"]["ACC_FAULTED"] != 0 + ret.genericToggle = cp.vl["STEERING_LEVERS"]["HIGH_BEAM_PRESSED"] == 1 + # steering wheel ret.steeringAngleDeg = cp.vl["STEERING"]["STEER_ANGLE"] ret.steeringRateDeg = cp.vl["STEERING"]["STEERING_RATE"] ret.steeringTorque = cp.vl["EPS_2"]["COLUMN_TORQUE"] ret.steeringTorqueEps = cp.vl["EPS_2"]["EPS_TORQUE_MOTOR"] ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD - steer_state = cp.vl["EPS_2"]["LKAS_STATE"] - ret.steerFaultPermanent = steer_state == 4 or (steer_state == 0 and ret.vEgo > self.CP.minSteerSpeed) - ret.genericToggle = bool(cp.vl["STEERING_LEVERS"]["HIGH_BEAM_PRESSED"]) + # cruise state + cp_cruise = cp_cam if self.CP.carFingerprint in RAM_CARS else cp + + ret.cruiseState.available = cp_cruise.vl["DAS_3"]["ACC_AVAILABLE"] == 1 + ret.cruiseState.enabled = cp_cruise.vl["DAS_3"]["ACC_ACTIVE"] == 1 + ret.cruiseState.speed = cp_cruise.vl["DAS_4"]["ACC_SET_SPEED_KPH"] * CV.KPH_TO_MS + ret.cruiseState.nonAdaptive = cp_cruise.vl["DAS_4"]["ACC_STATE"] in (1, 2) # 1 NormalCCOn and 2 NormalCCSet + ret.cruiseState.standstill = cp_cruise.vl["DAS_3"]["ACC_STANDSTILL"] == 1 + ret.accFaulted = cp_cruise.vl["DAS_3"]["ACC_FAULTED"] != 0 + + if self.CP.carFingerprint in RAM_CARS: + self.auto_high_beam = cp_cam.vl["DAS_6"]['AUTO_HIGH_BEAM_ON'] # Auto High Beam isn't Located in this message on chrysler or jeep currently located in 729 message + ret.steerFaultTemporary = cp.vl["EPS_3"]["DASM_FAULT"] == 1 + else: + steer_state = cp.vl["EPS_2"]["LKAS_STATE"] + ret.steerFaultPermanent = steer_state == 4 or (steer_state == 0 and ret.vEgo > self.CP.minSteerSpeed) + # blindspot sensors if self.CP.enableBsm: ret.leftBlindspot = cp.vl["BSM_1"]["LEFT_STATUS"] == 1 ret.rightBlindspot = cp.vl["BSM_1"]["RIGHT_STATUS"] == 1 - self.lkas_counter = cp_cam.vl["LKAS_COMMAND"]["COUNTER"] self.lkas_car_model = cp_cam.vl["DAS_6"]["CAR_MODEL"] - self.lkas_status_ok = cp_cam.vl["LKAS_HEARTBIT"]["LKAS_STATUS_OK"] self.button_counter = cp.vl["CRUISE_BUTTONS"]["COUNTER"] return ret + @staticmethod + def get_cruise_signals(): + signals = [ + ("ACC_AVAILABLE", "DAS_3"), + ("ACC_ACTIVE", "DAS_3"), + ("ACC_FAULTED", "DAS_3"), + ("ACC_STANDSTILL", "DAS_3"), + ("COUNTER", "DAS_3"), + ("ACC_SET_SPEED_KPH", "DAS_4"), + ("ACC_STATE", "DAS_4"), + ] + checks = [ + ("DAS_3", 50), + ("DAS_4", 50), + ] + return signals, checks + @staticmethod def get_can_parser(CP): signals = [ # sig_name, sig_address - ("PRNDL", "GEAR"), ("DOOR_OPEN_FL", "BCM_1"), ("DOOR_OPEN_FR", "BCM_1"), ("DOOR_OPEN_RL", "BCM_1"), ("DOOR_OPEN_RR", "BCM_1"), ("Brake_Pedal_State", "ESP_1"), ("Accelerator_Position", "ECM_5"), - ("SPEED_LEFT", "SPEED_1"), - ("SPEED_RIGHT", "SPEED_1"), ("WHEEL_SPEED_FL", "ESP_6"), ("WHEEL_SPEED_RR", "ESP_6"), ("WHEEL_SPEED_RL", "ESP_6"), @@ -97,18 +130,12 @@ class CarState(CarStateBase): ("STEER_ANGLE", "STEERING"), ("STEERING_RATE", "STEERING"), ("TURN_SIGNALS", "STEERING_LEVERS"), - ("ACC_AVAILABLE", "DAS_3"), - ("ACC_ACTIVE", "DAS_3"), - ("ACC_FAULTED", "DAS_3"), ("HIGH_BEAM_PRESSED", "STEERING_LEVERS"), - ("ACC_SET_SPEED_KPH", "DAS_4"), - ("ACC_STATE", "DAS_4"), + ("SEATBELT_DRIVER_UNLATCHED", "ORC_1"), + ("COUNTER", "EPS_2",), ("COLUMN_TORQUE", "EPS_2"), ("EPS_TORQUE_MOTOR", "EPS_2"), ("LKAS_STATE", "EPS_2"), - ("COUNTER", "EPS_2",), - ("TRACTION_OFF", "TRACTION_BUTTON"), - ("SEATBELT_DRIVER_UNLATCHED", "ORC_1"), ("COUNTER", "CRUISE_BUTTONS"), ] @@ -116,18 +143,13 @@ class CarState(CarStateBase): # sig_address, frequency ("ESP_1", 50), ("EPS_2", 100), - ("SPEED_1", 100), ("ESP_6", 50), ("STEERING", 100), - ("DAS_3", 50), - ("GEAR", 50), ("ECM_5", 50), ("CRUISE_BUTTONS", 50), - ("DAS_4", 15), ("STEERING_LEVERS", 10), ("ORC_1", 2), ("BCM_1", 1), - ("TRACTION_BUTTON", 1), ] if CP.enableBsm: @@ -137,20 +159,47 @@ class CarState(CarStateBase): ] checks.append(("BSM_1", 2)) + if CP.carFingerprint in RAM_CARS: + signals += [ + ("DASM_FAULT", "EPS_3"), + ("Vehicle_Speed", "ESP_8"), + ("Gear_State", "Transmission_Status"), + ] + checks += [ + ("ESP_8", 50), + ("EPS_3", 50), + ("Transmission_Status", 50), + ] + else: + signals += [ + ("PRNDL", "GEAR"), + ("SPEED_LEFT", "SPEED_1"), + ("SPEED_RIGHT", "SPEED_1"), + ] + checks += [ + ("GEAR", 50), + ("SPEED_1", 100), + ] + signals += CarState.get_cruise_signals()[0] + checks += CarState.get_cruise_signals()[1] + return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) @staticmethod def get_cam_can_parser(CP): signals = [ - # sig_name, sig_address - ("COUNTER", "LKAS_COMMAND"), + # sig_name, sig_address, default ("CAR_MODEL", "DAS_6"), - ("LKAS_STATUS_OK", "LKAS_HEARTBIT") ] checks = [ - ("LKAS_COMMAND", 100), - ("LKAS_HEARTBIT", 10), ("DAS_6", 4), ] + if CP.carFingerprint in RAM_CARS: + signals += [ + ("AUTO_HIGH_BEAM_ON", "DAS_6"), + ] + signals += CarState.get_cruise_signals()[0] + checks += CarState.get_cruise_signals()[1] + return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2) diff --git a/selfdrive/car/chrysler/chryslercan.py b/selfdrive/car/chrysler/chryslercan.py index adcd411d31..e17e5d5b2a 100644 --- a/selfdrive/car/chrysler/chryslercan.py +++ b/selfdrive/car/chrysler/chryslercan.py @@ -1,56 +1,69 @@ from cereal import car -from selfdrive.car import make_can_msg - +from selfdrive.car.chrysler.values import RAM_CARS GearShifter = car.CarState.GearShifter VisualAlert = car.CarControl.HUDControl.VisualAlert -def create_lkas_hud(packer, gear, lkas_active, hud_alert, hud_count, lkas_car_model): - # LKAS_HUD 0x2a6 (678) Controls what lane-keeping icon is displayed. +def create_lkas_hud(packer, CP, lkas_active, hud_alert, hud_count, car_model, auto_high_beam): + # LKAS_HUD - Controls what lane-keeping icon is displayed + + # == Color == + # 0 hidden? + # 1 white + # 2 green + # 3 ldw + + # == Lines == + # 03 white Lines + # 04 grey lines + # 09 left lane close + # 0A right lane close + # 0B left Lane very close + # 0C right Lane very close + # 0D left cross cross + # 0E right lane cross - if hud_alert in (VisualAlert.steerRequired, VisualAlert.ldw): - msg = b'\x00\x00\x00\x03\x00\x00\x00\x00' - return make_can_msg(0x2a6, msg, 0) + # == Alerts == + # 7 Normal + # 6 lane departure place hands on wheel - color = 1 # default values are for park or neutral in 2017 are 0 0, but trying 1 1 for 2019 - lines = 1 - alerts = 0 + color = 2 if lkas_active else 1 + lines = 3 if lkas_active else 0 + alerts = 7 if lkas_active else 0 if hud_count < (1 * 4): # first 3 seconds, 4Hz alerts = 1 - # CAR.PACIFICA_2018_HYBRID and CAR.PACIFICA_2019_HYBRID - # had color = 1 and lines = 1 but trying 2017 hybrid style for now. - if gear in (GearShifter.drive, GearShifter.reverse, GearShifter.low): - if lkas_active: - color = 2 # control active, display green. - lines = 6 - else: - color = 1 # control off, display white. - lines = 1 + + if hud_alert in (VisualAlert.ldw, VisualAlert.steerRequired): + color = 4 + lines = 0 + alerts = 6 values = { - "LKAS_ICON_COLOR": color, # byte 0, last 2 bits - "CAR_MODEL": lkas_car_model, # byte 1 - "LKAS_LANE_LINES": lines, # byte 2, last 4 bits - "LKAS_ALERTS": alerts, # byte 3, last 4 bits - } + "LKAS_ICON_COLOR": color, + "CAR_MODEL": car_model, + "LKAS_LANE_LINES": lines, + "LKAS_ALERTS": alerts, + } + + if CP.carFingerprint in RAM_CARS: + values['AUTO_HIGH_BEAM_ON'] = auto_high_beam - return packer.make_can_msg("DAS_6", 0, values) # 0x2a6 + return packer.make_can_msg("DAS_6", 0, values) -def create_lkas_command(packer, apply_steer, moving_fast, frame): - # LKAS_COMMAND 0x292 (658) Lane-keeping signal to turn the wheel. +def create_lkas_command(packer, CP, apply_steer, lat_active, frame): + # LKAS_COMMAND Lane-keeping signal to turn the wheel + enabled_val = 2 if CP.carFingerprint in RAM_CARS else 1 values = { "STEERING_TORQUE": apply_steer, - "LKAS_CONTROL_BIT": int(moving_fast), - "COUNTER": frame % 0x10, + "LKAS_CONTROL_BIT": enabled_val if lat_active else 0, } - return packer.make_can_msg("LKAS_COMMAND", 0, values) + return packer.make_can_msg("LKAS_COMMAND", 0, values, frame % 0x10) -def create_cruise_buttons(packer, frame, cancel=False): +def create_cruise_buttons(packer, frame, bus, cancel=False): values = { "ACC_Cancel": cancel, - "COUNTER": frame % 0x10, } - return packer.make_can_msg("CRUISE_BUTTONS", 0, values) + return packer.make_can_msg("CRUISE_BUTTONS", bus, values, frame % 0x10) diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 8ebcb6b126..af202cdc46 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -1,7 +1,8 @@ #!/usr/bin/env python3 from cereal import car -from selfdrive.car.chrysler.values import CAR +from panda import Panda from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config +from selfdrive.car.chrysler.values import CAR, RAM_CARS from selfdrive.car.interfaces import CarInterfaceBase @@ -10,7 +11,9 @@ class CarInterface(CarInterfaceBase): def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, disable_radar=False): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "chrysler" - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.chrysler)] + + param = Panda.FLAG_CHRYSLER_RAM_DT if candidate in RAM_CARS else None + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.chrysler, param)] ret.steerActuatorDelay = 0.1 ret.steerLimitTimer = 0.4 @@ -39,6 +42,15 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] ret.lateralTuning.pid.kf = 0.00006 + # Ram + elif candidate == CAR.RAM_1500: + ret.wheelbase = 3.88 + ret.steerRatio = 16.3 + ret.mass = 2493. + STD_CARGO_KG + ret.maxLateralAccel = 2.4 + ret.minSteerSpeed = 14.5 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + else: raise ValueError(f"Unsupported car: {candidate}") @@ -64,9 +76,9 @@ class CarInterface(CarInterfaceBase): events = self.create_common_events(ret, extra_gears=[car.CarState.GearShifter.low]) # Low speed steer alert hysteresis logic - if self.CP.minSteerSpeed > 0. and ret.vEgo < (self.CP.minSteerSpeed + 1.): + if self.CP.minSteerSpeed > 0. and ret.vEgo < (self.CP.minSteerSpeed + 0.5): self.low_speed_alert = True - elif ret.vEgo > (self.CP.minSteerSpeed + 2.): + elif ret.vEgo > (self.CP.minSteerSpeed + 1.): self.low_speed_alert = False if self.low_speed_alert: events.add(car.CarEvent.EventName.belowSteerSpeed) @@ -76,4 +88,4 @@ class CarInterface(CarInterfaceBase): return ret def apply(self, c): - return self.CC.update(c, self.CS) + return self.CC.update(c, self.CS, self.low_speed_alert) diff --git a/selfdrive/car/chrysler/radar_interface.py b/selfdrive/car/chrysler/radar_interface.py index 8882dc2d91..348e3c3632 100755 --- a/selfdrive/car/chrysler/radar_interface.py +++ b/selfdrive/car/chrysler/radar_interface.py @@ -10,6 +10,10 @@ LAST_MSG = max(RADAR_MSGS_C + RADAR_MSGS_D) NUMBER_MSGS = len(RADAR_MSGS_C) + len(RADAR_MSGS_D) def _create_radar_can_parser(car_fingerprint): + dbc = DBC[car_fingerprint]['radar'] + if dbc is None: + return None + msg_n = len(RADAR_MSGS_C) # list of [(signal name, message name or number), (...)] # [('RADAR_STATE', 1024), @@ -46,6 +50,9 @@ class RadarInterface(RadarInterfaceBase): self.trigger_msg = LAST_MSG def update(self, can_strings): + if self.rcp is None: + return super().update(None) + vls = self.rcp.update_strings(can_strings) self.updated_messages.update(vls) @@ -81,4 +88,4 @@ class RadarInterface(RadarInterfaceBase): ret.points = [x for x in self.pts.values() if x.dRel != 0] self.updated_messages.clear() - return ret + return ret \ No newline at end of file diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 5537b383d3..40210e68e6 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -2,19 +2,12 @@ from dataclasses import dataclass from enum import Enum from typing import Dict, List, Optional, Union +from cereal import car from selfdrive.car import dbc_dict from selfdrive.car.docs_definitions import CarInfo, Harness -from cereal import car Ecu = car.CarParams.Ecu -class CarControllerParams: - STEER_MAX = 261 # 262 faults - STEER_DELTA_UP = 3 # 3 is stock. 100 is fine. 200 is too much it seems - STEER_DELTA_DOWN = 3 # no faults on the way down it seems - STEER_ERROR_MAX = 80 - - class CAR: # Chrysler PACIFICA_2017_HYBRID = "CHRYSLER PACIFICA HYBRID 2017" @@ -24,16 +17,28 @@ class CAR: PACIFICA_2020 = "CHRYSLER PACIFICA 2020" # Jeep - JEEP_CHEROKEE = "JEEP GRAND CHEROKEE V6 2018" # includes 2017 Trailhawk - JEEP_CHEROKEE_2019 = "JEEP GRAND CHEROKEE 2019" # includes 2020 Trailhawk + JEEP_CHEROKEE = "JEEP GRAND CHEROKEE V6 2018" # includes 2017 Trailhawk + JEEP_CHEROKEE_2019 = "JEEP GRAND CHEROKEE 2019" # includes 2020 Trailhawk + + # Ram + RAM_1500 = "RAM 1500 5TH GEN" + +class CarControllerParams: + STEER_MAX = 261 # higher than this faults the EPS on Chrysler/Jeep. Ram DT allows more + STEER_DELTA_UP = 3 + STEER_DELTA_DOWN = 3 + STEER_ERROR_MAX = 80 + +STEER_THRESHOLD = 120 + +RAM_CARS = {CAR.RAM_1500, } @dataclass class ChryslerCarInfo(CarInfo): package: str = "Adaptive Cruise" harness: Enum = Harness.fca - CAR_INFO: Dict[str, Optional[Union[ChryslerCarInfo, List[ChryslerCarInfo]]]] = { CAR.PACIFICA_2017_HYBRID: ChryslerCarInfo("Chrysler Pacifica Hybrid 2017-18"), CAR.PACIFICA_2018_HYBRID: None, # same platforms @@ -42,6 +47,7 @@ CAR_INFO: Dict[str, Optional[Union[ChryslerCarInfo, List[ChryslerCarInfo]]]] = { CAR.PACIFICA_2020: ChryslerCarInfo("Chrysler Pacifica 2019-20"), CAR.JEEP_CHEROKEE: ChryslerCarInfo("Jeep Grand Cherokee 2016-18", video_link="https://www.youtube.com/watch?v=eLR9o2JkuRk"), CAR.JEEP_CHEROKEE_2019: ChryslerCarInfo("Jeep Grand Cherokee 2019-20", video_link="https://www.youtube.com/watch?v=jBe4lWnRSu4"), + CAR.RAM_1500: ChryslerCarInfo("Ram 1500 2019-21"), } # Unique CAN messages: @@ -97,6 +103,11 @@ FINGERPRINTS = { # Jeep Grand Cherokee 2019, including most 2020 models 55: 8, 168: 8, 179: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 341: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 530: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 640: 1, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 960: 4, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 8, 1225: 8, 1227: 8, 1235: 8, 1242: 8, 1250: 8, 1251: 8, 1252: 8, 1254: 8, 1264: 8, 1284: 8, 1536: 8, 1537: 8, 1543: 8, 1545: 8, 1562: 8, 1568: 8, 1570: 8, 1572: 8, 1593: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1867: 8, 1875: 8, 1882: 8, 1890: 8, 1891: 8, 1892: 8, 1894: 8, 1896: 8, 1904: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 }], + CAR.RAM_1500: [ + {35: 8, 37: 8, 39: 8, 41: 8, 43: 8, 47: 8, 49: 8, 53: 8, 55: 8, 113: 8, 119: 2, 121: 8, 123: 7, 125: 6, 127: 8, 129: 8, 131: 8, 133: 8, 135: 8, 137: 8, 139: 8, 141: 8, 145: 8, 147: 8, 149: 7, 153: 8, 155: 8, 157: 8, 163: 8, 164: 8, 166: 8, 167: 8, 169: 8, 171: 8, 173: 5, 177: 3, 179: 8, 181: 8, 213: 3, 221: 8, 232: 8, 250: 8, 278: 8, 289: 5, 293: 3, 295: 8, 296: 8, 297: 4, 298: 8, 299: 8, 305: 8, 307: 8, 311: 8, 315: 8, 317: 8, 319: 8, 323: 8, 333: 8, 334: 8, 341: 8, 343: 8, 345: 8, 347: 8, 409: 6, 421: 8, 448: 6, 456: 4, 464: 8, 489: 8, 491: 8, 502: 8, 503: 8, 505: 8, 507: 5, 516: 7, 517: 7, 524: 8, 526: 6, 557: 8, 560: 8, 584: 8, 601: 8, 605: 8, 607: 8, 609: 8, 611: 8, 613: 8, 623: 8, 631: 8, 633: 8, 634: 8, 635: 8, 637: 8, 641: 8, 643: 8, 645: 2, 649: 8, 650: 8, 651: 8, 656: 4, 657: 8, 659: 5, 663: 8, 664: 8, 673: 8, 676: 8, 679: 8, 685: 8, 687: 8, 689: 5, 706: 8, 709: 8, 710: 8, 711: 8, 720: 6, 752: 2, 754: 8, 773: 8, 788: 3, 792: 8, 808: 8, 818: 8, 819: 8, 822: 8, 823: 8, 825: 2, 838: 2, 840: 8, 848: 8, 856: 4, 860: 6, 862: 8, 875: 2, 897: 8, 906: 8, 910: 8, 926: 3, 929: 8, 930: 8, 931: 8, 932: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 961: 8, 962: 8, 969: 4, 971: 8, 972: 8, 973: 8, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8}, + {35: 8, 37: 8, 39: 8, 43: 8, 47: 8, 49: 8, 53: 8, 55: 8, 113: 8, 119: 2, 121: 8, 123: 7, 125: 6, 127: 8, 129: 8, 131: 8, 133: 8, 135: 8, 137: 8, 139: 8, 141: 8, 145: 8, 147: 8, 149: 7, 153: 8, 155: 8, 157: 8, 163: 8, 164: 8, 166: 8, 167: 8, 169: 8, 171: 8, 173: 5, 177: 3, 179: 8, 181: 8, 213: 3, 221: 8, 232: 8, 250: 8, 276: 8, 277: 8, 278: 8, 289: 5, 293: 3, 295: 8, 296: 8, 297: 4, 299: 8, 301: 8, 302: 8, 305: 8, 307: 8, 311: 8, 317: 8, 319: 8, 323: 8, 327: 8, 333: 8, 334: 8, 341: 8, 343: 8, 345: 8, 347: 8, 421: 8, 448: 6, 456: 4, 457: 8, 464: 8, 489: 8, 491: 8, 502: 8, 503: 8, 507: 5, 516: 7, 517: 7, 524: 8, 526: 6, 557: 8, 560: 8, 584: 8, 601: 8, 605: 8, 607: 8, 609: 8, 613: 8, 623: 8, 631: 8, 633: 8, 634: 8, 635: 8, 637: 8, 641: 8, 643: 8, 645: 2, 649: 8, 650: 8, 651: 8, 656: 4, 657: 8, 663: 8, 673: 8, 676: 8, 679: 8, 685: 8, 687: 8, 689: 5, 706: 8, 709: 8, 710: 8, 711: 8, 720: 6, 738: 8, 752: 2, 754: 8, 773: 8, 792: 8, 808: 8, 812: 8, 813: 8, 814: 8, 818: 8, 819: 8, 821: 8, 822: 8, 823: 8, 825: 2, 838: 2, 840: 8, 847: 1, 848: 8, 856: 4, 860: 6, 862: 8, 874: 2, 876: 8, 897: 8, 906: 8, 910: 8, 926: 3, 929: 8, 930: 8, 931: 8, 932: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 961: 8, 962: 8, 969: 4, 971: 8, 972: 8, 973: 8, 975: 8, 976: 8, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1030: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8}, + {35: 8, 37: 8, 39: 8, 43: 8, 47: 8, 49: 8, 53: 8, 55: 8, 113: 8, 119: 2, 121: 8, 123: 7, 125: 6, 127: 8, 129: 8, 131: 8, 133: 8, 135: 8, 137: 8, 139: 8, 141: 8, 145: 8, 147: 8, 149: 7, 153: 8, 155: 8, 157: 8, 163: 8, 164: 8, 166: 8, 167: 8, 169: 8, 171: 8, 173: 5, 177: 3, 179: 8, 181: 8, 213: 3, 221: 8, 232: 8, 250: 8, 289: 5, 293: 3, 295: 8, 296: 8, 297: 4, 299: 8, 301: 8, 302: 8, 305: 8, 307: 8, 311: 8, 317: 8, 319: 8, 323: 8, 334: 8, 337: 8, 343: 8, 347: 8, 409: 6, 421: 8, 448: 6, 456: 4, 464: 8, 489: 8, 491: 8, 502: 8, 503: 8, 507: 5, 516: 7, 517: 7, 524: 8, 526: 6, 557: 8, 560: 8, 584: 8, 601: 8, 605: 8, 607: 8, 609: 8, 613: 8, 623: 8, 631: 8, 633: 8, 634: 8, 635: 8, 637: 8, 641: 8, 643: 8, 645: 2, 649: 8, 650: 8, 651: 8, 656: 4, 657: 8, 659: 5, 663: 8, 664: 8, 673: 8, 676: 8, 679: 8, 685: 8, 687: 8, 689: 5, 706: 8, 709: 8, 710: 8, 711: 8, 720: 6, 752: 2, 754: 8, 773: 8, 788: 3, 792: 8, 808: 8, 812: 8, 813: 8, 814: 8, 818: 8, 819: 8, 821: 8, 822: 8, 825: 2, 838: 2, 840: 8, 847: 1, 848: 8, 856: 4, 860: 6, 862: 8, 876: 8, 897: 8, 906: 8, 910: 8, 926: 3, 929: 8, 930: 8, 931: 8, 932: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 961: 8, 962: 8, 969: 4, 971: 8, 972: 8, 973: 8, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1030: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8}, + ], } @@ -108,6 +119,5 @@ DBC = { CAR.PACIFICA_2019_HYBRID: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), CAR.JEEP_CHEROKEE: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), CAR.JEEP_CHEROKEE_2019: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.RAM_1500: dbc_dict('chrysler_ram_dt_generated', None), } - -STEER_THRESHOLD = 120 diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 19b1a05c23..96eb5f67b9 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -38,6 +38,7 @@ routes = [ TestRoute("378472f830ee7395|2021-05-28--07-38-43", CHRYSLER.PACIFICA_2018_HYBRID), TestRoute("8190c7275a24557b|2020-01-29--08-33-58", CHRYSLER.PACIFICA_2019_HYBRID), TestRoute("3d84727705fecd04|2021-05-25--08-38-56", CHRYSLER.PACIFICA_2020), + TestRoute("221c253375af4ee9|2022-06-15--18-38-24", CHRYSLER.RAM_1500), #TestRoute("f1b4c567731f4a1b|2018-04-30--10-15-35", FORD.FUSION), diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index a2200926c0..be81af2606 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -19,8 +19,9 @@ FORD FOCUS 4TH GEN: [.nan, 1.5, .nan] # No steering wheel COMMA BODY: [.nan, 1000, .nan] -# Totally new car +# Totally new cars KIA EV6 2022: [3.0, 2.5, 0.0] +RAM 1500 5TH GEN: [2.0, 2.0, 0.05] # Dashcam or fallback configured as ideal car mock: [10.0, 10, 0.0] diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 0eeae1e3e3..b0136da88e 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -b904e52e9de4ff7b2bd7f6af8b19abaf4957e6cc \ No newline at end of file +ebe7f1285ec60f522179606d483a198535c0e83a \ No newline at end of file From fd2de54172b4a76f2ab8ac5d8f8eca5c41739351 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 7 Jul 2022 00:24:03 -0700 Subject: [PATCH 220/302] Stock longitudinal: spam resume button when lead starts moving (#24873) * always log leads, we hide them in ui * only spam resume when future is > vEgoStarting * do rest but vw * vw * remove comments * rename to resume * maintain original button msg rate * mazda: ensure no resume if cancelling * same for non-HDA2 * Always run planner if not opLong * try 0.2 * 0.1 should be pretty safe * add test for resuming * fix test * stricter test, speeds[-1] is 0.14 when starting here * no walrus * fixup mazda cc * remove extra import --- selfdrive/car/honda/carcontroller.py | 2 +- selfdrive/car/hyundai/carcontroller.py | 4 ++-- selfdrive/car/mazda/carcontroller.py | 11 ++++------- selfdrive/car/volkswagen/carcontroller.py | 5 ++--- selfdrive/controls/controlsd.py | 4 ++++ selfdrive/test/longitudinal_maneuvers/maneuver.py | 5 +++++ selfdrive/test/longitudinal_maneuvers/plant.py | 3 +++ .../test/longitudinal_maneuvers/test_longitudinal.py | 12 ++++++++++++ 8 files changed, 33 insertions(+), 13 deletions(-) diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index 14049c9997..d47caaa9ad 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -195,7 +195,7 @@ class CarController: # If using stock ACC, spam cancel command to kill gas when OP disengages. if pcm_cancel_cmd: can_sends.append(hondacan.spam_buttons_command(self.packer, CruiseButtons.CANCEL, idx, self.CP.carFingerprint)) - elif CS.out.cruiseState.standstill: + elif CC.cruiseControl.resume: can_sends.append(hondacan.spam_buttons_command(self.packer, CruiseButtons.RES_ACCEL, idx, self.CP.carFingerprint)) else: diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 4fbb5ce0e1..f3066bda03 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -78,7 +78,7 @@ class CarController: self.last_button_frame = self.frame # cruise standstill resume - elif CC.enabled and CS.out.cruiseState.standstill: + elif CC.cruiseControl.resume: can_sends.append(hda2can.create_buttons(self.packer, CS.buttons_counter+1, False, True)) self.last_button_frame = self.frame else: @@ -96,7 +96,7 @@ class CarController: if not self.CP.openpilotLongitudinalControl: if CC.cruiseControl.cancel: can_sends.append(hyundaican.create_clu11(self.packer, self.frame, CS.clu11, Buttons.CANCEL)) - elif CS.out.cruiseState.standstill: + elif CC.cruiseControl.resume: # send resume at a max freq of 10Hz if (self.frame - self.last_button_frame) * DT_CTRL > 0.1: # send 25 messages at a time to increases the likelihood of resume being accepted diff --git a/selfdrive/car/mazda/carcontroller.py b/selfdrive/car/mazda/carcontroller.py index 0e43a11ceb..a83cef508a 100644 --- a/selfdrive/car/mazda/carcontroller.py +++ b/selfdrive/car/mazda/carcontroller.py @@ -29,13 +29,6 @@ class CarController: CS.out.steeringTorque, CarControllerParams) self.steer_rate_limited = new_steer != apply_steer - if CC.enabled: - if CS.out.standstill and self.frame % 5 == 0: - # Mazda Stop and Go requires a RES button (or gas) press if the car stops more than 3 seconds - # Send Resume button at 20hz if we're engaged at standstill to support full stop and go! - # TODO: improve the resume trigger logic by looking at actual radar data - can_sends.append(mazdacan.create_button_cmd(self.packer, self.CP.carFingerprint, CS.crz_btns_counter, Buttons.RESUME)) - if CC.cruiseControl.cancel: # If brake is pressed, let us wait >70ms before trying to disable crz to avoid # a race condition with the stock system, where the second cancel from openpilot @@ -48,6 +41,10 @@ class CarController: can_sends.append(mazdacan.create_button_cmd(self.packer, self.CP.carFingerprint, CS.crz_btns_counter, Buttons.CANCEL)) else: self.brake_counter = 0 + if CC.cruiseControl.resume and self.frame % 5 == 0: + # Mazda Stop and Go requires a RES button (or gas) press if the car stops more than 3 seconds + # Send Resume button when planner wants car to move + can_sends.append(mazdacan.create_button_cmd(self.packer, self.CP.carFingerprint, CS.crz_btns_counter, Buttons.RESUME)) self.apply_steer_last = apply_steer diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py index 4614463c6e..1643fbe9b6 100644 --- a/selfdrive/car/volkswagen/carcontroller.py +++ b/selfdrive/car/volkswagen/carcontroller.py @@ -96,9 +96,8 @@ class CarController: # Cancel ACC if it's engaged with OP disengaged. self.graButtonStatesToSend = BUTTON_STATES.copy() self.graButtonStatesToSend["cancel"] = True - elif CC.enabled and CS.out.cruiseState.standstill: - # Blip the Resume button if we're engaged at standstill. - # FIXME: This is a naive implementation, improve with visiond or radar input. + elif CC.cruiseControl.resume: + # Send Resume button when planner wants car to move self.graButtonStatesToSend = BUTTON_STATES.copy() self.graButtonStatesToSend["resumeCruise"] = True diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 9e3af9eb63..6f0c9c2ae6 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -658,6 +658,10 @@ class Controls: if self.joystick_mode and self.sm.rcv_frame['testJoystick'] > 0 and self.sm['testJoystick'].buttons[0]: CC.cruiseControl.cancel = True + speeds = self.sm['longitudinalPlan'].speeds + if len(speeds): + CC.cruiseControl.resume = self.enabled and CS.cruiseState.standstill and speeds[-1] > 0.1 + hudControl = CC.hudControl hudControl.setSpeed = float(self.v_cruise_kph * CV.KPH_TO_MS) hudControl.speedVisible = self.enabled diff --git a/selfdrive/test/longitudinal_maneuvers/maneuver.py b/selfdrive/test/longitudinal_maneuvers/maneuver.py index 9b4d016430..0d605a5fc7 100644 --- a/selfdrive/test/longitudinal_maneuvers/maneuver.py +++ b/selfdrive/test/longitudinal_maneuvers/maneuver.py @@ -16,6 +16,7 @@ class Maneuver(): self.only_lead2 = kwargs.get("only_lead2", False) self.only_radar = kwargs.get("only_radar", False) + self.ensure_start = kwargs.get("ensure_start", False) self.duration = duration self.title = title @@ -52,5 +53,9 @@ class Maneuver(): print("Crashed!!!!") valid = False + if self.ensure_start and log['v_rel'] > 0 and log['speeds'][-1] <= 0.1: + print('Planner not starting!') + valid = False + print("maneuver end", valid) return valid, np.array(logs) diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index 13025a9f03..3bd50ebcfa 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -28,6 +28,7 @@ class Plant(): self.distance = 0. self.speed = speed self.acceleration = 0.0 + self.speeds = [] # lead car self.distance_lead = distance_lead @@ -98,6 +99,7 @@ class Plant(): self.planner.update(sm) self.speed = self.planner.v_desired_filter.x self.acceleration = self.planner.a_desired + self.speeds = self.planner.v_desired_trajectory.tolist() fcw = self.planner.fcw self.distance_lead = self.distance_lead + v_lead * self.ts @@ -129,6 +131,7 @@ class Plant(): "distance": self.distance, "speed": self.speed, "acceleration": self.acceleration, + "speeds": self.speeds, "distance_lead": self.distance_lead, "fcw": fcw, } diff --git a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py index 698877dd3a..ec698d88fa 100755 --- a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py +++ b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py @@ -3,6 +3,7 @@ import os import unittest from common.params import Params +from selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import STOP_DISTANCE from selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver @@ -106,6 +107,17 @@ maneuvers = [ breakpoints=[1., 1.01, 11.], cruise_values=[float("nan"), 15., 15.], ), + # controls relies on planner commanding to move for stock-ACC resume spamming + Maneuver( + "resume from a stop", + duration=20., + initial_speed=0., + lead_relevancy=True, + initial_distance_lead=STOP_DISTANCE, + speed_lead_values=[0., 0., 2.], + breakpoints=[1., 10., 15.], + ensure_start=True, + ), ] From 30cb9ac962395a86464fdfc079b5f0030c7b9b9d Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 7 Jul 2022 00:28:21 -0700 Subject: [PATCH 221/302] FW query debug script: print version brand (#25058) * test_fw_query_on_routes: print brand * dynamic paddign --- selfdrive/debug/test_fw_query_on_routes.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/selfdrive/debug/test_fw_query_on_routes.py b/selfdrive/debug/test_fw_query_on_routes.py index 789baeca4b..8c8c631c38 100755 --- a/selfdrive/debug/test_fw_query_on_routes.py +++ b/selfdrive/debug/test_fw_query_on_routes.py @@ -126,9 +126,10 @@ if __name__ == "__main__": print("New style (exact):", exact_matches) print("New style (fuzzy):", fuzzy_matches) - for version in car_fw: + padding = max([len(fw.brand) for fw in car_fw]) + for version in sorted(car_fw, key=lambda fw: fw.brand): subaddr = None if version.subAddress == 0 else hex(version.subAddress) - print(f" (Ecu.{version.ecu}, {hex(version.address)}, {subaddr}): [{version.fwVersion}],") + print(f" Brand: {version.brand:{padding}} - (Ecu.{version.ecu}, {hex(version.address)}, {subaddr}): [{version.fwVersion}],") print("Mismatches") found = False From edf170103ed0d244e0483794feee6c3b4023ccc2 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Thu, 7 Jul 2022 11:14:31 +0200 Subject: [PATCH 222/302] Process replay: Fix subtest diff (#25054) Fix subtest diff --- selfdrive/test/process_replay/test_processes.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 9cbf4439ac..04bf51e2e9 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -71,7 +71,7 @@ def run_test_process(data): assert os.path.exists(cur_log_fn), f"Cannot find log to upload: {cur_log_fn}" upload_file(cur_log_fn, os.path.basename(cur_log_fn)) os.remove(cur_log_fn) - return (segment, cfg.proc_name, res) + return (segment, cfg.proc_name, cfg.subtest_name, res) def get_log_data(segment): @@ -212,9 +212,9 @@ if __name__ == "__main__": results: Any = defaultdict(dict) p2 = pool.map(run_test_process, pool_args) - for (segment, proc, result) in tqdm(p2, desc="Running Tests", total=len(pool_args)): + for (segment, proc, subtest_name, result) in tqdm(p2, desc="Running Tests", total=len(pool_args)): if isinstance(result, list): - results[segment][proc] = result + results[segment][proc + subtest_name] = result diff1, diff2, failed = format_diff(results, ref_commit) if not upload: From a3a9a0685c63ea57dc936e496cd5e6be5a71512e Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 7 Jul 2022 12:02:31 +0200 Subject: [PATCH 223/302] onroad.cc: fix mutcd sign width for metric speed limit --- selfdrive/ui/qt/onroad.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 604d3c09a9..ca39a89ae4 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -296,7 +296,7 @@ void NvgWindow::drawHud(QPainter &p) { // US/Canada (MUTCD style) sign if (has_us_speed_limit) { const int border_width = 6; - const int sign_width = (speedLimitStr.size() >= 3) ? 199 : 148; + const int sign_width = rect_width - 24; const int sign_height = 186; // White outer square From eaf7eb42784732136e52cd031035e9c5ab520e6e Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Thu, 7 Jul 2022 13:06:51 +0200 Subject: [PATCH 224/302] Laikad: Use clocks for faster fetching orbits (#25060) * Use clocks msg to for first fetch of orbits. Which is sent earlier than ublox msgs * refactor last_fetch_orbits * Add comment. Add test * increase timeout * Add clocks to process replay --- selfdrive/locationd/laikad.py | 39 ++++++++++++------- selfdrive/locationd/test/test_laikad.py | 26 ++++++++++++- .../test/process_replay/process_replay.py | 4 +- 3 files changed, 53 insertions(+), 16 deletions(-) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 40519da7bc..e262407e02 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -5,6 +5,7 @@ import os import time from collections import defaultdict from concurrent.futures import Future, ProcessPoolExecutor +from datetime import datetime from enum import IntEnum from typing import List, Optional @@ -13,7 +14,7 @@ import numpy as np from cereal import log, messaging from common.params import Params, put_nonblocking from laika import AstroDog -from laika.constants import SECS_IN_MIN +from laika.constants import SECS_IN_HR, SECS_IN_MIN from laika.ephemeris import Ephemeris, EphemerisType, convert_ublox_ephem from laika.gps_time import GPSTime from laika.helpers import ConstellationId @@ -30,7 +31,8 @@ CACHE_VERSION = 0.1 class Laikad: - def __init__(self, valid_const=("GPS", "GLONASS"), auto_fetch_orbits=True, auto_update=False, valid_ephem_types=(EphemerisType.ULTRA_RAPID_ORBIT, EphemerisType.NAV), + def __init__(self, valid_const=("GPS", "GLONASS"), auto_fetch_orbits=True, auto_update=False, + valid_ephem_types=(EphemerisType.ULTRA_RAPID_ORBIT, EphemerisType.NAV), save_ephemeris=False): """ valid_const: GNSS constellation which can be used @@ -47,6 +49,7 @@ class Laikad: self.orbit_fetch_future: Optional[Future] = None self.last_fetch_orbits_t = None + self.got_first_ublox_msg = False self.last_cached_t = None self.save_ephemeris = save_ephemeris self.load_cache() @@ -72,8 +75,9 @@ class Laikad: except json.decoder.JSONDecodeError: cloudlog.exception("Error parsing cache") timestamp = self.last_fetch_orbits_t.as_datetime() if self.last_fetch_orbits_t is not None else 'Nan' - cloudlog.debug(f"Loaded nav and orbits cache with timestamp: {timestamp}. Unique orbit and nav sats: {list(cache['orbits'].keys())} {list(cache['nav'].keys())} " + - f"Total: {sum([len(v) for v in cache['orbits']])} and {sum([len(v) for v in cache['nav']])}") + cloudlog.debug( + f"Loaded nav and orbits cache with timestamp: {timestamp}. Unique orbit and nav sats: {list(cache['orbits'].keys())} {list(cache['nav'].keys())} " + + f"Total: {sum([len(v) for v in cache['orbits']])} and {sum([len(v) for v in cache['nav']])}") def cache_ephemeris(self, t: GPSTime): if self.save_ephemeris and (self.last_cached_t is None or t - self.last_cached_t > SECS_IN_MIN): @@ -98,9 +102,10 @@ class Laikad: t = ublox_mono_time * 1e-9 report = ublox_msg.measurementReport if report.gpsWeek > 0: + self.got_first_ublox_msg = True latest_msg_t = GPSTime(report.gpsWeek, report.rcvTow) if self.auto_fetch_orbits: - self.fetch_orbits(latest_msg_t + SECS_IN_MIN, block) + self.fetch_orbits(latest_msg_t, block) new_meas = read_raw_ublox(report) # Filter measurements with unexpected pseudoranges for GPS and GLONASS satellites @@ -174,24 +179,26 @@ class Laikad: self.gnss_kf.init_state(x_initial, covs_diag=p_initial_diag) def fetch_orbits(self, t: GPSTime, block): - if t not in self.astro_dog.orbit_fetched_times and (self.last_fetch_orbits_t is None or t - self.last_fetch_orbits_t > SECS_IN_MIN): + # Download new orbits if 1 hour of orbits data left + if t + SECS_IN_HR not in self.astro_dog.orbit_fetched_times and (self.last_fetch_orbits_t is None or abs(t - self.last_fetch_orbits_t) > SECS_IN_MIN): astro_dog_vars = self.astro_dog.valid_const, self.astro_dog.auto_update, self.astro_dog.valid_ephem_types - ret = None - if block: + if block: # Used for testing purposes ret = get_orbit_data(t, *astro_dog_vars) elif self.orbit_fetch_future is None: self.orbit_fetch_executor = ProcessPoolExecutor(max_workers=1) self.orbit_fetch_future = self.orbit_fetch_executor.submit(get_orbit_data, t, *astro_dog_vars) elif self.orbit_fetch_future.done(): - self.last_fetch_orbits_t = t ret = self.orbit_fetch_future.result() self.orbit_fetch_executor = self.orbit_fetch_future = None if ret is not None: - self.astro_dog.orbits, self.astro_dog.orbit_fetched_times = ret - self.cache_ephemeris(t=t) + if ret[0] is None: + self.last_fetch_orbits_t = ret[2] + else: + self.astro_dog.orbits, self.astro_dog.orbit_fetched_times, self.last_fetch_orbits_t = ret + self.cache_ephemeris(t=t) def get_orbit_data(t: GPSTime, valid_const, auto_update, valid_ephem_types): @@ -201,9 +208,10 @@ def get_orbit_data(t: GPSTime, valid_const, auto_update, valid_ephem_types): try: astro_dog.get_orbit_data(t, only_predictions=True) cloudlog.info(f"Done parsing orbits. Took {time.monotonic() - start_time:.1f}s") - return astro_dog.orbits, astro_dog.orbit_fetched_times + return astro_dog.orbits, astro_dog.orbit_fetched_times, t except (RuntimeError, ValueError, IOError) as e: cloudlog.warning(f"No orbit data found or parsing failure: {e}") + return None, None, t def create_measurement_msg(meas: GNSSMeasurement): @@ -284,7 +292,7 @@ class EphemerisSourceType(IntEnum): def main(sm=None, pm=None): if sm is None: - sm = messaging.SubMaster(['ubloxGnss']) + sm = messaging.SubMaster(['ubloxGnss', 'clocks']) if pm is None: pm = messaging.PubMaster(['gnssMeasurements']) @@ -299,6 +307,11 @@ def main(sm=None, pm=None): msg = laikad.process_ublox_msg(ublox_msg, sm.logMonoTime['ubloxGnss'], block=replay) if msg is not None: pm.send('gnssMeasurements', msg) + if not laikad.got_first_ublox_msg and sm.updated['clocks']: + clocks_msg = sm['clocks'] + t = GPSTime.from_datetime(datetime.utcfromtimestamp(clocks_msg.wallTimeNanos * 1E-9)) + if laikad.auto_fetch_orbits: + laikad.fetch_orbits(t, block=replay) if __name__ == "__main__": diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py index 26c1d28820..3a7c073b55 100755 --- a/selfdrive/locationd/test/test_laikad.py +++ b/selfdrive/locationd/test/test_laikad.py @@ -67,7 +67,7 @@ class TestLaikad(unittest.TestCase): gpstime = GPSTime.from_datetime(datetime(2021, month=3, day=1)) laikad = Laikad() laikad.fetch_orbits(gpstime, block=False) - laikad.orbit_fetch_future.result(5) + laikad.orbit_fetch_future.result(30) # Get results and save orbits to laikad: laikad.fetch_orbits(gpstime, block=False) @@ -75,7 +75,7 @@ class TestLaikad(unittest.TestCase): self.assertIsNotNone(ephem) laikad.fetch_orbits(gpstime+2*SECS_IN_DAY, block=False) - laikad.orbit_fetch_future.result(5) + laikad.orbit_fetch_future.result(30) # Get results and save orbits to laikad: laikad.fetch_orbits(gpstime + 2 * SECS_IN_DAY, block=False) @@ -83,6 +83,28 @@ class TestLaikad(unittest.TestCase): self.assertIsNotNone(ephem) self.assertNotEqual(ephem, ephem2) + def test_fetch_orbits_with_wrong_clocks(self): + laikad = Laikad() + + def check_has_orbits(): + self.assertGreater(len(laikad.astro_dog.orbits), 0) + ephem = laikad.astro_dog.orbits['G01'][0] + self.assertIsNotNone(ephem) + real_current_time = GPSTime.from_datetime(datetime(2021, month=3, day=1)) + wrong_future_clock_time = real_current_time + SECS_IN_DAY + + laikad.fetch_orbits(wrong_future_clock_time, block=True) + check_has_orbits() + self.assertEqual(laikad.last_fetch_orbits_t, wrong_future_clock_time) + + # Test fetching orbits with earlier time + assert real_current_time < laikad.last_fetch_orbits_t + + laikad.astro_dog.orbits = {} + laikad.fetch_orbits(real_current_time, block=True) + check_has_orbits() + self.assertEqual(laikad.last_fetch_orbits_t, real_current_time) + def test_ephemeris_source_in_msg(self): data_mock = defaultdict(str) data_mock['sv_id'] = 1 diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 9c45281b0c..c667aa3887 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -239,7 +239,7 @@ def ublox_rcv_callback(msg): def laika_rcv_callback(msg, CP, cfg, fsm): - if msg.ubloxGnss.which() == "measurementReport": + if msg.which() == 'ubloxGnss' and msg.ubloxGnss.which() == "measurementReport": return ["gnssMeasurements"], True else: return [], True @@ -352,6 +352,7 @@ CONFIGS = [ subtest_name="Offline", pub_sub={ "ubloxGnss": ["gnssMeasurements"], + "clocks": [] }, ignore=["logMonoTime"], init_callback=get_car_params, @@ -364,6 +365,7 @@ CONFIGS = [ proc_name="laikad", pub_sub={ "ubloxGnss": ["gnssMeasurements"], + "clocks": [] }, ignore=["logMonoTime"], init_callback=get_car_params, From 356190f6712b68218237147deddf90fbe6268b6e Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 7 Jul 2022 16:13:05 +0200 Subject: [PATCH 225/302] fix MacOS buid: replay frameworks (#25061) * replay: fix macos build * here too * keep original frameworks --- tools/replay/SConscript | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/tools/replay/SConscript b/tools/replay/SConscript index 4a85f46d61..d3967708fa 100644 --- a/tools/replay/SConscript +++ b/tools/replay/SConscript @@ -2,8 +2,14 @@ import os Import('env', 'qt_env', 'arch', 'common', 'messaging', 'visionipc', 'cereal', 'transformations') +base_frameworks = qt_env['FRAMEWORKS'] base_libs = [common, messaging, cereal, visionipc, transformations, 'zmq', - 'capnp', 'kj', 'm', 'OpenCL', 'ssl', 'crypto', 'pthread'] + qt_env["LIBS"] + 'capnp', 'kj', 'm', 'ssl', 'crypto', 'pthread'] + qt_env["LIBS"] + +if arch == "Darwin": + base_frameworks.append('OpenCL') +else: + base_libs.append('OpenCL') qt_libs = ['qt_util'] + base_libs if arch in ['x86_64', 'Darwin'] or GetOption('extras'): @@ -11,9 +17,9 @@ if arch in ['x86_64', 'Darwin'] or GetOption('extras'): replay_lib_src = ["replay.cc", "consoleui.cc", "camera.cc", "filereader.cc", "logreader.cc", "framereader.cc", "route.cc", "util.cc"] - replay_lib = qt_env.Library("qt_replay", replay_lib_src, LIBS=qt_libs) + replay_lib = qt_env.Library("qt_replay", replay_lib_src, LIBS=qt_libs, FRAMEWORKS=base_frameworks) replay_libs = [replay_lib, 'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv', 'ncurses'] + qt_libs - qt_env.Program("replay", ["main.cc"], LIBS=replay_libs) + qt_env.Program("replay", ["main.cc"], LIBS=replay_libs, FRAMEWORKS=base_frameworks) if GetOption('test'): qt_env.Program('tests/test_replay', ['tests/test_runner.cc', 'tests/test_replay.cc'], LIBS=[replay_libs]) From 7e187426c7f02b8d63bce394f08219307e5900ca Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 7 Jul 2022 18:00:07 +0200 Subject: [PATCH 226/302] athena: skip duplicate upload requests (#25062) * athena: skip duplicate upload requests * cleanup * keep simple * just ignore --- selfdrive/athena/athenad.py | 5 +++++ selfdrive/athena/tests/test_athenad.py | 23 +++++++++++++++++++---- 2 files changed, 24 insertions(+), 4 deletions(-) diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index b0e138c495..6ccd6c3de1 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -364,6 +364,11 @@ def uploadFilesToUrls(files_data): failed.append(fn) continue + # Skip item if already in queue + url = file['url'].split('?')[0] + if any(url == item['url'].split('?')[0] for item in listUploadQueue()): + continue + item = UploadItem( path=path, url=file['url'], diff --git a/selfdrive/athena/tests/test_athenad.py b/selfdrive/athena/tests/test_athenad.py index 382b549c1b..7f511eecf6 100755 --- a/selfdrive/athena/tests/test_athenad.py +++ b/selfdrive/athena/tests/test_athenad.py @@ -124,7 +124,7 @@ class TestAthenadMethods(unittest.TestCase): fn = os.path.join(athenad.ROOT, 'qlog.bz2') Path(fn).touch() if fn.endswith('.bz2'): - self.assertEqual(athenad.strip_bz2_extension(fn), fn[:-4]) + self.assertEqual(athenad.strip_bz2_extension(fn), fn[:-4]) @with_http_server @@ -142,9 +142,6 @@ class TestAthenadMethods(unittest.TestCase): @with_http_server def test_uploadFileToUrl(self, host): - not_exists_resp = dispatcher["uploadFileToUrl"]("does_not_exist.bz2", "http://localhost:1238", {}) - self.assertEqual(not_exists_resp, {'enqueued': 0, 'items': [], 'failed': ['does_not_exist.bz2']}) - fn = os.path.join(athenad.ROOT, 'qlog.bz2') Path(fn).touch() @@ -155,6 +152,24 @@ class TestAthenadMethods(unittest.TestCase): self.assertIsNotNone(resp['items'][0].get('id')) self.assertEqual(athenad.upload_queue.qsize(), 1) + @with_http_server + def test_uploadFileToUrl_duplicate(self, host): + fn = os.path.join(athenad.ROOT, 'qlog.bz2') + Path(fn).touch() + + url1 = f"{host}/qlog.bz2?sig=sig1" + dispatcher["uploadFileToUrl"]("qlog.bz2", url1, {}) + + # Upload same file again, but with different signature + url2 = f"{host}/qlog.bz2?sig=sig2" + resp = dispatcher["uploadFileToUrl"]("qlog.bz2", url2, {}) + self.assertEqual(resp, {'enqueued': 0, 'items': []}) + + @with_http_server + def test_uploadFileToUrl_does_not_exist(self, host): + not_exists_resp = dispatcher["uploadFileToUrl"]("does_not_exist.bz2", "http://localhost:1238", {}) + self.assertEqual(not_exists_resp, {'enqueued': 0, 'items': [], 'failed': ['does_not_exist.bz2']}) + @with_http_server def test_upload_handler(self, host): fn = os.path.join(athenad.ROOT, 'qlog.bz2') From ea80ee0845b619cc20309228611c01ed4c717fd1 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 7 Jul 2022 09:40:04 -0700 Subject: [PATCH 227/302] Chrysler: resume from cruise standstill (#25009) * Chrysler: resume from cruise standstill * bump panda * resume isn't set yet --- panda | 2 +- selfdrive/car/chrysler/carcontroller.py | 6 ++++-- selfdrive/car/chrysler/chryslercan.py | 3 ++- 3 files changed, 7 insertions(+), 4 deletions(-) diff --git a/panda b/panda index fae3ee2e81..53466f0934 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit fae3ee2e8161d34a7c1939503e583db9b85e5402 +Subproject commit 53466f09344c8ff6cdce3b19df76b5bca79e1327 diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py index 606cb51176..e0eb979e6a 100644 --- a/selfdrive/car/chrysler/carcontroller.py +++ b/selfdrive/car/chrysler/carcontroller.py @@ -25,9 +25,11 @@ class CarController: # *** control msgs *** + das_bus = 2 if self.CP.carFingerprint in RAM_CARS else 0 if CC.cruiseControl.cancel: - bus = 2 if self.CP.carFingerprint in RAM_CARS else 0 - can_sends.append(create_cruise_buttons(self.packer, CS.button_counter + 1, bus, cancel=True)) + can_sends.append(create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, cancel=True)) + elif CC.enabled and CS.out.cruiseState.standstill: + can_sends.append(create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, resume=True)) # HUD alerts if self.frame % 25 == 0: diff --git a/selfdrive/car/chrysler/chryslercan.py b/selfdrive/car/chrysler/chryslercan.py index e17e5d5b2a..632c0d2bcf 100644 --- a/selfdrive/car/chrysler/chryslercan.py +++ b/selfdrive/car/chrysler/chryslercan.py @@ -62,8 +62,9 @@ def create_lkas_command(packer, CP, apply_steer, lat_active, frame): return packer.make_can_msg("LKAS_COMMAND", 0, values, frame % 0x10) -def create_cruise_buttons(packer, frame, bus, cancel=False): +def create_cruise_buttons(packer, frame, bus, cancel=False, resume=False): values = { "ACC_Cancel": cancel, + "ACC_Resume": resume, } return packer.make_can_msg("CRUISE_BUTTONS", bus, values, frame % 0x10) From 8d98d8c6578830e28ea8f39fce3844a7e493c019 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 7 Jul 2022 10:28:55 -0700 Subject: [PATCH 228/302] process replay: add Ram route (#25063) --- selfdrive/car/chrysler/interface.py | 4 +++- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/test/process_replay/test_processes.py | 2 ++ 3 files changed, 6 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index af202cdc46..920000b271 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -2,7 +2,7 @@ from cereal import car from panda import Panda from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config -from selfdrive.car.chrysler.values import CAR, RAM_CARS +from selfdrive.car.chrysler.values import CAR, DBC, RAM_CARS from selfdrive.car.interfaces import CarInterfaceBase @@ -12,6 +12,8 @@ class CarInterface(CarInterfaceBase): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "chrysler" + ret.radarOffCan = DBC[candidate]['radar'] is None + param = Panda.FLAG_CHRYSLER_RAM_DT if candidate in RAM_CARS else None ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.chrysler, param)] diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index b0136da88e..0521fd8295 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -ebe7f1285ec60f522179606d483a198535c0e83a \ No newline at end of file +cf46781e405a01c96307d30d1266d46e0fa92255 \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 04bf51e2e9..96d1014004 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -24,6 +24,7 @@ original_segments = [ ("HONDA", "eb140f119469d9ab|2021-06-12--10-46-24--27"), # HONDA.CIVIC (NIDEC) ("HONDA2", "7d2244f34d1bbcda|2021-06-25--12-25-37--26"), # HONDA.ACCORD (BOSCH) ("CHRYSLER", "4deb27de11bee626|2021-02-20--11-28-55--8"), # CHRYSLER.PACIFICA + ("RAM", "2f4452b03ccb98f0|2022-07-07--08-01-56--2"), # CHRYSLER.RAM_1500 ("SUBARU", "4d70bc5e608678be|2021-01-15--17-02-04--5"), # SUBARU.IMPREZA ("GM", "0c58b6a25109da2b|2021-02-23--16-35-50--11"), # GM.VOLT ("NISSAN", "35336926920f3571|2021-02-12--18-38-48--46"), # NISSAN.XTRAIL @@ -43,6 +44,7 @@ segments = [ ("HONDA", "regen17B09D158B8|2022-07-06--14-31-46--0"), ("HONDA2", "regen041739C3E9A|2022-07-06--15-08-02--0"), ("CHRYSLER", "regenBB2F9C1425C|2022-07-06--14-31-41--0"), + ("RAM", "2f4452b03ccb98f0|2022-07-07--08-01-56--2"), ("SUBARU", "regen732B69F33B1|2022-07-06--14-36-18--0"), ("GM", "regen01D09D915B5|2022-07-06--14-36-20--0"), ("NISSAN", "regenEA6FB2773F5|2022-07-06--14-58-23--0"), From 568cc0f892d650bd5906b59e1ab169158a7a6bf7 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 8 Jul 2022 01:54:56 +0800 Subject: [PATCH 229/302] loggerd: remove 'enable' from struct LogCameraInfo (#25052) remove enalbe --- selfdrive/loggerd/encoderd.cc | 6 ++---- selfdrive/loggerd/loggerd.cc | 6 ++---- selfdrive/loggerd/loggerd.h | 5 ----- 3 files changed, 4 insertions(+), 13 deletions(-) diff --git a/selfdrive/loggerd/encoderd.cc b/selfdrive/loggerd/encoderd.cc index 87cf4a492f..9bd8e2f1d4 100644 --- a/selfdrive/loggerd/encoderd.cc +++ b/selfdrive/loggerd/encoderd.cc @@ -124,10 +124,8 @@ void encoderd_thread() { std::vector encoder_threads; for (const auto &cam : cameras_logged) { - if (cam.enable) { - encoder_threads.push_back(std::thread(encoder_thread, &s, cam)); - s.max_waiting++; - } + encoder_threads.push_back(std::thread(encoder_thread, &s, cam)); + s.max_waiting++; } for (auto &t : encoder_threads) t.join(); } diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index a75ab2c92b..e0892e68b4 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -204,10 +204,8 @@ void loggerd_thread() { // init encoders s.last_camera_seen_tms = millis_since_boot(); for (const auto &cam : cameras_logged) { - if (cam.enable) { - s.max_waiting++; - if (cam.has_qcamera) { s.max_waiting++; } - } + s.max_waiting++; + if (cam.has_qcamera) { s.max_waiting++; } } uint64_t msg_count = 0, bytes_count = 0; diff --git a/selfdrive/loggerd/loggerd.h b/selfdrive/loggerd/loggerd.h index 2c4990086a..6eafbe08d0 100644 --- a/selfdrive/loggerd/loggerd.h +++ b/selfdrive/loggerd/loggerd.h @@ -50,7 +50,6 @@ struct LogCameraInfo { int bitrate; bool is_h265; bool has_qcamera; - bool enable; bool record; }; @@ -63,7 +62,6 @@ const LogCameraInfo cameras_logged[] = { .bitrate = MAIN_BITRATE, .is_h265 = true, .has_qcamera = true, - .enable = true, .record = true, .frame_width = 1928, .frame_height = 1208, @@ -76,7 +74,6 @@ const LogCameraInfo cameras_logged[] = { .bitrate = DCAM_BITRATE, .is_h265 = true, .has_qcamera = false, - .enable = true, .record = Params().getBool("RecordFront"), .frame_width = 1928, .frame_height = 1208, @@ -89,7 +86,6 @@ const LogCameraInfo cameras_logged[] = { .bitrate = MAIN_BITRATE, .is_h265 = true, .has_qcamera = false, - .enable = true, .record = true, .frame_width = 1928, .frame_height = 1208, @@ -100,7 +96,6 @@ const LogCameraInfo qcam_info = { .fps = MAIN_FPS, .bitrate = 256000, .is_h265 = false, - .enable = true, .record = true, .frame_width = 526, .frame_height = 330, From 836e2a4d98b587b7ae083bb710190ed1dfa9dccf Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 7 Jul 2022 13:20:42 -0700 Subject: [PATCH 230/302] Chrysler: fix steer fault detection (#25068) --- selfdrive/car/chrysler/carstate.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index 71b7e34623..47b28f9e05 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -83,8 +83,7 @@ class CarState(CarStateBase): self.auto_high_beam = cp_cam.vl["DAS_6"]['AUTO_HIGH_BEAM_ON'] # Auto High Beam isn't Located in this message on chrysler or jeep currently located in 729 message ret.steerFaultTemporary = cp.vl["EPS_3"]["DASM_FAULT"] == 1 else: - steer_state = cp.vl["EPS_2"]["LKAS_STATE"] - ret.steerFaultPermanent = steer_state == 4 or (steer_state == 0 and ret.vEgo > self.CP.minSteerSpeed) + ret.steerFaultPermanent = cp.vl["EPS_2"]["LKAS_STATE"] == 4 # blindspot sensors if self.CP.enableBsm: From bd2ea158977f5c26658bed8ac683b72c2c592d06 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 7 Jul 2022 14:19:30 -0700 Subject: [PATCH 231/302] Add Chinese (traditional) translations (#25064) * Add Chinese translations * wrap these * add to languages.json * fix tests * use tmp dir for tests (doesn't change translation files in git repo) * defaultdict not used * update main_zh.ts (test outdated QM file) * test outdated QM file (prev commit tests missing) * update qm file * add sidebar translations * no need for function --- selfdrive/ui/qt/sidebar.h | 14 +- selfdrive/ui/tests/test_translations.py | 46 +- selfdrive/ui/translations/languages.json | 3 +- selfdrive/ui/translations/main_zh.qm | Bin 0 -> 17617 bytes selfdrive/ui/translations/main_zh.ts | 1212 ++++++++++++++++++++++ selfdrive/ui/update_translations.py | 4 +- 6 files changed, 1254 insertions(+), 25 deletions(-) create mode 100644 selfdrive/ui/translations/main_zh.qm create mode 100644 selfdrive/ui/translations/main_zh.ts diff --git a/selfdrive/ui/qt/sidebar.h b/selfdrive/ui/qt/sidebar.h index 98ae6564d6..4c6d8f47e5 100644 --- a/selfdrive/ui/qt/sidebar.h +++ b/selfdrive/ui/qt/sidebar.h @@ -34,13 +34,13 @@ protected: QPixmap home_img, settings_img; const QMap network_type = { - {cereal::DeviceState::NetworkType::NONE, "--"}, - {cereal::DeviceState::NetworkType::WIFI, "Wi-Fi"}, - {cereal::DeviceState::NetworkType::ETHERNET, "ETH"}, - {cereal::DeviceState::NetworkType::CELL2_G, "2G"}, - {cereal::DeviceState::NetworkType::CELL3_G, "3G"}, - {cereal::DeviceState::NetworkType::CELL4_G, "LTE"}, - {cereal::DeviceState::NetworkType::CELL5_G, "5G"} + {cereal::DeviceState::NetworkType::NONE, tr("--")}, + {cereal::DeviceState::NetworkType::WIFI, tr("Wi-Fi")}, + {cereal::DeviceState::NetworkType::ETHERNET, tr("ETH")}, + {cereal::DeviceState::NetworkType::CELL2_G, tr("2G")}, + {cereal::DeviceState::NetworkType::CELL3_G, tr("3G")}, + {cereal::DeviceState::NetworkType::CELL4_G, tr("LTE")}, + {cereal::DeviceState::NetworkType::CELL5_G, tr("5G")} }; const QRect settings_btn = QRect(50, 35, 200, 117); diff --git a/selfdrive/ui/tests/test_translations.py b/selfdrive/ui/tests/test_translations.py index ccea748e24..2dedf3d785 100755 --- a/selfdrive/ui/tests/test_translations.py +++ b/selfdrive/ui/tests/test_translations.py @@ -1,10 +1,13 @@ #!/usr/bin/env python3 import json import os +import shutil import unittest from selfdrive.ui.update_translations import TRANSLATIONS_DIR, LANGUAGES_FILE, update_translations +TMP_TRANSLATIONS_DIR = os.path.join(TRANSLATIONS_DIR, "tmp") + class TestTranslations(unittest.TestCase): @classmethod @@ -12,11 +15,25 @@ class TestTranslations(unittest.TestCase): with open(LANGUAGES_FILE, "r") as f: cls.translation_files = json.load(f) + # Set up temp directory + shutil.copytree(TRANSLATIONS_DIR, TMP_TRANSLATIONS_DIR, dirs_exist_ok=True) + + @classmethod + def tearDownClass(cls): + shutil.rmtree(TMP_TRANSLATIONS_DIR, ignore_errors=True) + + @staticmethod + def _read_translation_file(path, file, file_ext): + tr_file = os.path.join(path, f"{file}.{file_ext}") + with open(tr_file, "rb") as f: + # fix relative path depth + return f.read().replace(b"filename=\"../../", b"filename=\"../") + def test_missing_translation_files(self): for name, file in self.translation_files.items(): with self.subTest(name=name, file=file): if not len(file): - self.skipTest(f"{name} translation has no file") + self.skipTest(f"{name} translation has no defined file") self.assertTrue(os.path.exists(os.path.join(TRANSLATIONS_DIR, f"{file}.ts")), f"{name} has no XML translation file, run selfdrive/ui/update_translations.py") @@ -24,26 +41,25 @@ class TestTranslations(unittest.TestCase): f"{name} has no compiled QM translation file, run selfdrive/ui/update_translations.py --release") def test_translations_updated(self): - suffix = "_test" - update_translations(suffix=suffix) + update_translations(release=True, translations_dir=TMP_TRANSLATIONS_DIR) for name, file in self.translation_files.items(): with self.subTest(name=name, file=file): - cur_tr_file = os.path.join(TRANSLATIONS_DIR, f"{file}.ts") - new_tr_file = os.path.join(TRANSLATIONS_DIR, f"{file}{suffix}.ts") - if not len(file): - self.skipTest(f"{name} translation has no file") - elif not os.path.exists(cur_tr_file): - self.skipTest(f"{name} missing translation file") # caught by test_missing_translation_files + self.skipTest(f"{name} translation has no defined file") + + for file_ext in ["ts", "qm"]: + with self.subTest(file_ext=file_ext): + + # caught by test_missing_translation_files + if not os.path.exists(os.path.join(TRANSLATIONS_DIR, f"{file}.{file_ext}")): + self.skipTest(f"{name} missing translation file") - with open(cur_tr_file, "r") as f: - cur_translations = f.read() - with open(new_tr_file, "r") as f: - new_translations = f.read() + cur_translations = self._read_translation_file(TRANSLATIONS_DIR, file, file_ext) + new_translations = self._read_translation_file(TMP_TRANSLATIONS_DIR, file, file_ext) - self.assertEqual(cur_translations, new_translations, - f"{name} translation file out of date. Run selfdrive/ui/update_translations.py to update the translation files") + self.assertEqual(cur_translations, new_translations, + f"{file} ({name}) {file_ext.upper()} translation file out of date. Run selfdrive/ui/update_translations.py --release to update the translation files") if __name__ == "__main__": diff --git a/selfdrive/ui/translations/languages.json b/selfdrive/ui/translations/languages.json index f2f9400d64..e62de24a1e 100644 --- a/selfdrive/ui/translations/languages.json +++ b/selfdrive/ui/translations/languages.json @@ -1,3 +1,4 @@ { - "English": "" + "English": "", + "中文(简体)": "main_zh" } diff --git a/selfdrive/ui/translations/main_zh.qm b/selfdrive/ui/translations/main_zh.qm new file mode 100644 index 0000000000000000000000000000000000000000..627f6afc204dba0b2c2a87f13cad266e9edcbd4f GIT binary patch literal 17617 zcmcIrdwf*&mH#D~S0E(QdWwQd+CxtF>-d7i}%ge$VgD+_^Kkf$bk# zKK4##&N;vHJHPWg@4NH|{z=b$aR0uO)21BV@X(LW)H7y!kg?+PjLj@&tR#r%HF);n zxg5`X@$6yDfZxk+Va!;|Sk-Pkm*DwJJi7tYr97v)88bh_nC$(o+s#MpHUS<^e;V{G1R)?Dgkta5GWvpDD3ONw86@G{W5yX4A081em6CDVsKgZ=!rB-H_W3rkDBSpj~l z9xZwNiFU}(Qu42l1HSsQl4COmpkvRKoPx|)QM%-l)FDW9mZ9<8?=Uw0%Z3ey{{{Sf zXb837>&j(@{?~72?8?K2y9^&Pwjgad(DD@Y>{{hnu~2zVdEIdT!=K>Xo;Q5;O+WZ6 zF?{RPKE|eQHhj1DVaU^Oc+!S*v3+cK{;kva{-u zGnNnC3i;hlze3ag#Jf{>X&nssu&!rC=?;nO9Sifj|_|EN&O_*-{_D^49Y|azL zAD@Sui?o4nWT)@E_*svmmD# z%zS9_9oUy-{&w^Ytlw(>!1-0kZKwHvUcCZxdei*zdyq@Xx6Gd|d7H5-&RZI09m75N zg5{PH@Lln|MSA~J=>2_`-Km54eaP~aZ-U-gbG z885@eJZiPihW##zgD4Q03fy8&{nE8Ci$0KESxJMjmc&ox(+ z{j3dgx@5X-!ZTR+y1lk(kK_C4Cv4R>^+P{`w&e{t=NtcQyXA(pj4l4iwxS;Uzy5C9 z%6*_W#chj-#LsHmy?^Nf{(9TvdvVYHL9#vjAmlaY9ox@O<2m~_+vyYF%W!A8>CiP; z&rx1`<*&fUjpa9<--&zrZ26-L@%vS$%D>--=i>VEW7A=q%}EPF?nvL06I}@2O^z@dfx@wudT@+kWG8u{niP=l+ z{lf=`YHLcvrVf5_1bF=%kT64{|rG&PXAg*ie4k%$vHIl3(53CkJXTfI3w zs3H_Q6wMn8SYJ`gmPx*FC@Qskf)ZEgao%4HoEfpXHV$vb!Ovjx)CDfffX)$8(NHvz z^n}C0jCsW1C?fMW99e(-z$V`z*RO(}-kaUKf*$dlx9#@xjxDJwkd;}CNi2&053w-* zO3p1-muXlnr-Vo(8Q!Hq!N-K$E0X1 z6qb`Ux=hVw!iFR1!J(&Dn|)^Ycx89&G5(y-1otlfX+h?jg&LOT2;eC$_@#8nCkdg1 z5R*f=0)A}&$Bzj!=5xkoETGQ|vuhJ*yC*7zxl|`?II=O?eQ@X2j>NwAQ;VW|+?S6` zRkwV#JuV6T*mfe7`OxQyV&gIv>cjrzK;Sc(Esa5T?@8$~cdheC9$8^bvT<%wFG_Pu zv}an!i9DLKFF-RPB?X@+9P%odg(Gb8iW~dS*D9*b$t@7^Dk>ZwR)k7Qobx6N<$eMJP|4G z(M2G#nTdH>hCdc4ylg+{26-_!XH1JU-F|9~TWBYL66-!5$<-kr4cU=Hf== zRFwQVZdHPt5N@fx5=>2oPDGA|k}`QkLE0FDdz4^FghDujoiV*LgwFGL-#|$v+ABq7dilni8PS>>gq3^ereM~Dx}pZ1yf-Uw$rZ* zZ6Q|aeybRWwCD;q!ct<65Rg1cSWJAP;4qBCPI4cazyamFfi4dQasG~0 zmA1)+v-WUjJNl&h%EB+JkcKfYO0ig$gYwIL+}Dq$<_u}!!criq%ilIV>FnGZuFu|| zuBx?fc_+F)gd7)=%YvQTj(cXs-;3yP??jPgd_(p(x>I^I9g}@U1Mia_jM&!iSTp`! zwsR|KhQ|FJQ5~xgmu^jkAaQPkGuH~&4OfC+F1W6{8^Y(}`D59ez5d@h$NUeTtz?(omnOpv~vBi9zfbr~3(A~A^+L2uN zZxehy9?Jcscw!o@R@M@YrIOm_FbONd98!Bd8!Y95o18K%&F z&*iR<@A$s!mB7vYb%?az8aT20gMp)z(665C_}vDXS;Zwgw+?-Ezmd$*ZO^+B;deTA zVMjeIiGMMcV09>D)-oSVRTTdud`jYk=`Nr#5v;LzC?X-~_9lGs5P}66cE}Y9M#(ru<-R(h zCz*^T>S}9YkD{Pj!|`f7q0xe?2tO1o?S6t;DX!U{^QjX=1S4`pvW8_Jmz)6mH5z>! zp|3sbSffjT3Jw<`U>$xbIJNNLNGtQtjaz~IgR2;NIaSsD*KOBDRt&uyZ&pQnxjWv^ z&AjMIhk^?4^-_{Yp7|6w^FcQJQhKm}gNacY)|oTm&nb@%6Q+*l;nSLA){-r^kf^K$ zHJ3tQ)I_Krp{*ViqD*03EY5W*2sapm4khrf58uR@U)^#=R~%va1qoTiI`K}Bn64rj zDczs0$EP7LelfPTv?_?w~X%BDs^n-ypmaZy$XZpf?KnL68-+1=cy7D5)^!YIVa{acDN4CC)4>*qy< zo7hY?5B~``U-~W#8$#ca?TE7=3Jy_L&A$!c_d3AML%#VZ&_(EZ z!39|`vQk8I5u2N%*;VCT5v&ufLr3@h5x@PNwhrspat{7qc#A#R@u@H+@~QJd=`ji| zg)2vF-d^7+*N2Y7;;w;@HWvN=uD`|viCo0mGeKIs{giVqRd2*4YaHu3DWP;6Z9lc{ zo>bLsW$T7T)^k1ipYA)xxP{W0mLne%1}iDZ8mpCX=k zFcht(Shh}>wV!peIb@T}v(Yi!h#*I)>;u!)BS)pB zwc*g;LAoIv^7RVSJ$}DHRa7MypUz!f!sm%{)7{~OtMemYRsQ6$@87vhy)5@a2E7!M z=lMX|7-yc`n*a|gNmxax#Dx%eg?c40BY0vl?TSll<*>3zvIDkuPl&SZb~%=cal0{P zjVW8C6D#Nwg%rE5^-WOF^g>MRW9FyIvRK9ELB`^rN zWFinH0EtKuFZ>sx)j}DM!G?7`bG>xCv47Z^%S0+sVUWVe)SyjLyqEh}ogMH1EZ!e` za%8f~Rb{&q8H}*J(eCa<#iDMERV~B6zO9UGn2K2Llp=Bx+d-jLDZcBhXh}TQRpn|L zIINU}!Fk>NMT+l~JgbKt-o1m6XOnHgx>O^@hr$p>bn~-@82C z3}e->@}R6cT89HekFD?2zQ=(`pN^p+0m-GV5MrQVibZ}c&6$` z*2d%&o-bD0<_1QwH@x6%MBW zK}l4$GA*9ndvfSyP1R;P=S~QCkQn-FgiIF|20Dqj-V;RmoaeV1x|j6&x~hma1p>G* z+Qb+cZnp5ENFb9QYtSv9|8(HDgs$$<=IT!*r3lu}Bt07Fr90npy_ChEjrdAQK2Bl3 z-}~8MX~*{NC*8ZKC9C{K)qoA&)#X%x&}>r5tPrOau(MDwD8*^JC=w@l9f=xe@9OHHlkLOE4QuZ3Us6%TKgV!o);vWb#)j$&8YkVfMQnK0-z|06yMoLkAr+X$iY!{LXsB6c;l`-r42?ph z2O*eF=0q({2$o9CBQ_|~1iGBaYX0eV_m&PioNe;z%^H39?x2unw&in^ zwC|mqtWbF4Wq6dk<7kDC0@mpoqH9(FHkT)DJ3D&TT?^gWJRA_K#k#C-c6=$d$UAZC zdplaaTfD~)ys$r{5zKO>5vehdG!B5c8ex2<$cF-Rl$-#{GqJer%M^q;2F@8>i9~PV z9YasdU7Kew5#sXcBSpLg>?5oRN~%b#ToeLby{1;mIpqA3clD^_M{8ev(UxKGZB{(^o6gEh3s42 z43urTVyw6gq9w}sCr!X@p{y)VUS&Kp%Sme#%78Y(%cN3DWw$V`5?Iwm6RlYYfWX4K z^np8FuaM#tP>iAG6GBY}LrjiI8(z~W(5g`>Bv%_Hw$EG~p(^u1E&R^n_stjfgd$4% zsmTSXD=fviN{!mJ0p_q;J;UPaY7(c}g$}9Lqcj!_2=<$D5c8XKAQosL7U)4N(n2iK zfgl^Bu42w)L8F)2cg4^LDwwg+>2&aBK_15@@$BmBHb1U{l{C7WM^nlRQw&WG2QOLX z6Jkx6z;opYHMR2`FAvCY@KsHH*wEb4GQlP)3yIn4g2r~cxXeC!IscT+ zxtg=dh3-wmXaN|avosZAgS)Y1SY%6U`4}+ld zO3vdNdL)$7$V_U6Oh>b2gRX{9=oOqMDL0j2Z9>JXK91ypSI%`-RPlT-in%0^<29fe zrR2UwTkFx9=lLe~3k1i9N13avIu^&JDk~qg7*bgKh*WVPYMFIhuJr zwBUFJDUb?Nzn@M5aSojY3WzB_^IIbjuJRd$x+t~%Qp^(1ys4{kcvX2A>h|Wx6P%H%25MnDL(_`(r ze2QH(0-JXbqLsIgwTxe#zgmwcftIw;i=A9}t#2u@=J0>4G5L0gJG%c|xE6(YVl}U^ zgzq`Tl_DcJs_h0F_P5i0cAA|dq&6FlY<+L-pWx{yj-@^XO*K;YsMVgmTWFiBiNBE(MW(4iG}5Ui3SC*n%KCq(J6Qm zy#&cwK(htt=sgrrfL5op4Lf3**AC2?$!r}!OY}dTM`#XPr8&;!gJD3U3lfFZjq%G=nor)Eo7z_K zFey(n*w+d$Etv^yo%L?%un+w}-*N0ob?;dF7TSsr@0q;e1IN(1H2MN)Gt%tmy2GN? z8{E;Fn*-IjjgUPYMuw!8c8PV_EA{gMvuYe94khjh1e9U>H1cFV9!}q*6#_RB(V6eW zh2`zA>`w{I67o~DWy(ysP{bA-SkIgf?wNXbWpIlskE?PMz>cV3hbZwH3yoU}?UG-a zB^*uaT8!zb-TB*XVtJr8*MX<08EWxswmt)k&9S8%%@|jhw6|tc%Hd~+*FQcooln}L+=WjYEwyFo_!yM zX8fv~N#=Y4j8tPZjY-6ko_478vahG8hpkU&aJ`GNJql$}lR3M4`|wXeb^$d`a`GIp z@IJhdllVv}8gq~^6fG^Cqo6Ue!a0}d>~Reo6|Hh{|EIUx$QH}bM3xMP-Qyj9dgyBdTeMAXX#*5d1C`m`roku62Pyk500O+CWA4)bjYrIN=UrrBjdLKO`BMcP_<|-SD0C2sK^BBwzzkRR)?T7aXuB>!V4BWcos)7A5*CU^`d%~uCFA;#&?ZK&g|+*PjvO*Qa8Hoq}B5m_E5ZsS6uYZd$IV! z=&^EQn@aGgq+z&Rx^eh)&U|dTH>_=jbZ7YIb$3jvpd~;xGrj3?Qei$m9*UrBgqM0W zkec~$PdJD{@nlbA4ABaiS6x&=I2Vg=1V%)wtC`h`Wv<+y)l_(TjR3Tl+Y_mc@z&R9 zFaNoa!j1f?yaFUvbKoaw~&lqn3K-qE`Cy*!*lA$qJ-L zQ;Vc?si{)4=Jx!8_$DE%cV0*+eIuR$_&u1+!!h{cDZIA9yEpJ(Tq*e#>6N5d_9XEJ z7lJYB;nXOv?0AyY>d6#9vvb1KX{TU>v>G7n1S{2~+EnZ$#?szc#vCIK0JWOK>-xhqC&ch3^b!cXpdhy2MJ)6O^c`}J(1 zMnucI$ZANuiG-SOjG9{tcS`d;>v>}2d6d`%!;hJFTvV}+p{Y~!vb=%sxyRGltJn1^ zl?=+2kWDh>$1G@=q5(=Y^i^%89_clv{;erq?M)Bv|9JT6b!p$BO%IVg+`F7N4hPbM zv@oepHk5TtCJe~P4jWRh86%G6nBoB&HqGCT%pA*18WHy+FQhxo0q6u3ON+`L@l7r? zh}fDS@ZJ*6wy*RK&`b#S#`6DH=YrgC_HkC)8^cVc3p$-VoHFaRlYeToWZLrsOxP;ZWdALx+1B zr5sCci5GBqW=$drAQh*)Dnmf~%8Q%KW40ZVpqFSs9%`@9oSK)4qGZ~+%6O}m5FZtwIYEw| ZKPoWEh4C}~ZXVfh^r2{cIZ?p!{{qG<2A}`{ literal 0 HcmV?d00001 diff --git a/selfdrive/ui/translations/main_zh.ts b/selfdrive/ui/translations/main_zh.ts new file mode 100644 index 0000000000..7bcee2c23a --- /dev/null +++ b/selfdrive/ui/translations/main_zh.ts @@ -0,0 +1,1212 @@ + + + + + AbstractAlert + + + Close + + + + + Snooze Update + 暂停更新 + + + + Reboot and Update + 重启和更新 + + + + AdvancedNetworking + + + Back + 后退 + + + + Enable Tethering + 启用网络共享 + + + + Tethering Password + 网络共享密码 + + + + + EDIT + 编辑 + + + + Enter new tethering password + 输入新的网络共享密码 + + + + IP Address + IP地址 + + + + Enable Roaming + 启用漫游 + + + + APN Setting + APN 设置 + + + + Enter APN + 输入 APN + + + + leave blank for automatic configuration + 为自动配置留空 + + + + ConfirmationDialog + + + + Ok + 好的 + + + + Cancel + 取消 + + + + DeclinePage + + + You must accept the Terms and Conditions in order to use openpilot. + 您必须接受条款和条件才能使用 openpilot。 + + + + Back + 后退 + + + + Decline, uninstall %1 + 拒绝,卸载 %1 + + + + DevicePanel + + + Dongle ID + 加密狗 ID + + + + N/A + 不适用 + + + + Serial + 串行 + + + + Driver Camera + 司机摄像头 + + + + PREVIEW + 预习 + + + + Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off) + 预览面向驾驶员的摄像头,以帮助优化设备安装位置以获得最佳驾驶员监控体验。 (车辆必须关闭) + + + + Reset Calibration + 重置校准 + + + + RESET + 重置 + + + + Are you sure you want to reset calibration? + 您确定要重置校准吗? + + + + Review Training Guide + 查看培训指南 + + + + REVIEW + 审查 + + + + Review the rules, features, and limitations of openpilot + 查看 openpilot 的规则、功能和限制 + + + + Are you sure you want to review the training guide? + 您确定要查看培训指南吗? + + + + Regulatory + 监管 + + + + VIEW + 看法 + + + Change Language + 改变语言 + + + CHANGE + 改变 + + + Select a language + 选择语言 + + + + Reboot + 重启 + + + + Power Off + 关机 + + + + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. + openpilot 要求设备安装在左或右 4° 以内,上 5° 或下 8° 以内。 openpilot 会持续校准,很少需要重置。 + + + + Your device is pointed %1° %2 and %3° %4. + 您的设备指向 %1° %2 和 %3° %4。 + + + + down + + + + + up + 向上 + + + + left + 剩下 + + + + right + 向右 + + + + Are you sure you want to reboot? + 您确定要重新启动吗? + + + + Disengage to Reboot + 脱离以重新启动 + + + + Are you sure you want to power off? + 您确定要关闭电源吗? + + + + Disengage to Power Off + 脱离以关闭电源 + + + + DriveStats + + + Drives + 驱动器 + + + + Hours + 小时 + + + + ALL TIME + 整天 + + + + PAST WEEK + 上周 + + + + KM + 千米 + + + + Miles + 迈尔斯 + + + + DriverViewScene + + + camera starting + 相机启动 + + + + InputDialog + + + Cancel + 取消 + + + + Need at least + 需要至少 + + + + characters! + 字符! + + + + Installer + + + Installing... + 安装... + + + + Receiving objects: + 接收物体: + + + + Resolving deltas: + 解决增量: + + + + Updating files: + 更新文件: + + + + MapPanel + + + Current Destination + 当前目的地 + + + + CLEAR + CLEAR + + + + Recent Destinations + 近期目的地 + + + + Try the Navigation Beta + 试用导航测试版 + + + + Get turn-by-turn directions displayed and more with a comma +prime subscription. Sign up now: https://connect.comma.ai + 使用逗号获取显示的详细路线和更多信息 +主要订阅。 立即注册:https://connect.comma.ai + + + + No home +location set + 没有家 +位置集 + + + + No work +location set + 没有工作 +位置集 + + + + no recent destinations + 没有最近的目的地 + + + + MultiOptionDialog + + Select + 选择 + + + Cancel + 取消 + + + + Networking + + + Advanced + 先进的 + + + + Enter password + 先进的 + + + + + for " + 为了 " + + + + Wrong password + Wrong password + + + + NvgWindow + + + km/h + 公里/小时 + + + + mph + 英里/小时 + + + + + MAX + 最大限度 + + + + + SPEED + 速度 + + + + + LIMIT + 限制 + + + + OffroadHome + + + UPDATE + 更新 + + + + ALERTS + 个警报 + + + + ALERT + 个警报 + + + + PairingPopup + + + Pair your device to your comma account + 将您的设备与您的逗号账户配对 + + + + + <ol type='1' style='margin-left: 15px;'> + <li style='margin-bottom: 50px;'>Go to https://connect.comma.ai on your phone</li> + <li style='margin-bottom: 50px;'>Click "add new device" and scan the QR code on the right</li> + <li style='margin-bottom: 50px;'>Bookmark connect.comma.ai to your home screen to use it like an app</li> + </ol> + + + <ol type='1' style='margin-left: 15px;'> + <li style='margin-bottom: 50px;'>在手机上访问 https://connect.comma.ai</li> + <li style='margin-bottom: 50px;'>点击“添加新设备”,扫描右侧二维码</li> + <li style='margin-bottom: 50px;'>将 connect.comma.ai 收藏到您的主屏幕,以便像应用程序一样使用它</li> + </ol> + + + + + PrimeAdWidget + + + Upgrade Now + 现在升级 + + + + Become a comma prime member at connect.comma.ai + 成为 connect.comma.ai 的逗号主要会员 + + + + PRIME FEATURES: + 主要特点: + + + + Remote access + 远程访问 + + + + 1 year of storage + 1年存储 + + + + Developer perks + 开发者福利 + + + + PrimeUserWidget + + + ✓ SUBSCRIBED + ✓ 订阅 + + + + comma prime + 逗号素数 + + + + CONNECT.COMMA.AI + CONNECT.COMMA.AI + + + + COMMA POINTS + 逗号分 + + + + QObject + + + Reboot + 重启 + + + + Exit + 出口 + + + + dashcam + 行车记录器 + + + + openpilot + 开放式飞行员 + + + + %1 minute%2 ago + %1 分钟%2 前 + + + + %1 hour%2 ago + %1 小时%2 前 + + + + %1 day%2 ago + %1 天%2 前 + + + + Reset + + + Reset failed. Reboot to try again. + 重置失败。 重新启动以重试。 + + + + Are you sure you want to reset your device? + 您确定要重置您的设备吗? + + + + Resetting device... + 正在重置设备... + + + + System Reset + 系统重置 + + + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + 触发系统重置。 按确认删除所有内容和设置。 按取消恢复启动。 + + + + Cancel + 取消 + + + + Reboot + 重启 + + + + Confirm + 确认 + + + + Unable to mount data partition. Press confirm to reset your device. + 无法挂载数据分区。 按确认重置您的设备。 + + + + RichTextDialog + + + Ok + 好的 + + + + SettingsWindow + + + × + × + + + + Device + 设备 + + + + + Network + 网络 + + + + Toggles + 切换 + + + + Software + 软件 + + + + Navigation + 导航 + + + + Setup + + + WARNING: Low Voltage + 警告:低电压 + + + + Power your device in a car with a harness or proceed at your own risk. + 使用安全带在汽车中为您的设备供电或自行承担风险。 + + + + Power off + 关机 + + + + + + Continue + 继续 + + + + Getting Started + 入门 + + + + Before we get on the road, let’s finish installation and cover some details. + 在我们上路之前,让我们完成安装并介绍一些细节。 + + + + Connect to Wi-Fi + 连接到无线网络 + + + + + Back + 后退 + + + + Continue without Wi-Fi + 在没有 Wi-Fi 的情况下继续 + + + + Waiting for internet + 等待上网 + + + + Choose Software to Install + 选择要安装的软件 + + + + Dashcam + 行车记录器 + + + + Custom Software + 定制的软件 + + + + Enter URL + 输入网址 + + + + for Custom Software + 定制软件 + + + + Downloading... + 正在下载... + + + + Download Failed + 下载失败 + + + + Ensure the entered URL is valid, and the device’s internet connection is good. + 确保输入的 URL 有效,并且设备的互联网连接良好。 + + + + Reboot device + 重启设备 + + + + Start over + 重来 + + + + SetupWidget + + + Finish Setup + 完成设置 + + + + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. + 将您的设备与 comma connect (connect.comma.ai) 配对并领取您的 comma prime 优惠。 + + + + Pair device + 配对设备 + + + + Sidebar + + + + CONNECT + 连接 + + + + OFFLINE + 离线 + + + + + ONLINE + 在线的 + + + + ERROR + 错误 + + + + + + TEMP + 温度 + + + + HIGH + 高的 + + + + GOOD + 好的 + + + + OK + 好的 + + + + VEHICLE + 车辆 + + + + NO + + + + + PANDA + 熊猫 + + + + GPS + GPS + + + + SEARCH + 搜索 + + + + -- + -- + + + + Wi-Fi + Wi-Fi + + + + ETH + 以太網 + + + + 2G + 2G + + + + 3G + 3G + + + + LTE + LTE + + + + 5G + 5G + + + + SoftwarePanel + + + Git Branch + Git 分支 + + + + Git Commit + Git 提交 + + + + OS Version + 操作系统版本 + + + + Version + 版本 + + + + Last Update Check + 最后更新检查 + + + + The last time openpilot successfully checked for an update. The updater only runs while the car is off. + 上次 openpilot 成功检查更新的时间。 更新程序仅在汽车关闭时运行。 + + + + Check for Update + 检查更新 + + + + CHECKING + 正在检查 + + + + Uninstall + 卸载 + + + + UNINSTALL + 卸载 + + + + Are you sure you want to uninstall? + 您确定要卸载吗? + + + + failed to fetch update + 未能获取更新 + + + + + CHECK + 查看 + + + + SshControl + + + SSH Keys + SSH 密钥 + + + + Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. + 警告:这将授予对 GitHub 设置中所有公钥的 SSH 访问权限。 切勿输入您自己以外的 GitHub 用户名。 逗号员工永远不会要求您添加他们的 GitHub 用户名。 + + + + + ADD + 添加 + + + + Enter your GitHub username + 输入你的 GitHub 用户名 + + + + LOADING + 正在加载 + + + + REMOVE + 消除 + + + + Username '%1' has no keys on GitHub + 用户名“%1”在 GitHub 上没有密钥 + + + + Request timed out + 请求超时 + + + + Username '%1' doesn't exist on GitHub + GitHub 上不存在用户名“%1” + + + + SshToggle + + + Enable SSH + 启用 SSH + + + + TermsPage + + + Terms & Conditions + 条款和条件 + + + + Decline + 衰退 + + + + Scroll to accept + 滚动接受 + + + + Agree + 同意 + + + + TogglesPanel + + + Enable openpilot + 启用 openpilot + + + + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. + 使用 openpilot 系统进行自适应巡航控制和车道保持驾驶员辅助。 任何时候都需要您注意使用此功能。 更改此设置在汽车断电时生效。 + + + + Enable Lane Departure Warnings + 启用车道偏离警告 + + + + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). + 当您的车辆在以超过 31 英里/小时(50 公里/小时)的速度行驶时在检测到的车道线上漂移而没有激活转向信号时,接收提醒以返回车道。 + + + + Enable Right-Hand Drive + 启用右手驱动 + + + + Allow openpilot to obey left-hand traffic conventions and perform driver monitoring on right driver seat. + 允许 openpilot 遵守左侧交通惯例并在右侧驾驶座上执行驾驶员监控。 + + + + Use Metric System + 使用公制 + + + + Display speed in km/h instead of mph. + 以公里/小时而不是英里/小时显示速度。 + + + + Record and Upload Driver Camera + 记录和上传司机摄像头 + + + + Upload data from the driver facing camera and help improve the driver monitoring algorithm. + 从面向驾驶员的摄像头上传数据,帮助改进驾驶员监控算法。 + + + + Disengage On Accelerator Pedal + 松开加速踏板 + + + + When enabled, pressing the accelerator pedal will disengage openpilot. + 启用后,踩下油门踏板将解除 openpilot。 + + + + Show ETA in 24h format + 以 24 小时格式显示 ETA + + + + Use 24h format instead of am/pm + 使用 24 小时制代替上午/下午 + + + + openpilot Longitudinal Control + openpilot 纵向控制 + + + + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! + openpilot 将禁用汽车的雷达并接管油门和刹车的控制。 警告:这会禁用 AEB! + + + + Updater + + + Update Required + 需要更新 + + + + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. + 需要操作系统更新。 将您的设备连接到 Wi-Fi,以获得最快的更新体验。 下载大小约为 1GB。 + + + + Connect to Wi-Fi + 连接到无线网络 + + + + Install + 安装 + + + + Back + 后退 + + + + Loading... + 正在加载... + + + + Reboot + 重启 + + + + Update failed + 更新失败 + + + + WifiUI + + + + Scanning for networks... + 正在扫描网络... + + + + CONNECTING... + 正在连接... + + + + FORGET + 忘记 + + + + Forget Wi-Fi Network " + 忘记 Wi-Fi 网络" + + + diff --git a/selfdrive/ui/update_translations.py b/selfdrive/ui/update_translations.py index 5d57fa39d2..263eb5e670 100755 --- a/selfdrive/ui/update_translations.py +++ b/selfdrive/ui/update_translations.py @@ -10,7 +10,7 @@ TRANSLATIONS_DIR = os.path.join(UI_DIR, "translations") LANGUAGES_FILE = os.path.join(TRANSLATIONS_DIR, "languages.json") -def update_translations(release=False, suffix=""): +def update_translations(release=False, translations_dir=TRANSLATIONS_DIR): with open(LANGUAGES_FILE, "r") as f: translation_files = json.load(f) @@ -19,7 +19,7 @@ def update_translations(release=False, suffix=""): print(f"{name} has no translation file, skipping...") continue - tr_file = os.path.join(TRANSLATIONS_DIR, f"{file}{suffix}.ts") + tr_file = os.path.join(translations_dir, f"{file}.ts") ret = os.system(f"lupdate -recursive {UI_DIR} -ts {tr_file}") assert ret == 0 From b035b538ec5dc4ae837fe26ab900a34828525647 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 7 Jul 2022 14:54:14 -0700 Subject: [PATCH 232/302] chill ram tune (#25071) --- selfdrive/car/chrysler/interface.py | 5 ++++- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 920000b271..697fb9b83a 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -51,7 +51,10 @@ class CarInterface(CarInterfaceBase): ret.mass = 2493. + STD_CARGO_KG ret.maxLateralAccel = 2.4 ret.minSteerSpeed = 14.5 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[0.], [0.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.1], [0.02]] + ret.lateralTuning.pid.kf = 0.00003 else: raise ValueError(f"Unsupported car: {candidate}") diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 0521fd8295..4908b86182 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -cf46781e405a01c96307d30d1266d46e0fa92255 \ No newline at end of file +bd2ea158977f5c26658bed8ac683b72c2c592d06 \ No newline at end of file From dc3d94d662654a6bb2bf40560c2a17ed2303fa80 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 8 Jul 2022 06:01:02 +0800 Subject: [PATCH 233/302] UI: fix unable to scroll on 'Regulatory' page (#25014) * fix unable to scroll on 'Regulatory' page deleteLater after hide * remove alert * override exec * set MousePressEventDelay to 0 * set to 0.01 * cleanup * check event->pos() --- selfdrive/ui/qt/widgets/controls.cc | 4 +++- selfdrive/ui/qt/widgets/controls.h | 6 +++++- selfdrive/ui/qt/widgets/scrollview.cc | 2 +- 3 files changed, 9 insertions(+), 3 deletions(-) diff --git a/selfdrive/ui/qt/widgets/controls.cc b/selfdrive/ui/qt/widgets/controls.cc index 89c95843fb..a86c05a3c4 100644 --- a/selfdrive/ui/qt/widgets/controls.cc +++ b/selfdrive/ui/qt/widgets/controls.cc @@ -125,7 +125,9 @@ void ElidedLabel::paintEvent(QPaintEvent *event) { ClickableWidget::ClickableWidget(QWidget *parent) : QWidget(parent) { } void ClickableWidget::mouseReleaseEvent(QMouseEvent *event) { - emit clicked(); + if (rect().contains(event->pos())) { + emit clicked(); + } } // Fix stylesheets diff --git a/selfdrive/ui/qt/widgets/controls.h b/selfdrive/ui/qt/widgets/controls.h index b6684e28b2..aed99edae8 100644 --- a/selfdrive/ui/qt/widgets/controls.h +++ b/selfdrive/ui/qt/widgets/controls.h @@ -24,7 +24,11 @@ signals: protected: void paintEvent(QPaintEvent *event) override; void resizeEvent(QResizeEvent* event) override; - void mouseReleaseEvent(QMouseEvent *event) override { emit clicked(); } + void mouseReleaseEvent(QMouseEvent *event) override { + if (rect().contains(event->pos())) { + emit clicked(); + } + } QString lastText_, elidedText_; }; diff --git a/selfdrive/ui/qt/widgets/scrollview.cc b/selfdrive/ui/qt/widgets/scrollview.cc index 1aa05b4157..bd4309d8d0 100644 --- a/selfdrive/ui/qt/widgets/scrollview.cc +++ b/selfdrive/ui/qt/widgets/scrollview.cc @@ -37,7 +37,7 @@ ScrollView::ScrollView(QWidget *w, QWidget *parent) : QScrollArea(parent) { sp.setScrollMetric(QScrollerProperties::VerticalOvershootPolicy, QVariant::fromValue(QScrollerProperties::OvershootAlwaysOff)); sp.setScrollMetric(QScrollerProperties::HorizontalOvershootPolicy, QVariant::fromValue(QScrollerProperties::OvershootAlwaysOff)); - + sp.setScrollMetric(QScrollerProperties::MousePressEventDelay, 0.01); scroller->grabGesture(this->viewport(), QScroller::LeftMouseButtonGesture); scroller->setScrollerProperties(sp); } From ff3f6de149475ce995c21f8308da0bbc08922c54 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 7 Jul 2022 16:53:34 -0700 Subject: [PATCH 234/302] UI: fix reset calibration description --- selfdrive/ui/qt/widgets/controls.cc | 30 +++++++++++++++-------------- 1 file changed, 16 insertions(+), 14 deletions(-) diff --git a/selfdrive/ui/qt/widgets/controls.cc b/selfdrive/ui/qt/widgets/controls.cc index a86c05a3c4..3264fd3aac 100644 --- a/selfdrive/ui/qt/widgets/controls.cc +++ b/selfdrive/ui/qt/widgets/controls.cc @@ -45,21 +45,23 @@ AbstractControl::AbstractControl(const QString &title, const QString &desc, cons main_layout->addLayout(hlayout); // description - if (!desc.isEmpty()) { - description = new QLabel(desc); - description->setContentsMargins(40, 20, 40, 20); - description->setStyleSheet("font-size: 40px; color: grey"); - description->setWordWrap(true); - description->setVisible(false); - main_layout->addWidget(description); - - connect(title_label, &QPushButton::clicked, [=]() { - if (!description->isVisible()) { - emit showDescription(); - } + description = new QLabel(desc); + description->setContentsMargins(40, 20, 40, 20); + description->setStyleSheet("font-size: 40px; color: grey"); + description->setWordWrap(true); + description->setVisible(false); + main_layout->addWidget(description); + + connect(title_label, &QPushButton::clicked, [=]() { + if (!description->isVisible()) { + emit showDescription(); + } + + if (!description->text().isEmpty()) { description->setVisible(!description->isVisible()); - }); - } + } + }); + main_layout->addStretch(); } From a4c90765813e1cc3ab7afbe58cf23b392ec8181c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 7 Jul 2022 17:09:36 -0700 Subject: [PATCH 235/302] Hyundai: limit Kona torque (#25074) --- selfdrive/car/hyundai/values.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index f6efedb248..c55a0dc639 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -32,6 +32,12 @@ class CarControllerParams: CAR.IONIQ_EV_LTD, CAR.SANTA_FE_PHEV_2022, CAR.SONATA_LF, CAR.KIA_FORTE, CAR.KIA_NIRO_HEV, CAR.KIA_OPTIMA_H, CAR.KIA_SORENTO, CAR.KIA_STINGER): self.STEER_MAX = 255 + + # These cars have significantly more torque than most HKG. Limit to 70% of max. + elif CP.carFingerprint in (CAR.KONA, CAR.KONA_EV, CAR.KONA_HEV): + self.STEER_MAX = 270 + + # Default for most HKG else: self.STEER_MAX = 384 From bd432eb76bf4c2d99a0f66b3a1df0067adb81a1a Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 7 Jul 2022 17:27:59 -0700 Subject: [PATCH 236/302] move kona limit to car controller --- selfdrive/car/hyundai/carcontroller.py | 7 ++++++- selfdrive/car/hyundai/values.py | 4 ---- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index f3066bda03..73635375ad 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -52,7 +52,12 @@ class CarController: hud_control = CC.hudControl # Steering Torque - new_steer = int(round(actuators.steer * self.params.STEER_MAX)) + + # These cars have significantly more torque than most HKG. Limit to 70% of max. + steer = actuators.steer + if self.CP.carFingerprint in (CAR.KONA, CAR.KONA_EV, CAR.KONA_HEV): + steer = clip(steer, -0.7, 0.7) + new_steer = int(round(steer * self.params.STEER_MAX)) apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) self.steer_rate_limited = new_steer != apply_steer diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index c55a0dc639..4b3acf3f27 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -33,10 +33,6 @@ class CarControllerParams: CAR.KIA_OPTIMA_H, CAR.KIA_SORENTO, CAR.KIA_STINGER): self.STEER_MAX = 255 - # These cars have significantly more torque than most HKG. Limit to 70% of max. - elif CP.carFingerprint in (CAR.KONA, CAR.KONA_EV, CAR.KONA_HEV): - self.STEER_MAX = 270 - # Default for most HKG else: self.STEER_MAX = 384 From 1382e28aa0b32923a44efa28c5b25d9b02c41d68 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 7 Jul 2022 20:02:07 -0700 Subject: [PATCH 237/302] add pandas and tabulate packages (#25076) * add pandas and tabulate packages * remove that --- Pipfile | 4 +- Pipfile.lock | 1226 ++++++++++++++++++---------------- selfdrive/debug/can_table.py | 2 +- 3 files changed, 647 insertions(+), 585 deletions(-) diff --git a/Pipfile b/Pipfile index b8545b1a21..81669e4807 100644 --- a/Pipfile +++ b/Pipfile @@ -41,6 +41,8 @@ tenacity = "*" mpld3 = "*" carla = {version = "==0.9.13", markers="platform_system != 'Darwin'"} ft4222 = "*" +pandas = "*" +tabulate = "*" [packages] atomicwrites = "*" @@ -86,8 +88,6 @@ urllib3 = "*" utm = "*" websocket_client = "*" hatanaka = "==2.4" -PyQt5 = "==5.15.4" -PyQt5-sip = "==12.9.0" [requires] python_version = "3.8" diff --git a/Pipfile.lock b/Pipfile.lock index cc347a60f4..0612d0ff39 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "d2629168f477b3a14f68f26e3b63ea9797b20599c066b2aa23a027bcee2ca40a" + "sha256": "c92514c0e6968af008916446514f41b4e004aa7aa4a2951cc1e9e258ac072111" }, "pipfile-spec": 6, "requires": { @@ -79,75 +79,89 @@ }, "certifi": { "hashes": [ - "sha256:9c5705e395cd70084351dd8ad5c41e65655e08ce46f2ec9cf6c2c08390f71eb7", - "sha256:f1d53542ee8cbedbe2118b5686372fb33c297fcd6379b050cca0ef13a597382a" + "sha256:84c85a9078b11105f04f3036a9482ae10e4621616db313fe045dd24743a0820d", + "sha256:fe86415d55e84719d75f8b69414f6438ac3547d2078ab91b67e779ef69378412" ], "markers": "python_version >= '3.6'", - "version": "==2022.5.18.1" + "version": "==2022.6.15" }, "cffi": { "hashes": [ - "sha256:00c878c90cb53ccfaae6b8bc18ad05d2036553e6d9d1d9dbcf323bbe83854ca3", - "sha256:0104fb5ae2391d46a4cb082abdd5c69ea4eab79d8d44eaaf79f1b1fd806ee4c2", - "sha256:06c48159c1abed75c2e721b1715c379fa3200c7784271b3c46df01383b593636", - "sha256:0808014eb713677ec1292301ea4c81ad277b6cdf2fdd90fd540af98c0b101d20", - "sha256:10dffb601ccfb65262a27233ac273d552ddc4d8ae1bf93b21c94b8511bffe728", - "sha256:14cd121ea63ecdae71efa69c15c5543a4b5fbcd0bbe2aad864baca0063cecf27", - "sha256:17771976e82e9f94976180f76468546834d22a7cc404b17c22df2a2c81db0c66", - "sha256:181dee03b1170ff1969489acf1c26533710231c58f95534e3edac87fff06c443", - "sha256:23cfe892bd5dd8941608f93348c0737e369e51c100d03718f108bf1add7bd6d0", - "sha256:263cc3d821c4ab2213cbe8cd8b355a7f72a8324577dc865ef98487c1aeee2bc7", - "sha256:2756c88cbb94231c7a147402476be2c4df2f6078099a6f4a480d239a8817ae39", - "sha256:27c219baf94952ae9d50ec19651a687b826792055353d07648a5695413e0c605", - "sha256:2a23af14f408d53d5e6cd4e3d9a24ff9e05906ad574822a10563efcef137979a", - "sha256:31fb708d9d7c3f49a60f04cf5b119aeefe5644daba1cd2a0fe389b674fd1de37", - "sha256:3415c89f9204ee60cd09b235810be700e993e343a408693e80ce7f6a40108029", - "sha256:3773c4d81e6e818df2efbc7dd77325ca0dcb688116050fb2b3011218eda36139", - "sha256:3b96a311ac60a3f6be21d2572e46ce67f09abcf4d09344c49274eb9e0bf345fc", - "sha256:3f7d084648d77af029acb79a0ff49a0ad7e9d09057a9bf46596dac9514dc07df", - "sha256:41d45de54cd277a7878919867c0f08b0cf817605e4eb94093e7516505d3c8d14", - "sha256:4238e6dab5d6a8ba812de994bbb0a79bddbdf80994e4ce802b6f6f3142fcc880", - "sha256:45db3a33139e9c8f7c09234b5784a5e33d31fd6907800b316decad50af323ff2", - "sha256:45e8636704eacc432a206ac7345a5d3d2c62d95a507ec70d62f23cd91770482a", - "sha256:4958391dbd6249d7ad855b9ca88fae690783a6be9e86df65865058ed81fc860e", - "sha256:4a306fa632e8f0928956a41fa8e1d6243c71e7eb59ffbd165fc0b41e316b2474", - "sha256:57e9ac9ccc3101fac9d6014fba037473e4358ef4e89f8e181f8951a2c0162024", - "sha256:59888172256cac5629e60e72e86598027aca6bf01fa2465bdb676d37636573e8", - "sha256:5e069f72d497312b24fcc02073d70cb989045d1c91cbd53979366077959933e0", - "sha256:64d4ec9f448dfe041705426000cc13e34e6e5bb13736e9fd62e34a0b0c41566e", - "sha256:6dc2737a3674b3e344847c8686cf29e500584ccad76204efea14f451d4cc669a", - "sha256:74fdfdbfdc48d3f47148976f49fab3251e550a8720bebc99bf1483f5bfb5db3e", - "sha256:75e4024375654472cc27e91cbe9eaa08567f7fbdf822638be2814ce059f58032", - "sha256:786902fb9ba7433aae840e0ed609f45c7bcd4e225ebb9c753aa39725bb3e6ad6", - "sha256:8b6c2ea03845c9f501ed1313e78de148cd3f6cad741a75d43a29b43da27f2e1e", - "sha256:91d77d2a782be4274da750752bb1650a97bfd8f291022b379bb8e01c66b4e96b", - "sha256:91ec59c33514b7c7559a6acda53bbfe1b283949c34fe7440bcf917f96ac0723e", - "sha256:920f0d66a896c2d99f0adbb391f990a84091179542c205fa53ce5787aff87954", - "sha256:a5263e363c27b653a90078143adb3d076c1a748ec9ecc78ea2fb916f9b861962", - "sha256:abb9a20a72ac4e0fdb50dae135ba5e77880518e742077ced47eb1499e29a443c", - "sha256:c2051981a968d7de9dd2d7b87bcb9c939c74a34626a6e2f8181455dd49ed69e4", - "sha256:c21c9e3896c23007803a875460fb786118f0cdd4434359577ea25eb556e34c55", - "sha256:c2502a1a03b6312837279c8c1bd3ebedf6c12c4228ddbad40912d671ccc8a962", - "sha256:d4d692a89c5cf08a8557fdeb329b82e7bf609aadfaed6c0d79f5a449a3c7c023", - "sha256:da5db4e883f1ce37f55c667e5c0de439df76ac4cb55964655906306918e7363c", - "sha256:e7022a66d9b55e93e1a845d8c9eba2a1bebd4966cd8bfc25d9cd07d515b33fa6", - "sha256:ef1f279350da2c586a69d32fc8733092fd32cc8ac95139a00377841f59a3f8d8", - "sha256:f54a64f8b0c8ff0b64d18aa76675262e1700f3995182267998c31ae974fbc382", - "sha256:f5c7150ad32ba43a07c4479f40241756145a1f03b43480e058cfd862bf5041c7", - "sha256:f6f824dc3bce0edab5f427efcfb1d63ee75b6fcb7282900ccaf925be84efb0fc", - "sha256:fd8a250edc26254fe5b33be00402e6d287f562b6a5b2152dec302fa15bb3e997", - "sha256:ffaa5c925128e29efbde7301d8ecaf35c8c60ffbcd6a1ffd3a552177c8e5e796" - ], - "index": "pypi", - "version": "==1.15.0" + "sha256:00a9ed42e88df81ffae7a8ab6d9356b371399b91dbdf0c3cb1e84c03a13aceb5", + "sha256:03425bdae262c76aad70202debd780501fabeaca237cdfddc008987c0e0f59ef", + "sha256:04ed324bda3cda42b9b695d51bb7d54b680b9719cfab04227cdd1e04e5de3104", + "sha256:0e2642fe3142e4cc4af0799748233ad6da94c62a8bec3a6648bf8ee68b1c7426", + "sha256:173379135477dc8cac4bc58f45db08ab45d228b3363adb7af79436135d028405", + "sha256:198caafb44239b60e252492445da556afafc7d1e3ab7a1fb3f0584ef6d742375", + "sha256:1e74c6b51a9ed6589199c787bf5f9875612ca4a8a0785fb2d4a84429badaf22a", + "sha256:2012c72d854c2d03e45d06ae57f40d78e5770d252f195b93f581acf3ba44496e", + "sha256:21157295583fe8943475029ed5abdcf71eb3911894724e360acff1d61c1d54bc", + "sha256:2470043b93ff09bf8fb1d46d1cb756ce6132c54826661a32d4e4d132e1977adf", + "sha256:285d29981935eb726a4399badae8f0ffdff4f5050eaa6d0cfc3f64b857b77185", + "sha256:30d78fbc8ebf9c92c9b7823ee18eb92f2e6ef79b45ac84db507f52fbe3ec4497", + "sha256:320dab6e7cb2eacdf0e658569d2575c4dad258c0fcc794f46215e1e39f90f2c3", + "sha256:33ab79603146aace82c2427da5ca6e58f2b3f2fb5da893ceac0c42218a40be35", + "sha256:3548db281cd7d2561c9ad9984681c95f7b0e38881201e157833a2342c30d5e8c", + "sha256:3799aecf2e17cf585d977b780ce79ff0dc9b78d799fc694221ce814c2c19db83", + "sha256:39d39875251ca8f612b6f33e6b1195af86d1b3e60086068be9cc053aa4376e21", + "sha256:3b926aa83d1edb5aa5b427b4053dc420ec295a08e40911296b9eb1b6170f6cca", + "sha256:3bcde07039e586f91b45c88f8583ea7cf7a0770df3a1649627bf598332cb6984", + "sha256:3d08afd128ddaa624a48cf2b859afef385b720bb4b43df214f85616922e6a5ac", + "sha256:3eb6971dcff08619f8d91607cfc726518b6fa2a9eba42856be181c6d0d9515fd", + "sha256:40f4774f5a9d4f5e344f31a32b5096977b5d48560c5592e2f3d2c4374bd543ee", + "sha256:4289fc34b2f5316fbb762d75362931e351941fa95fa18789191b33fc4cf9504a", + "sha256:470c103ae716238bbe698d67ad020e1db9d9dba34fa5a899b5e21577e6d52ed2", + "sha256:4f2c9f67e9821cad2e5f480bc8d83b8742896f1242dba247911072d4fa94c192", + "sha256:50a74364d85fd319352182ef59c5c790484a336f6db772c1a9231f1c3ed0cbd7", + "sha256:54a2db7b78338edd780e7ef7f9f6c442500fb0d41a5a4ea24fff1c929d5af585", + "sha256:5635bd9cb9731e6d4a1132a498dd34f764034a8ce60cef4f5319c0541159392f", + "sha256:59c0b02d0a6c384d453fece7566d1c7e6b7bae4fc5874ef2ef46d56776d61c9e", + "sha256:5d598b938678ebf3c67377cdd45e09d431369c3b1a5b331058c338e201f12b27", + "sha256:5df2768244d19ab7f60546d0c7c63ce1581f7af8b5de3eb3004b9b6fc8a9f84b", + "sha256:5ef34d190326c3b1f822a5b7a45f6c4535e2f47ed06fec77d3d799c450b2651e", + "sha256:6975a3fac6bc83c4a65c9f9fcab9e47019a11d3d2cf7f3c0d03431bf145a941e", + "sha256:6c9a799e985904922a4d207a94eae35c78ebae90e128f0c4e521ce339396be9d", + "sha256:70df4e3b545a17496c9b3f41f5115e69a4f2e77e94e1d2a8e1070bc0c38c8a3c", + "sha256:7473e861101c9e72452f9bf8acb984947aa1661a7704553a9f6e4baa5ba64415", + "sha256:8102eaf27e1e448db915d08afa8b41d6c7ca7a04b7d73af6514df10a3e74bd82", + "sha256:87c450779d0914f2861b8526e035c5e6da0a3199d8f1add1a665e1cbc6fc6d02", + "sha256:8b7ee99e510d7b66cdb6c593f21c043c248537a32e0bedf02e01e9553a172314", + "sha256:91fc98adde3d7881af9b59ed0294046f3806221863722ba7d8d120c575314325", + "sha256:94411f22c3985acaec6f83c6df553f2dbe17b698cc7f8ae751ff2237d96b9e3c", + "sha256:98d85c6a2bef81588d9227dde12db8a7f47f639f4a17c9ae08e773aa9c697bf3", + "sha256:9ad5db27f9cabae298d151c85cf2bad1d359a1b9c686a275df03385758e2f914", + "sha256:a0b71b1b8fbf2b96e41c4d990244165e2c9be83d54962a9a1d118fd8657d2045", + "sha256:a0f100c8912c114ff53e1202d0078b425bee3649ae34d7b070e9697f93c5d52d", + "sha256:a591fe9e525846e4d154205572a029f653ada1a78b93697f3b5a8f1f2bc055b9", + "sha256:a5c84c68147988265e60416b57fc83425a78058853509c1b0629c180094904a5", + "sha256:a66d3508133af6e8548451b25058d5812812ec3798c886bf38ed24a98216fab2", + "sha256:a8c4917bd7ad33e8eb21e9a5bbba979b49d9a97acb3a803092cbc1133e20343c", + "sha256:b3bbeb01c2b273cca1e1e0c5df57f12dce9a4dd331b4fa1635b8bec26350bde3", + "sha256:cba9d6b9a7d64d4bd46167096fc9d2f835e25d7e4c121fb2ddfc6528fb0413b2", + "sha256:cc4d65aeeaa04136a12677d3dd0b1c0c94dc43abac5860ab33cceb42b801c1e8", + "sha256:ce4bcc037df4fc5e3d184794f27bdaab018943698f4ca31630bc7f84a7b69c6d", + "sha256:cec7d9412a9102bdc577382c3929b337320c4c4c4849f2c5cdd14d7368c5562d", + "sha256:d400bfb9a37b1351253cb402671cea7e89bdecc294e8016a707f6d1d8ac934f9", + "sha256:d61f4695e6c866a23a21acab0509af1cdfd2c013cf256bbf5b6b5e2695827162", + "sha256:db0fbb9c62743ce59a9ff687eb5f4afbe77e5e8403d6697f7446e5f609976f76", + "sha256:dd86c085fae2efd48ac91dd7ccffcfc0571387fe1193d33b6394db7ef31fe2a4", + "sha256:e00b098126fd45523dd056d2efba6c5a63b71ffe9f2bbe1a4fe1716e1d0c331e", + "sha256:e229a521186c75c8ad9490854fd8bbdd9a0c9aa3a524326b55be83b54d4e0ad9", + "sha256:e263d77ee3dd201c3a142934a086a4450861778baaeeb45db4591ef65550b0a6", + "sha256:ed9cb427ba5504c1dc15ede7d516b84757c3e3d7868ccc85121d9310d27eed0b", + "sha256:fa6693661a4c91757f4412306191b6dc88c1703f780c8234035eac011922bc01", + "sha256:fcd131dd944808b5bdb38e6f5b53013c5aa4f334c5cad0c72742f6eba4b73db0" + ], + "index": "pypi", + "version": "==1.15.1" }, "charset-normalizer": { "hashes": [ - "sha256:2857e29ff0d34db842cd7ca3230549d1a697f96ee6d3fb071cfa6c7393832597", - "sha256:6881edbebdb17b39b4eaaa821b438bf6eddffb4468cf344f09f89def34a8b1df" + "sha256:5189b6f22b01957427f35b6a08d9a0bc45b46d3788ef5a92e978433c7a35f8a5", + "sha256:575e708016ff3a5e3681541cb9d79312c416835686d054a23accb873b254f413" ], - "markers": "python_full_version >= '3.5.0'", - "version": "==2.0.12" + "markers": "python_version >= '3.6'", + "version": "==2.1.0" }, "click": { "hashes": [ @@ -169,31 +183,31 @@ }, "cryptography": { "hashes": [ - "sha256:093cb351031656d3ee2f4fa1be579a8c69c754cf874206be1d4cf3b542042804", - "sha256:0cc20f655157d4cfc7bada909dc5cc228211b075ba8407c46467f63597c78178", - "sha256:1b9362d34363f2c71b7853f6251219298124aa4cc2075ae2932e64c91a3e2717", - "sha256:1f3bfbd611db5cb58ca82f3deb35e83af34bb8cf06043fa61500157d50a70982", - "sha256:2bd1096476aaac820426239ab534b636c77d71af66c547b9ddcd76eb9c79e004", - "sha256:31fe38d14d2e5f787e0aecef831457da6cec68e0bb09a35835b0b44ae8b988fe", - "sha256:3b8398b3d0efc420e777c40c16764d6870bcef2eb383df9c6dbb9ffe12c64452", - "sha256:3c81599befb4d4f3d7648ed3217e00d21a9341a9a688ecdd615ff72ffbed7336", - "sha256:419c57d7b63f5ec38b1199a9521d77d7d1754eb97827bbb773162073ccd8c8d4", - "sha256:46f4c544f6557a2fefa7ac8ac7d1b17bf9b647bd20b16decc8fbcab7117fbc15", - "sha256:471e0d70201c069f74c837983189949aa0d24bb2d751b57e26e3761f2f782b8d", - "sha256:59b281eab51e1b6b6afa525af2bd93c16d49358404f814fe2c2410058623928c", - "sha256:731c8abd27693323b348518ed0e0705713a36d79fdbd969ad968fbef0979a7e0", - "sha256:95e590dd70642eb2079d280420a888190aa040ad20f19ec8c6e097e38aa29e06", - "sha256:a68254dd88021f24a68b613d8c51d5c5e74d735878b9e32cc0adf19d1f10aaf9", - "sha256:a7d5137e556cc0ea418dca6186deabe9129cee318618eb1ffecbd35bee55ddc1", - "sha256:aeaba7b5e756ea52c8861c133c596afe93dd716cbcacae23b80bc238202dc023", - "sha256:dc26bb134452081859aa21d4990474ddb7e863aa39e60d1592800a8865a702de", - "sha256:e53258e69874a306fcecb88b7534d61820db8a98655662a3dd2ec7f1afd9132f", - "sha256:ef15c2df7656763b4ff20a9bc4381d8352e6640cfeb95c2972c38ef508e75181", - "sha256:f224ad253cc9cea7568f49077007d2263efa57396a2f2f78114066fd54b5c68e", - "sha256:f8ec91983e638a9bcd75b39f1396e5c0dc2330cbd9ce4accefe68717e6779e0a" - ], - "index": "pypi", - "version": "==37.0.2" + "sha256:190f82f3e87033821828f60787cfa42bff98404483577b591429ed99bed39d59", + "sha256:2be53f9f5505673eeda5f2736bea736c40f051a739bfae2f92d18aed1eb54596", + "sha256:30788e070800fec9bbcf9faa71ea6d8068f5136f60029759fd8c3efec3c9dcb3", + "sha256:3d41b965b3380f10e4611dbae366f6dc3cefc7c9ac4e8842a806b9672ae9add5", + "sha256:4c590ec31550a724ef893c50f9a97a0c14e9c851c85621c5650d699a7b88f7ab", + "sha256:549153378611c0cca1042f20fd9c5030d37a72f634c9326e225c9f666d472884", + "sha256:63f9c17c0e2474ccbebc9302ce2f07b55b3b3fcb211ded18a42d5764f5c10a82", + "sha256:6bc95ed67b6741b2607298f9ea4932ff157e570ef456ef7ff0ef4884a134cc4b", + "sha256:7099a8d55cd49b737ffc99c17de504f2257e3787e02abe6d1a6d136574873441", + "sha256:75976c217f10d48a8b5a8de3d70c454c249e4b91851f6838a4e48b8f41eb71aa", + "sha256:7bc997818309f56c0038a33b8da5c0bfbb3f1f067f315f9abd6fc07ad359398d", + "sha256:80f49023dd13ba35f7c34072fa17f604d2f19bf0989f292cedf7ab5770b87a0b", + "sha256:91ce48d35f4e3d3f1d83e29ef4a9267246e6a3be51864a5b7d2247d5086fa99a", + "sha256:a958c52505c8adf0d3822703078580d2c0456dd1d27fabfb6f76fe63d2971cd6", + "sha256:b62439d7cd1222f3da897e9a9fe53bbf5c104fff4d60893ad1355d4c14a24157", + "sha256:b7f8dd0d4c1f21759695c05a5ec8536c12f31611541f8904083f3dc582604280", + "sha256:d204833f3c8a33bbe11eda63a54b1aad7aa7456ed769a982f21ec599ba5fa282", + "sha256:e007f052ed10cc316df59bc90fbb7ff7950d7e2919c9757fd42a2b8ecf8a5f67", + "sha256:f2dcb0b3b63afb6df7fd94ec6fbddac81b5492513f7b0436210d390c14d46ee8", + "sha256:f721d1885ecae9078c3f6bbe8a88bc0786b6e749bf32ccec1ef2b18929a05046", + "sha256:f7a6de3e98771e183645181b3627e2563dcde3ce94a9e42a3f427d2255190327", + "sha256:f8c0a6e9e1dd3eb0414ba320f85da6b0dcbd543126e30fcc546e7372a7fbf3b9" + ], + "index": "pypi", + "version": "==37.0.4" }, "cython": { "hashes": [ @@ -347,31 +361,31 @@ "sha256:84d9dd047ffa80596e0f246e2eab0b391788b0503584e8945f2368256d2735ff", "sha256:9d643ff0a55b762d5cdb124b8eaa99c66322e2157b69160bc32796e824360e6d" ], - "markers": "python_full_version >= '3.5.0'", + "markers": "python_version >= '3.5'", "version": "==3.3" }, "importlib-metadata": { "hashes": [ - "sha256:5d26852efe48c0a32b0509ffbc583fda1a2266545a78d104a6f4aff3db17d700", - "sha256:c58c8eb8a762858f49e18436ff552e83914778e50e9d2f1660535ffb364552ec" + "sha256:637245b8bab2b6502fcbc752cc4b7a6f6243bb02b31c5c26156ad103d3d45670", + "sha256:7401a975809ea1fdc658c3aa4f78cc2195a0e019c5cbc4c06122884e9ae80c23" ], "markers": "python_version < '3.10'", - "version": "==4.11.4" + "version": "==4.12.0" }, "importlib-resources": { "hashes": [ - "sha256:b6062987dfc51f0fcb809187cffbd60f35df7acb4589091f154214af6d0d49d3", - "sha256:e447dc01619b1e951286f3929be820029d48c75eb25d265c28b92a16548212b8" + "sha256:568c9f16cb204f9decc8d6d24a572eeea27dacbb4cee9e6b03a8025736769751", + "sha256:7952325ffd516c05a8ad0858c74dff2c3343f136fe66a6002b2623dd1d43f223" ], "markers": "python_version >= '3.7'", - "version": "==5.7.1" + "version": "==5.8.0" }, "isort": { "hashes": [ "sha256:6f62d78e2f89b4500b080fe3a81690850cd254227f27f75c3a0c491a1f351ba7", "sha256:e8443a5e7a020e9d7f97f1d7d9cd17c88bcb3bc7e218bf9cf5095fe550be2951" ], - "markers": "python_version < '4.0' and python_full_version >= '3.6.1'", + "markers": "python_version < '4' and python_full_version >= '3.6.1'", "version": "==5.10.1" }, "itsdangerous": { @@ -563,62 +577,58 @@ }, "numpy": { "hashes": [ - "sha256:0791fbd1e43bf74b3502133207e378901272f3c156c4df4954cad833b1380207", - "sha256:1ce7ab2053e36c0a71e7a13a7475bd3b1f54750b4b433adc96313e127b870887", - "sha256:2d487e06ecbf1dc2f18e7efce82ded4f705f4bd0cd02677ffccfb39e5c284c7e", - "sha256:37431a77ceb9307c28382c9773da9f306435135fae6b80b62a11c53cfedd8802", - "sha256:3e1ffa4748168e1cc8d3cde93f006fe92b5421396221a02f2274aab6ac83b077", - "sha256:425b390e4619f58d8526b3dcf656dde069133ae5c240229821f01b5f44ea07af", - "sha256:43a8ca7391b626b4c4fe20aefe79fec683279e31e7c79716863b4b25021e0e74", - "sha256:4c6036521f11a731ce0648f10c18ae66d7143865f19f7299943c985cdc95afb5", - "sha256:59d55e634968b8f77d3fd674a3cf0b96e85147cd6556ec64ade018f27e9479e1", - "sha256:64f56fc53a2d18b1924abd15745e30d82a5782b2cab3429aceecc6875bd5add0", - "sha256:7228ad13744f63575b3a972d7ee4fd61815b2879998e70930d4ccf9ec721dce0", - "sha256:9ce7df0abeabe7fbd8ccbf343dc0db72f68549856b863ae3dd580255d009648e", - "sha256:a911e317e8c826ea632205e63ed8507e0dc877dcdc49744584dfc363df9ca08c", - "sha256:b89bf9b94b3d624e7bb480344e91f68c1c6c75f026ed6755955117de00917a7c", - "sha256:ba9ead61dfb5d971d77b6c131a9dbee62294a932bf6a356e48c75ae684e635b3", - "sha256:c1d937820db6e43bec43e8d016b9b3165dcb42892ea9f106c70fb13d430ffe72", - "sha256:cc7f00008eb7d3f2489fca6f334ec19ca63e31371be28fd5dad955b16ec285bd", - "sha256:d4c5d5eb2ec8da0b4f50c9a843393971f31f1d60be87e0fb0917a49133d257d6", - "sha256:e96d7f3096a36c8754207ab89d4b3282ba7b49ea140e4973591852c77d09eb76", - "sha256:f0725df166cf4785c0bc4cbfb320203182b1ecd30fee6e541c8752a92df6aa32", - "sha256:f3eb268dbd5cfaffd9448113539e44e2dd1c5ca9ce25576f7c04a5453edc26fa", - "sha256:fb7a980c81dd932381f8228a426df8aeb70d59bbcda2af075b627bbc50207cba" - ], - "index": "pypi", - "version": "==1.22.4" + "sha256:092f5e6025813e64ad6d1b52b519165d08c730d099c114a9247c9bb635a2a450", + "sha256:196cd074c3f97c4121601790955f915187736f9cf458d3ee1f1b46aff2b1ade0", + "sha256:1c29b44905af288b3919803aceb6ec7fec77406d8b08aaa2e8b9e63d0fe2f160", + "sha256:2b2da66582f3a69c8ce25ed7921dcd8010d05e59ac8d89d126a299be60421171", + "sha256:5043bcd71fcc458dfb8a0fc5509bbc979da0131b9d08e3d5f50fb0bbb36f169a", + "sha256:58bfd40eb478f54ff7a5710dd61c8097e169bc36cc68333d00a9bcd8def53b38", + "sha256:79a506cacf2be3a74ead5467aee97b81fca00c9c4c8b3ba16dbab488cd99ba10", + "sha256:94b170b4fa0168cd6be4becf37cb5b127bd12a795123984385b8cd4aca9857e5", + "sha256:97a76604d9b0e79f59baeca16593c711fddb44936e40310f78bfef79ee9a835f", + "sha256:98e8e0d8d69ff4d3fa63e6c61e8cfe2d03c29b16b58dbef1f9baa175bbed7860", + "sha256:ac86f407873b952679f5f9e6c0612687e51547af0e14ddea1eedfcb22466babd", + "sha256:ae8adff4172692ce56233db04b7ce5792186f179c415c37d539c25de7298d25d", + "sha256:bd3fa4fe2e38533d5336e1272fc4e765cabbbde144309ccee8675509d5cd7b05", + "sha256:d0d2094e8f4d760500394d77b383a1b06d3663e8892cdf5df3c592f55f3bff66", + "sha256:d54b3b828d618a19779a84c3ad952e96e2c2311b16384e973e671aa5be1f6187", + "sha256:d6ca8dabe696c2785d0c8c9b0d8a9b6e5fdbe4f922bde70d57fa1a2848134f95", + "sha256:d8cc87bed09de55477dba9da370c1679bd534df9baa171dd01accbb09687dac3", + "sha256:f0f18804df7370571fb65db9b98bf1378172bd4e962482b857e612d1fec0f53e", + "sha256:f1d88ef79e0a7fa631bb2c3dda1ea46b32b1fe614e10fedd611d3d5398447f2f", + "sha256:f9c3fc2adf67762c9fe1849c859942d23f8d3e0bee7b5ed3d4a9c3eeb50a2f07", + "sha256:fc431493df245f3c627c0c05c2bd134535e7929dbe2e602b80e42bf52ff760bc", + "sha256:fe8b9683eb26d2c4d5db32cd29b38fdcf8381324ab48313b5b69088e0e355379" + ], + "index": "pypi", + "version": "==1.23.0" }, "onnx": { "hashes": [ - "sha256:0cf47c205b376b3763beef92a6de4152f3b1552d6f640d93044938500baf5958", - "sha256:3403884c482859f8cf2e0c276da84bd9ac2235d266726f4ddc9625d3fd263218", - "sha256:43b32a2f20c94aa98866deae9e4218faf0495144ad05402e918fa279674b6df9", - "sha256:4454906de80a351de6929b0896ad605d106c324c3112c92249240e531f68fbba", - "sha256:4aa899f74acd4c5543f0efed8bfe98a3b701df75c5ffa179212e3088c51971bb", - "sha256:58d4873ec587ac14c44227d8027787edc88cd61596e646e3417f2a826a920898", - "sha256:593ca9e11f15afa26b3aaf2d170bb803d4bd86dbd560aa7be4e5f535d03f83d5", - "sha256:67c6d2654c1c203e5c839a47900b51f588fd0de71bbd497fb193d30a0b3ec1e9", - "sha256:7924d9baa13dbbf335737229f6d068f380d153679f357e495da60007b61cf56d", - "sha256:7a2f5d6998fe79aed80fad9d4522140d02c4d29513047e335d5c5355c1ebda5e", - "sha256:82221a07707b1ccf71fb18c6abb77f2566517a55d5185809775b5ff008bfb35c", - "sha256:89420e5b824d7e182846fe2aa09190ddb41162b261465c6ca928174bc2ac10b7", - "sha256:997d91ffd7b7ae7aee09c6d652a896d906be430d425865c759b51a8de5df9fe0", - "sha256:9b9f58ea01c1b20b057f55f628df4fc0403bbc160b7282a56e3bb4df5c7fb96f", - "sha256:a6e9135f1d02539ca7573f699fb0d31d3c43d10fac1d2d2239a9a1c553506c29", - "sha256:ae74bf8fa343b64e2b7fe205091b7f3728887c018ae061d161dd86ec95eb66a8", - "sha256:b2de0b117ad77689d308824a0c9eb89539ec28a799b4e2e05b3bb977b0da0b45", - "sha256:c3d3503110f2cab2c818f4a7b2bc8abc3bc79649daa39e70d5fb504b208ddb1e", - "sha256:d6581dd2122525549d1d8b431b8bf375298993c77bddb8fd0bf0d92611df76a1", - "sha256:d6ddbe89e32f885db736d36fcb132784e368331a18c3b6168ac9f561eb462057", - "sha256:df85666ab2b88fd9cf9b2504bcb551da39422eab65a143926a8db58f81b09164", - "sha256:ea06dbf57a287657b6dc4e189918e4cb451450308589d482117216194d6f83d6", - "sha256:eb46f31f12bb0bfdcfb68497d10b20447cf8fa6c4f693120c013e052645357b8", - "sha256:eca224c7c2c8ee4072a0743e4898a84a9bdf8297b5e5910a2632e4c4182ffb2a", - "sha256:f335d982b8ed201cf767459b993630acfd20c32b100529f70af9f28a26e72167" - ], - "index": "pypi", - "version": "==1.11.0" + "sha256:13b3e77d27523b9dbf4f30dfc9c959455859d5e34e921c44f712d69b8369eff9", + "sha256:213e73610173f6b2e99f99a4b0636f80b379c417312079d603806e48ada4ca8b", + "sha256:23781594bb8b7ee985de1005b3c601648d5b0568a81e01365c48f91d1f5648e4", + "sha256:2d9a7db54e75529160337232282a4816cc50667dc7dc34be178fd6f6b79d4705", + "sha256:341c7016e23273e9ffa9b6e301eee95b8c37d0f04df7cedbdb169d2c39524c96", + "sha256:3c6e6bcffc3f5c1e148df3837dc667fa4c51999788c1b76b0b8fbba607e02da8", + "sha256:5578b93dc6c918cec4dee7fb7d9dd3b09d338301ee64ca8b4f28bc217ed42dca", + "sha256:56ceb7e094c43882b723cfaa107d85ad673cfdf91faeb28d7dcadacca4f43a07", + "sha256:81a3555fd67be2518bf86096299b48fb9154652596219890abfe90bd43a9ec13", + "sha256:8a7aa61aea339bd28f310f4af4f52ce6c4b876386228760b16308efd58f95059", + "sha256:9fd2f4e23078df197bb76a59b9cd8f5a43a6ad2edc035edb3ecfb9042093e05a", + "sha256:af90427ca04c6b7b8107c2021e1273227a3ef1a7a01f3073039cae7855a59833", + "sha256:b3629e8258db15d4e2c9b7f1be91a3186719dd94661c218c6f5fde3cc7de3d4d", + "sha256:bdbd2578424c70836f4d0f9dda16c21868ddb07cc8192f9e8a176908b43d694b", + "sha256:c11162ffc487167da140f1112f49c4f82d815824f06e58bc3095407699f05863", + "sha256:c39a7a0352c856f1df30dccf527eb6cb4909052e5eaf6fa2772a637324c526aa", + "sha256:c7a9b3ea02c30efc1d2662337e280266aca491a8e86be0d8a657f874b7cccd1e", + "sha256:f66d2996e65f490a57b3ae952e4e9189b53cc9fe3f75e601d50d4db2dc1b1cd9", + "sha256:f8800f28c746ab06e51ef8449fd1215621f4ddba91be3ffc264658937d38a2af", + "sha256:fab13feb4d94342aae6d357d480f2e47d41b9f4e584367542b21ca6defda9e0a", + "sha256:fea5156a03398fe0e23248042d8651c1eaac5f6637d4dd683b4c1f1320b9f7b4" + ], + "index": "pypi", + "version": "==1.12.0" }, "onnxruntime-gpu": { "hashes": [ @@ -635,47 +645,67 @@ }, "pillow": { "hashes": [ - "sha256:088df396b047477dd1bbc7de6e22f58400dae2f21310d9e2ec2933b2ef7dfa4f", - "sha256:09e67ef6e430f90caa093528bd758b0616f8165e57ed8d8ce014ae32df6a831d", - "sha256:0b4d5ad2cd3a1f0d1df882d926b37dbb2ab6c823ae21d041b46910c8f8cd844b", - "sha256:0b525a356680022b0af53385944026d3486fc8c013638cf9900eb87c866afb4c", - "sha256:1d4331aeb12f6b3791911a6da82de72257a99ad99726ed6b63f481c0184b6fb9", - "sha256:20d514c989fa28e73a5adbddd7a171afa5824710d0ab06d4e1234195d2a2e546", - "sha256:2b291cab8a888658d72b575a03e340509b6b050b62db1f5539dd5cd18fd50578", - "sha256:3f6c1716c473ebd1649663bf3b42702d0d53e27af8b64642be0dd3598c761fb1", - "sha256:42dfefbef90eb67c10c45a73a9bc1599d4dac920f7dfcbf4ec6b80cb620757fe", - "sha256:488f3383cf5159907d48d32957ac6f9ea85ccdcc296c14eca1a4e396ecc32098", - "sha256:4d45dbe4b21a9679c3e8b3f7f4f42a45a7d3ddff8a4a16109dff0e1da30a35b2", - "sha256:53c27bd452e0f1bc4bfed07ceb235663a1df7c74df08e37fd6b03eb89454946a", - "sha256:55e74faf8359ddda43fee01bffbc5bd99d96ea508d8a08c527099e84eb708f45", - "sha256:59789a7d06c742e9d13b883d5e3569188c16acb02eeed2510fd3bfdbc1bd1530", - "sha256:5b650dbbc0969a4e226d98a0b440c2f07a850896aed9266b6fedc0f7e7834108", - "sha256:66daa16952d5bf0c9d5389c5e9df562922a59bd16d77e2a276e575d32e38afd1", - "sha256:6e760cf01259a1c0a50f3c845f9cad1af30577fd8b670339b1659c6d0e7a41dd", - "sha256:7502539939b53d7565f3d11d87c78e7ec900d3c72945d4ee0e2f250d598309a0", - "sha256:769a7f131a2f43752455cc72f9f7a093c3ff3856bf976c5fb53a59d0ccc704f6", - "sha256:7c150dbbb4a94ea4825d1e5f2c5501af7141ea95825fadd7829f9b11c97aaf6c", - "sha256:8844217cdf66eabe39567118f229e275f0727e9195635a15e0e4b9227458daaf", - "sha256:8a66fe50386162df2da701b3722781cbe90ce043e7d53c1fd6bd801bca6b48d4", - "sha256:9370d6744d379f2de5d7fa95cdbd3a4d92f0b0ef29609b4b1687f16bc197063d", - "sha256:937a54e5694684f74dcbf6e24cc453bfc5b33940216ddd8f4cd8f0f79167f765", - "sha256:9c857532c719fb30fafabd2371ce9b7031812ff3889d75273827633bca0c4602", - "sha256:a4165205a13b16a29e1ac57efeee6be2dfd5b5408122d59ef2145bc3239fa340", - "sha256:b3fe2ff1e1715d4475d7e2c3e8dabd7c025f4410f79513b4ff2de3d51ce0fa9c", - "sha256:b6617221ff08fbd3b7a811950b5c3f9367f6e941b86259843eab77c8e3d2b56b", - "sha256:b761727ed7d593e49671d1827044b942dd2f4caae6e51bab144d4accf8244a84", - "sha256:baf3be0b9446a4083cc0c5bb9f9c964034be5374b5bc09757be89f5d2fa247b8", - "sha256:c17770a62a71718a74b7548098a74cd6880be16bcfff5f937f900ead90ca8e92", - "sha256:c67db410508b9de9c4694c57ed754b65a460e4812126e87f5052ecf23a011a54", - "sha256:d78ca526a559fb84faaaf84da2dd4addef5edb109db8b81677c0bb1aad342601", - "sha256:e9ed59d1b6ee837f4515b9584f3d26cf0388b742a11ecdae0d9237a94505d03a", - "sha256:f054b020c4d7e9786ae0404278ea318768eb123403b18453e28e47cdb7a0a4bf", - "sha256:f372d0f08eff1475ef426344efe42493f71f377ec52237bf153c5713de987251", - "sha256:f3f6a6034140e9e17e9abc175fc7a266a6e63652028e157750bd98e804a8ed9a", - "sha256:ffde4c6fabb52891d81606411cbfaf77756e3b561b566efd270b3ed3791fde4e" - ], - "index": "pypi", - "version": "==9.1.1" + "sha256:0030fdbd926fb85844b8b92e2f9449ba89607231d3dd597a21ae72dc7fe26927", + "sha256:030e3460861488e249731c3e7ab59b07c7853838ff3b8e16aac9561bb345da14", + "sha256:0ed2c4ef2451de908c90436d6e8092e13a43992f1860275b4d8082667fbb2ffc", + "sha256:136659638f61a251e8ed3b331fc6ccd124590eeff539de57c5f80ef3a9594e58", + "sha256:13b725463f32df1bfeacbf3dd197fb358ae8ebcd8c5548faa75126ea425ccb60", + "sha256:1536ad017a9f789430fb6b8be8bf99d2f214c76502becc196c6f2d9a75b01b76", + "sha256:15928f824870535c85dbf949c09d6ae7d3d6ac2d6efec80f3227f73eefba741c", + "sha256:17d4cafe22f050b46d983b71c707162d63d796a1235cdf8b9d7a112e97b15bac", + "sha256:1802f34298f5ba11d55e5bb09c31997dc0c6aed919658dfdf0198a2fe75d5490", + "sha256:1cc1d2451e8a3b4bfdb9caf745b58e6c7a77d2e469159b0d527a4554d73694d1", + "sha256:1fd6f5e3c0e4697fa7eb45b6e93996299f3feee73a3175fa451f49a74d092b9f", + "sha256:254164c57bab4b459f14c64e93df11eff5ded575192c294a0c49270f22c5d93d", + "sha256:2ad0d4df0f5ef2247e27fc790d5c9b5a0af8ade9ba340db4a73bb1a4a3e5fb4f", + "sha256:2c58b24e3a63efd22554c676d81b0e57f80e0a7d3a5874a7e14ce90ec40d3069", + "sha256:2d33a11f601213dcd5718109c09a52c2a1c893e7461f0be2d6febc2879ec2402", + "sha256:337a74fd2f291c607d220c793a8135273c4c2ab001b03e601c36766005f36885", + "sha256:37ff6b522a26d0538b753f0b4e8e164fdada12db6c6f00f62145d732d8a3152e", + "sha256:3d1f14f5f691f55e1b47f824ca4fdcb4b19b4323fe43cc7bb105988cad7496be", + "sha256:408673ed75594933714482501fe97e055a42996087eeca7e5d06e33218d05aa8", + "sha256:4134d3f1ba5f15027ff5c04296f13328fecd46921424084516bdb1b2548e66ff", + "sha256:4ad2f835e0ad81d1689f1b7e3fbac7b01bb8777d5a985c8962bedee0cc6d43da", + "sha256:50dff9cc21826d2977ef2d2a205504034e3a4563ca6f5db739b0d1026658e004", + "sha256:510cef4a3f401c246cfd8227b300828715dd055463cdca6176c2e4036df8bd4f", + "sha256:5aed7dde98403cd91d86a1115c78d8145c83078e864c1de1064f52e6feb61b20", + "sha256:69bd1a15d7ba3694631e00df8de65a8cb031911ca11f44929c97fe05eb9b6c1d", + "sha256:6bf088c1ce160f50ea40764f825ec9b72ed9da25346216b91361eef8ad1b8f8c", + "sha256:6e8c66f70fb539301e064f6478d7453e820d8a2c631da948a23384865cd95544", + "sha256:727dd1389bc5cb9827cbd1f9d40d2c2a1a0c9b32dd2261db522d22a604a6eec9", + "sha256:74a04183e6e64930b667d321524e3c5361094bb4af9083db5c301db64cd341f3", + "sha256:75e636fd3e0fb872693f23ccb8a5ff2cd578801251f3a4f6854c6a5d437d3c04", + "sha256:7761afe0126d046974a01e030ae7529ed0ca6a196de3ec6937c11df0df1bc91c", + "sha256:7888310f6214f19ab2b6df90f3f06afa3df7ef7355fc025e78a3044737fab1f5", + "sha256:7b0554af24df2bf96618dac71ddada02420f946be943b181108cac55a7a2dcd4", + "sha256:7c7b502bc34f6e32ba022b4a209638f9e097d7a9098104ae420eb8186217ebbb", + "sha256:808add66ea764ed97d44dda1ac4f2cfec4c1867d9efb16a33d158be79f32b8a4", + "sha256:831e648102c82f152e14c1a0938689dbb22480c548c8d4b8b248b3e50967b88c", + "sha256:93689632949aff41199090eff5474f3990b6823404e45d66a5d44304e9cdc467", + "sha256:96b5e6874431df16aee0c1ba237574cb6dff1dcb173798faa6a9d8b399a05d0e", + "sha256:9a54614049a18a2d6fe156e68e188da02a046a4a93cf24f373bffd977e943421", + "sha256:a138441e95562b3c078746a22f8fca8ff1c22c014f856278bdbdd89ca36cff1b", + "sha256:a647c0d4478b995c5e54615a2e5360ccedd2f85e70ab57fbe817ca613d5e63b8", + "sha256:a9c9bc489f8ab30906d7a85afac4b4944a572a7432e00698a7239f44a44e6efb", + "sha256:ad2277b185ebce47a63f4dc6302e30f05762b688f8dc3de55dbae4651872cdf3", + "sha256:b6d5e92df2b77665e07ddb2e4dbd6d644b78e4c0d2e9272a852627cdba0d75cf", + "sha256:bc431b065722a5ad1dfb4df354fb9333b7a582a5ee39a90e6ffff688d72f27a1", + "sha256:bdd0de2d64688ecae88dd8935012c4a72681e5df632af903a1dca8c5e7aa871a", + "sha256:c79698d4cd9318d9481d89a77e2d3fcaeff5486be641e60a4b49f3d2ecca4e28", + "sha256:cb6259196a589123d755380b65127ddc60f4c64b21fc3bb46ce3a6ea663659b0", + "sha256:d5b87da55a08acb586bad5c3aa3b86505f559b84f39035b233d5bf844b0834b1", + "sha256:dcd7b9c7139dc8258d164b55696ecd16c04607f1cc33ba7af86613881ffe4ac8", + "sha256:dfe4c1fedfde4e2fbc009d5ad420647f7730d719786388b7de0999bf32c0d9fd", + "sha256:ea98f633d45f7e815db648fd7ff0f19e328302ac36427343e4432c84432e7ff4", + "sha256:ec52c351b35ca269cb1f8069d610fc45c5bd38c3e91f9ab4cbbf0aebc136d9c8", + "sha256:eef7592281f7c174d3d6cbfbb7ee5984a671fcd77e3fc78e973d492e9bf0eb3f", + "sha256:f07f1f00e22b231dd3d9b9208692042e29792d6bd4f6639415d2f23158a80013", + "sha256:f3fac744f9b540148fa7715a435d2283b71f68bfb6d4aae24482a890aed18b59", + "sha256:fa768eff5f9f958270b081bb33581b4b569faabf8774726b283edb06617101dc", + "sha256:fac2d65901fb0fdf20363fbd345c01958a742f2dc62a8dd4495af66e3ff502a4" + ], + "index": "pypi", + "version": "==9.2.0" }, "platformdirs": { "hashes": [ @@ -803,39 +833,39 @@ }, "pycryptodome": { "hashes": [ - "sha256:028dcbf62d128b4335b61c9fbb7dd8c376594db607ef36d5721ee659719935d5", - "sha256:12ef157eb1e01a157ca43eda275fa68f8db0dd2792bc4fe00479ab8f0e6ae075", - "sha256:2562de213960693b6d657098505fd4493c45f3429304da67efcbeb61f0edfe89", - "sha256:27e92c1293afcb8d2639baf7eb43f4baada86e4de0f1fb22312bfc989b95dae2", - "sha256:36e3242c4792e54ed906c53f5d840712793dc68b726ec6baefd8d978c5282d30", - "sha256:50a5346af703330944bea503106cd50c9c2212174cfcb9939db4deb5305a8367", - "sha256:53dedbd2a6a0b02924718b520a723e88bcf22e37076191eb9b91b79934fb2192", - "sha256:69f05aaa90c99ac2f2af72d8d7f185f729721ad7c4be89e9e3d0ab101b0ee875", - "sha256:75a3a364fee153e77ed889c957f6f94ec6d234b82e7195b117180dcc9fc16f96", - "sha256:766a8e9832128c70012e0c2b263049506cbf334fb21ff7224e2704102b6ef59e", - "sha256:7fb90a5000cc9c9ff34b4d99f7f039e9c3477700e309ff234eafca7b7471afc0", - "sha256:893f32210de74b9f8ac869ed66c97d04e7d351182d6d39ebd3b36d3db8bda65d", - "sha256:8b5c28058102e2974b9868d72ae5144128485d466ba8739abd674b77971454cc", - "sha256:924b6aad5386fb54f2645f22658cb0398b1f25bc1e714a6d1522c75d527deaa5", - "sha256:9924248d6920b59c260adcae3ee231cd5af404ac706ad30aa4cd87051bf09c50", - "sha256:9ec761a35dbac4a99dcbc5cd557e6e57432ddf3e17af8c3c86b44af9da0189c0", - "sha256:a36ab51674b014ba03da7f98b675fcb8eabd709a2d8e18219f784aba2db73b72", - "sha256:aae395f79fa549fb1f6e3dc85cf277f0351e15a22e6547250056c7f0c990d6a5", - "sha256:c880a98376939165b7dc504559f60abe234b99e294523a273847f9e7756f4132", - "sha256:ce7a875694cd6ccd8682017a7c06c6483600f151d8916f2b25cf7a439e600263", - "sha256:d1b7739b68a032ad14c5e51f7e4e1a5f92f3628bba024a2bda1f30c481fc85d8", - "sha256:dcd65355acba9a1d0fc9b923875da35ed50506e339b35436277703d7ace3e222", - "sha256:e04e40a7f8c1669195536a37979dd87da2c32dbdc73d6fe35f0077b0c17c803b", - "sha256:e0c04c41e9ade19fbc0eff6aacea40b831bfcb2c91c266137bcdfd0d7b2f33ba", - "sha256:e24d4ec4b029611359566c52f31af45c5aecde7ef90bf8f31620fd44c438efe7", - "sha256:e64738207a02a83590df35f59d708bf1e7ea0d6adce712a777be2967e5f7043c", - "sha256:ea56a35fd0d13121417d39a83f291017551fa2c62d6daa6b04af6ece7ed30d84", - "sha256:f2772af1c3ef8025c85335f8b828d0193fa1e43256621f613280e2c81bfad423", - "sha256:f403a3e297a59d94121cb3ee4b1cf41f844332940a62d71f9e4a009cc3533493", - "sha256:f572a3ff7b6029dd9b904d6be4e0ce9e309dcb847b03e3ac8698d9d23bb36525" - ], - "index": "pypi", - "version": "==3.14.1" + "sha256:045d75527241d17e6ef13636d845a12e54660aa82e823b3b3341bcf5af03fa79", + "sha256:0926f7cc3735033061ef3cf27ed16faad6544b14666410727b31fea85a5b16eb", + "sha256:092a26e78b73f2530b8bd6b3898e7453ab2f36e42fd85097d705d6aba2ec3e5e", + "sha256:1b22bcd9ec55e9c74927f6b1f69843cb256fb5a465088ce62837f793d9ffea88", + "sha256:2aa55aae81f935a08d5a3c2042eb81741a43e044bd8a81ea7239448ad751f763", + "sha256:2ea63d46157386c5053cfebcdd9bd8e0c8b7b0ac4a0507a027f5174929403884", + "sha256:2ec709b0a58b539a4f9d33fb8508264c3678d7edb33a68b8906ba914f71e8c13", + "sha256:2ffd8b31561455453ca9f62cb4c24e6b8d119d6d531087af5f14b64bee2c23e6", + "sha256:4b52cb18b0ad46087caeb37a15e08040f3b4c2d444d58371b6f5d786d95534c2", + "sha256:4c3ccad74eeb7b001f3538643c4225eac398c77d617ebb3e57571a897943c667", + "sha256:5099c9ca345b2f252f0c28e96904643153bae9258647585e5e6f649bb7a1844a", + "sha256:57f565acd2f0cf6fb3e1ba553d0cb1f33405ec1f9c5ded9b9a0a5320f2c0bd3d", + "sha256:60b4faae330c3624cc5a546ba9cfd7b8273995a15de94ee4538130d74953ec2e", + "sha256:7c9ed8aa31c146bef65d89a1b655f5f4eab5e1120f55fc297713c89c9e56ff0b", + "sha256:7e3a8f6ee405b3bd1c4da371b93c31f7027944b2bcce0697022801db93120d83", + "sha256:9135dddad504592bcc18b0d2d95ce86c3a5ea87ec6447ef25cfedea12d6018b8", + "sha256:9c772c485b27967514d0df1458b56875f4b6d025566bf27399d0c239ff1b369f", + "sha256:9eaadc058106344a566dc51d3d3a758ab07f8edde013712bc8d22032a86b264f", + "sha256:9ee40e2168f1348ae476676a2e938ca80a2f57b14a249d8fe0d3cdf803e5a676", + "sha256:a8f06611e691c2ce45ca09bbf983e2ff2f8f4f87313609d80c125aff9fad6e7f", + "sha256:b9c5b1a1977491533dfd31e01550ee36ae0249d78aae7f632590db833a5012b8", + "sha256:b9cc96e274b253e47ad33ae1fccc36ea386f5251a823ccb50593a935db47fdd2", + "sha256:c3640deff4197fa064295aaac10ab49a0d55ef3d6a54ae1499c40d646655c89f", + "sha256:c77126899c4b9c9827ddf50565e93955cb3996813c18900c16b2ea0474e130e9", + "sha256:d2a39a66057ab191e5c27211a7daf8f0737f23acbf6b3562b25a62df65ffcb7b", + "sha256:e244ab85c422260de91cda6379e8e986405b4f13dc97d2876497178707f87fc1", + "sha256:ecaaef2d21b365d9c5ca8427ffc10cebed9d9102749fd502218c23cb9a05feb5", + "sha256:fd2184aae6ee2a944aaa49113e6f5787cdc5e4db1eb8edb1aea914bd75f33a0c", + "sha256:ff287bcba9fbeb4f1cccc1f2e90a08d691480735a611ee83c80a7d74ad72b9d9", + "sha256:ff7ae90e36c1715a54446e7872b76102baa5c63aa980917f4aa45e8c78d1a3ec" + ], + "index": "pypi", + "version": "==3.15.0" }, "pyflakes": { "hashes": [ @@ -855,101 +885,54 @@ }, "pylint": { "hashes": [ - "sha256:549261e0762c3466cc001024c4419c08252cb8c8d40f5c2c6966fea690e7fe2a", - "sha256:bb71e6d169506de585edea997e48d9ff20c0dc0e2fbc1d166bad6b640120326b" + "sha256:47705453aa9dce520e123a7d51843d5f0032cbfa06870f89f00927aa1f735a4a", + "sha256:89b61867db16eefb7b3c5b84afc94081edaf11544189e2b238154677529ad69f" ], "index": "pypi", - "version": "==2.14.1" + "version": "==2.14.4" }, "pyopencl": { "hashes": [ - "sha256:01030054c201b021715deb3d6f1355844f9795429dfa0591b59b6f8000ec2d38", - "sha256:02997935ac164f519be65c371f9dd2267a2b7532247dc0a2ef43f435cf76cf4b", - "sha256:07482df440e1246cba6dc46ef70d3ebf1a6c8157a3c6456091026c7f9e4d18d2", - "sha256:0b179591c60b4446846fbea035cb3d1acd2685b0226ba91724109882dc59af2c", - "sha256:15ebc3f3eb2df1d196a7dcefd68d0e9ffa11e275f8a6c57a1145a1d0ff36c382", - "sha256:1a5fb7dc32cf24cdeab1205bc075710d7112656720c2bf9972bebe906e28ec4b", - "sha256:1b649637d608e8dabdec0e0f85392f727fdf622463b425cf7587bdd313b4d9eb", - "sha256:22eed49903178bc686287192a8319ce763129b4e5d42a9dfb5d8f763ba5d6bd6", - "sha256:2deef59d73d0bdd11ba40613ab0798c767214a669a1a5a672500787fb7da63d3", - "sha256:3736bfdc946068be66fe4b5c680926c84366b724b3c4b649b2a1940f7bd6afde", - "sha256:3dd0b5ff24d12ad4c13446d8e5439e63914496dfcf9e23a26baeaa65ec3c7039", - "sha256:5430b938e9391309be2ffaefb6269a0a3c016af5d729121cf8a5fce62a5146c2", - "sha256:5e89596e7f18824fc1f84e2cb0ae059fbfe187d1e2e3919ab0cd701cc634eb03", - "sha256:65e406603fbe47ca72298e022a3c3855b2e1732cb9d04ecbb411025050d0bc57", - "sha256:6f9f91594358af6a9728908c31c5ed4bec3fe1a0d25c6292e37e40c92903fe36", - "sha256:77a70b76789aac85566cb0e3ff6b60c4c00729bbd7f0edd24ac4b3b43e4627e2", - "sha256:799355c27463bf801260e3398643c3c9359627fa9e6ac621cfb5dc1d6e77d859", - "sha256:7ae4825562f7c5956b8926cb99882df1631c5e28aa1310d896c22a8471cf8f56", - "sha256:7b17906a4821a30aa1ce7a9d783bba2564230ea6a55ff31eb3f0e2a4aa5b80af", - "sha256:7d4bf4c858554e9e3af9e7f18b06e8d6c39b25d7a80c28db6e5dd412dc457aee", - "sha256:8981a9274796272508158b08a3cb1a5711318cf32b5f0e4829edecb1a9efcf93", - "sha256:8da3ef5a03cfd0a9859a5ebe623f3c43037e9f0dffd2b658e944bbc381beb529", - "sha256:94c744997f4aff86e68fa3a5d383dc8b5f1e529a360156b82c7583a757eddaa5", - "sha256:9a7fb5769bce7ec09a2d264a233ec9c730b15b391c830d04a381df3fc85bdaca", - "sha256:a6ce276a42caedd3a9a7be00031cfe6bf5d1796efdac40e47f1b707846c96d86", - "sha256:a84310ae508f998ed31825b6e3ab888098cb69a2c627bf5970706620a8d4b127", - "sha256:ad08e37cdeda5d38ac3ca9820400da62ce3a67aab76a5eefa5d089ef3a4877c9", - "sha256:b6e426b5fdce61051b112825da20df4cb78429967e491223bfedaf95c025273a", - "sha256:bb363f9993013b04c0b146e269a73b3d5ebef30f78d5fa542f317cc2440e15b6", - "sha256:c58f05b050ae4ac3b0584d97738ae7ac4381e611567b9d67fe7cf4210c0a7b62", - "sha256:c84ef85cf6b83dbcef4e034390fc1ed6bd8eadf5260b5ae89515d3b9744ef207", - "sha256:c9a841b80ef4c332a6133377fc295fe5376f90f8f2e7c63d36903b07b8ea7262", - "sha256:cd5871aff617d3c9d338fd94c9187382390db82452be0868055b8c519a73445d", - "sha256:cf45c232bf818ef54ee831eb41f4edbd5dfe4c67d894b1e65fc17a690a63c81e", - "sha256:e90bd1ed69cca2a750ffabafc70b4f9eb4d109299e986c3c8fdc4c40fee36ef2", - "sha256:ea5b6ef0e4ad23a3ccbdb382f7cccadbb200a47ceb6ff3e965a3c6c46360b4c2", - "sha256:f433ddd7bfd688b591ea95b6971e5e6cb00f8d5f2dc5db833e528e5ede6909d6" - ], - "index": "pypi", - "version": "==2022.1.5" - }, - "pyqt5": { - "hashes": [ - "sha256:213bebd51821ed89b4d5b35bb10dbe67564228b3568f463a351a08e8b1677025", - "sha256:2a69597e0dd11caabe75fae133feca66387819fc9bc050f547e5551bce97e5be", - "sha256:883a549382fc22d29a0568f3ef20b38c8e7ab633a59498ac4eb63a3bf36d3fd3", - "sha256:8c0848ba790a895801d5bfd171da31cad3e551dbcc4e59677a3b622de2ceca98", - "sha256:a88526a271e846e44779bb9ad7a738c6d3c4a9d01e15a128ecfc6dd4696393b7" - ], - "index": "pypi", - "version": "==5.15.4" - }, - "pyqt5-qt5": { - "hashes": [ - "sha256:1988f364ec8caf87a6ee5d5a3a5210d57539988bf8e84714c7d60972692e2f4a", - "sha256:750b78e4dba6bdf1607febedc08738e318ea09e9b10aea9ff0d73073f11f6962", - "sha256:76980cd3d7ae87e3c7a33bfebfaee84448fd650bad6840471d6cae199b56e154", - "sha256:9cc7a768b1921f4b982ebc00a318ccb38578e44e45316c7a4a850e953e1dd327" - ], - "version": "==5.15.2" - }, - "pyqt5-sip": { - "hashes": [ - "sha256:055581c6fed44ba4302b70eeb82e979ff70400037358908f251cd85cbb3dbd93", - "sha256:0fc9aefacf502696710b36cdc9fa2a61487f55ee883dbcf2c2a6477e261546f7", - "sha256:42274a501ab4806d2c31659170db14c282b8313d2255458064666d9e70d96206", - "sha256:4347bd81d30c8e3181e553b3734f91658cfbdd8f1a19f254777f906870974e6d", - "sha256:485972daff2fb0311013f471998f8ec8262ea381bded244f9d14edaad5f54271", - "sha256:4f8e05fe01d54275877c59018d8e82dcdd0bc5696053a8b830eecea3ce806121", - "sha256:69a3ad4259172e2b1aa9060de211efac39ddd734a517b1924d9c6c0cc4f55f96", - "sha256:6a8701892a01a5a2a4720872361197cc80fdd5f49c8482d488ddf38c9c84f055", - "sha256:6d5bca2fc222d58e8093ee8a81a6e3437067bb22bc3f86d06ec8be721e15e90a", - "sha256:83c3220b1ca36eb8623ba2eb3766637b19eb0ce9f42336ad8253656d32750c0a", - "sha256:a25b9843c7da6a1608f310879c38e6434331aab1dc2fe6cb65c14f1ecf33780e", - "sha256:ac57d796c78117eb39edd1d1d1aea90354651efac9d3590aac67fa4983f99f1f", - "sha256:b09f4cd36a4831229fb77c424d89635fa937d97765ec90685e2f257e56a2685a", - "sha256:c446971c360a0a1030282a69375a08c78e8a61d568bfd6dab3dcc5cf8817f644", - "sha256:c5216403d4d8d857ec4a61f631d3945e44fa248aa2415e9ee9369ab7c8a4d0c7", - "sha256:d3e4489d7c2b0ece9d203ae66e573939f7f60d4d29e089c9f11daa17cfeaae32", - "sha256:d59af63120d1475b2bf94fe8062610720a9be1e8940ea146c7f42bb449d49067", - "sha256:d85002238b5180bce4b245c13d6face848faa1a7a9e5c6e292025004f2fd619a", - "sha256:d8b2bdff7bbf45bc975c113a03b14fd669dc0c73e1327f02706666a7dd51a197", - "sha256:dd05c768c2b55ffe56a9d49ce6cc77cdf3d53dbfad935258a9e347cbfd9a5850", - "sha256:fc43f2d7c438517ee33e929e8ae77132749c15909afab6aeece5fcf4147ffdb5" - ], - "index": "pypi", - "version": "==12.9.0" + "sha256:069e7eb1a223d88c13eafa54d6ae896fa892e75ba3d56ff2135a26107ef1142b", + "sha256:1490e6cdeaecba42854013c273685d65fd9102ee6dc6bc3bcb814e9e2b8179e5", + "sha256:15f7b3d29c9359e1e440e4f52f70de031f8d0d8d0f8de53a3bc01501b89360c0", + "sha256:1a2029b7fda6709eca077f618f997372c3d6f2780ad45512632b0d056e6305f9", + "sha256:25e87b4ccc0cc53487d445bea07ce9bdb478a335725df16986aead2ff65b68a4", + "sha256:2c9ad1cbc3f540afc52038851be8e06640aacfece051c89408bc3aece605a7ee", + "sha256:2df01c95ea9ae3dd66b277f0df47144cf7535a27b48a8d49fdd98e0583e368ce", + "sha256:316f59d0c40bfce4f6c160dbaf6501883b33880370bb1819f360dad747e52dfe", + "sha256:4836bc4619be967d6c28627adac151223037fdca056c4ab54da16b591f719347", + "sha256:4b53f7f3ed85ab671c8bfc61a0bbc5476725a7a5f51a94bba5512c3962b2d609", + "sha256:5304cb336af7316ae0650abb7467c076032635bfe4710b8df191612d245dca28", + "sha256:55e9302b8f0b1964c87b0fdab7b853aa2b2f10b4188f5b4618782d4380448c11", + "sha256:6032bef8a35f6df727a0b66e3c9faedb3f560318052848b28d2f72622cfbeace", + "sha256:6ec55934057e99461f684ccd293d87db59a452f5834c13ae36b19d31dfe38599", + "sha256:7176f96728be9b43024bd71704f60849cbfcf0fafd20270181b68ea4730ceb2d", + "sha256:730901d409d8251cd6e9dc59e6c518dff5cdb20a3a0b728344bfd2c707f28b64", + "sha256:75be43c7f33fb86f9d18b7b6f8e9081d8bd5b6331a90aec0d2cad3e81e72bc8f", + "sha256:7bef8e8bcfff574b481565390113ea0a37cf33fd2587ade7f2980f15e73f7b08", + "sha256:7ca9597877e1f8bdb4a49810988230f538b2d7aac389c33418a21cf4358f2fd4", + "sha256:814389b3eb9e6930cf43b984283c94a955edf20ec286402da5acfa503d3ae790", + "sha256:8efc3467454ce8c644f09029a3308496f9cb6e93ca5e8c08f6b79e7825da72c5", + "sha256:98bad7035f27b6de5c9268f52c1e10bffe3a2874994e862468a1792b699a4884", + "sha256:9bbfe94bb6e9d0458693183334e73c973e2fcba01568f42db15b453b926fb816", + "sha256:9d112a4426f5b356641c1312bf1004247dc4019e649502589b86333557203c01", + "sha256:a845779f505ed57b83f279307ae6307d886f3e41fb24dcf7889da27daa726118", + "sha256:aca3581f1a7f6b809b8cdc78b0e66587848b38b143bf2983e91ff8fb9a41bc8f", + "sha256:af5664b98140a29966c5fb12e9d29b85b6c6310efa97d82aee58310774917e8f", + "sha256:b85fa5ba1678dd40713587fd437787b6aa940000c2ddffa360884431be21723a", + "sha256:bcabfb5217ca8f8770f9c69298f79576080bb994b1883a99494b4c2668b04836", + "sha256:c00989bed1e7e5b32ad498fec3deb1c93403ab802cd99b7c78b9c692bd0910ef", + "sha256:d0ddc3b74ad1804eb3fe238dfa3b844b997e88b1ca5164a717c16b362b4f34c3", + "sha256:d8bb2eea4e960917e0a6132dedd34c8ec0b7a384f22713f775d50dbce154263a", + "sha256:db833ebb1e756969a8f851f15486598eb9e3fb27b0535c2a8193cc1c71455016", + "sha256:dc2d78cb5da0081ada1c263aaa773fd5479b3da5e2c421547bf7f3258d3239a5", + "sha256:dd2728e59ae088c900ed68f68d953476d0ff07189f182f917b74de2ac7b3972e", + "sha256:ea4eff6b922fa4ad2077ef90b3254d78597d050ada09bfbe74c22dd22d10c6ac", + "sha256:f8887d54e654598f3854472540b2eb228ac56b56a2491b95bdfac8f15be1c943" + ], + "index": "pypi", + "version": "==2022.1.6" }, "pyserial": { "hashes": [ @@ -969,10 +952,10 @@ }, "pytools": { "hashes": [ - "sha256:3393d25029982080e3fb94c47bf627a1e553ccd174fe2edef6c1c5ec723918ff" + "sha256:4d62875e9a2ab2a24e393a9a8b799492f1a721bffa840af3807bfd42871dd1f4" ], "markers": "python_version ~= '3.6'", - "version": "==2022.1.9" + "version": "==2022.1.12" }, "pyyaml": { "hashes": [ @@ -1015,74 +998,74 @@ }, "pyzmq": { "hashes": [ - "sha256:057176dd3f5ccf5aad4abd662d76b6a39bbf799baaf2f39cd4fdaf2eab326e43", - "sha256:05ec90a8da618f2398f9d1aa20b18a9ef332992c6ac23e8c866099faad6ef0d6", - "sha256:154de02b15422af28b53d29a02de72121ba503634955017255573fc1f995143d", - "sha256:16b832adb5d8716f46051da5533c480250bf126984ce86804db6137a3a7f931b", - "sha256:1df26aa854bdd3a8341bf199064dd6aa6e240f2eaa3c9fa8d217e5d8b868c73e", - "sha256:28f9164fb2658b7b414fa0894c75b1a9c61375774cdc1bdb7298beb042a2cd87", - "sha256:2951c29b8649f3672af9dca8ff61d86310d3664d9629788b1c66422fb13b1239", - "sha256:2b08774057ae7ce8a2eb4e7d54db05358234440706ce43a85814500c5d7bd22e", - "sha256:2e2ac40f7a91c740ec68d6db07ae19ea9259c959333c68bee56ab2c799a67d66", - "sha256:312e56799410c34797417a4060a8bd37d4db1f06d1ec0c54f7c8fd81e0d90376", - "sha256:38f778a74e3889392e949326cfd0e9b2eb37dcbb2980d98fad2c51703d523db2", - "sha256:3955dd5bbbe02f454655296ee36a66c334c7102a29b8458223d168c0380edfd5", - "sha256:425ba851a6f9892bde1da2024d82e2fe6796bd77e3391fb96665c50fe9d4c6a5", - "sha256:48bbc2db041ab28eeee4a3e8ada0ed336640946dd5a8e53dbd3805f9dbdcf0dc", - "sha256:4fbcd657cda75574fd1315a4c44bd322bc2e219039fb09f146bbe6f8aef039e9", - "sha256:523ba7fd4d8fe75ad09c1e574a648892b75a97d0cfc8005727681053ac19555b", - "sha256:53b2c1326c2e484d450932d2be739f064b7cb572faabec38386098a28516a529", - "sha256:540d7146c3cdc9bbffab039ea067f494eba24d1abe5bd33eb9f963c01e3305d4", - "sha256:563d4281c4dbdf647d93114420151d33f895afc4c46b7115a67a0aa5347e6624", - "sha256:67a049bcf967a39993858beed873ed3405536019820922d4efacfe35ab3da51a", - "sha256:67ec63ae3c9c1fa2e077fcb42e77035e2121a04f987464bdf9945a28535d30ad", - "sha256:68e22c5d3be451e87d47f956b397a7823bfbde2176341bc902fba30f96831d7e", - "sha256:6ab4b6108e69f63c917cd7ef7217c5727955b1ac90600e44a13ed5312019a014", - "sha256:6bd7f18bd4cf51ea8d7e54825902cf36f9d2f35cc51ef618373988d5398b8dd0", - "sha256:6cd53e861bccc0bdc4620f68fb4a91d5bcfe9f4213cf8e200fa498044d33a6dc", - "sha256:6d346e551fa64b89d57a4ac74b9bc66703413f02f50093e089e861999ec5cccc", - "sha256:6ff8708fabc9f9bc2949f457d39b4088c9656c4c9ac15fbbbbaafce8f6d07833", - "sha256:7626e8384275a7dea6f3d1f749fb5e00299042e9c895fc3dbe24cb154909c242", - "sha256:7e7346b2b33dcd4a2171dd8a9870ae283eec8f6231dcbcf237a0f41e74751a50", - "sha256:81623c67cb71b93b5f7e06c9107f3781738ae86866db830c950223d87af2a235", - "sha256:83f1c76068faf62c32a36dd62dc4db642c2027bbbd960f8f6345b59e9d4dc472", - "sha256:8679bb1dd723ecbea03b1f96c98972815775fd8ec756c440a14f289c436c472e", - "sha256:86fb683cb9a9c0bb7476988b7957393ecdd22777d87d804442c66e62c99197f9", - "sha256:8757c62f7960cd26122f7aaaf86eda1e016fa85734c3777b8054dd334d7dea4d", - "sha256:894be7d17228e7328cc188096c0162697211ec91761f6812fff12790cbe11c66", - "sha256:8a0f240bf43c29be1bd82d77e602a61c798e9de02e5f8bb7bb414cb814f43236", - "sha256:8c3abf7eab5b76ae162c4fbb16d514a947fc57fd995b64e5ea8ef8ba3b888a69", - "sha256:93332c6972e4c91522c4810e907f3aea067424338071161b39cacded022559df", - "sha256:97d6c676dc97d593625d9fc48154f2ffeabb619a1e6fe8d2a5b53f97e3e9bdee", - "sha256:99dd85f0ca1db8d17a01a25c2bbb7784d25a2d39497c6beddbe96bff74194e04", - "sha256:9c7fb691fb07ec7ab99fd173bb0e7e0248d31bf83d484a87b917a342f63812c9", - "sha256:b3bc3cf200aab74f3d758586ac50295214eda496ac6a6636e0c881c5958d9123", - "sha256:bba54f97578943f48f621b4a7afb8eb022370da26a88b88ccc9fee9f3ef7ce45", - "sha256:bd2a13a0f8367e50347cbac87ae230ae1953935443240238f956bf10668bead6", - "sha256:cbc1184349ca6e5112898aa7fc3efa1b1bbae24ab1edc774cfd09cbfd3b091d7", - "sha256:cd82cca9c489e441574804dbda2dd8e114cf3be7935b03de11dade2c9478aea6", - "sha256:ce8ba5ed8b0a7a203922d61cff45ee6001a41a9359f04f00d055a4e988755569", - "sha256:cfee22e072a382b92ee0709dbb8203dabd52d54258051e770d9d2a81b162530b", - "sha256:d977df6f7c4109ed1d96ffb6795f6af77114be606ae4556efbfc9cac725db65d", - "sha256:da72a384a1d7e87490ca71182f3ab469ed21d847adc16b70c34faac5a3b12801", - "sha256:ddf4ad1d651e6c9234945061e1a31fe27a4be0dea21c498b87b186fadf8f5919", - "sha256:eb0ae5dfda83bbce660179d7b41c1c38fd833a54d2e6d9b258c644f3b75ef94d", - "sha256:f4c7d370badc60ac94a554bc571a46d03e39d8aacfba8006b334512e184aed59", - "sha256:f6c378b435a26fda8996579c0e324b108d2ca0d01b4661503a75634e5155559f", - "sha256:f6c9d30888503f2f5f87d6d41f016301352dd98da4a861bd10663c3a2d99d3b5", - "sha256:fab8a7877275060f7b303e1f91c218069a2814a616b6a5ee2d8a3737deb15915", - "sha256:fc32e7d7f98cac3d8d5153ed2cb583158ae3d446a6efb8e28ccb1c54a09f4169" - ], - "index": "pypi", - "version": "==23.1.0" + "sha256:004a431dfa0459123e6f4660d7e3c4ac19217d134ca38bacfffb2e78716fe944", + "sha256:057b154471e096e2dda147f7b057041acc303bb7ca4aa24c3b88c6cecdd78717", + "sha256:0e08671dc202a1880fa522f921f35ca5925ba30da8bc96228d74a8f0643ead9c", + "sha256:1b2a21f595f8cc549abd6c8de1fcd34c83441e35fb24b8a59bf161889c62a486", + "sha256:21552624ce69e69f7924f413b802b1fb554f4c0497f837810e429faa1cd4f163", + "sha256:22ac0243a41798e3eb5d5714b28c2f28e3d10792dffbc8a5fca092f975fdeceb", + "sha256:2b054525c9f7e240562185bf21671ca16d56bde92e9bd0f822c07dec7626b704", + "sha256:30c365e60c39c53f8eea042b37ea28304ffa6558fb7241cf278745095a5757da", + "sha256:3a4d87342c2737fbb9eee5c33c792db27b36b04957b4e6b7edd73a5b239a2a13", + "sha256:420b9abd1a7330687a095373b8280a20cdee04342fbc8ccb3b56d9ec8efd4e62", + "sha256:444f7d615d5f686d0ef508b9edfa8a286e6d89f449a1ba37b60ef69d869220a3", + "sha256:558f5f636e3e65f261b64925e8b190e8689e334911595394572cc7523879006d", + "sha256:5592fb4316f895922b1cacb91b04a0fa09d6f6f19bbab4442b4d0a0825177b93", + "sha256:59928dfebe93cf1e203e3cb0fd5d5dd384da56b99c8305f2e1b0a933751710f6", + "sha256:5cb642e94337b0c76c9c8cb9bfb0f8a78654575847d080d3e1504f312d691fc3", + "sha256:5d57542429df6acff02ff022067aa75b677603cee70e3abb9742787545eec966", + "sha256:5d92e7cbeab7f70b08cc0f27255b0bb2500afc30f31075bca0b1cb87735d186c", + "sha256:602835e5672ca9ca1d78e6c148fb28c4f91b748ebc41fbd2f479d8763d58bc9b", + "sha256:60746a7e8558655420a69441c0a1d47ed225ed3ac355920b96a96d0554ef7e6b", + "sha256:61b97f624da42813f74977425a3a6144d604ea21cf065616d36ea3a866d92c1c", + "sha256:693c96ae4d975eb8efa1639670e9b1fac0c3f98b7845b65c0f369141fb4bb21f", + "sha256:814e5aaf0c3be9991a59066eafb2d6e117aed6b413e3e7e9be45d4e55f5e2748", + "sha256:83005d8928f8a5cebcfb33af3bfb84b1ad65d882b899141a331cc5d07d89f093", + "sha256:831da96ba3f36cc892f0afbb4fb89b28b61b387261676e55d55a682addbd29f7", + "sha256:8355744fdbdeac5cfadfa4f38b82029b5f2b8cab7472a33453a217a7f3a9dce2", + "sha256:8496a2a5efd055c61ac2c6a18116c768a25c644b6747dcfde43e91620ab3453c", + "sha256:859059caf564f0c9398c9005278055ed3d37af4d73de6b1597821193b04ca09b", + "sha256:8c0f4d6f8c985bab83792be26ff3233940ba42e22237610ac50cbcfc10a5c235", + "sha256:8c2d8b69a2bf239ae3d987537bf3fbc2b044a405394cf4c258fc684971dd48b2", + "sha256:984b232802eddf9f0be264a4d57a10b3a1fd7319df14ee6fc7b41c6d155a3e6c", + "sha256:99cedf38eaddf263cf7e2a50e405f12c02cedf6d9df00a0d9c5d7b9417b57f76", + "sha256:a3dc339f7bc185d5fd0fd976242a5baf35de404d467e056484def8a4dd95868b", + "sha256:a51f12a8719aad9dcfb55d456022f16b90abc8dde7d3ca93ce3120b40e3fa169", + "sha256:bbabd1df23bf63ae829e81200034c0e433499275a6ed29ca1a912ea7629426d9", + "sha256:bcc6953e47bcfc9028ddf9ab2a321a3c51d7cc969db65edec092019bb837959f", + "sha256:c0a5f987d73fd9b46c3d180891f829afda714ab6bab30a1218724d4a0a63afd8", + "sha256:c223a13555444707a0a7ebc6f9ee63053147c8c082bd1a31fd1207a03e8b0500", + "sha256:c616893a577e9d6773a3836732fd7e2a729157a108b8fccd31c87512fa01671a", + "sha256:c882f1d4f96fbd807e92c334251d8ebd159a1ef89059ccd386ddea83fdb91bd8", + "sha256:c8dec8a2f3f0bb462e6439df436cd8c7ec37968e90b4209ac621e7fbc0ed3b00", + "sha256:c9638e0057e3f1a8b7c5ce33c7575349d9183a033a19b5676ad55096ae36820b", + "sha256:ce4f71e17fa849de41a06109030d3f6815fcc33338bf98dd0dde6d456d33c929", + "sha256:ced12075cdf3c7332ecc1960f77f7439d5ebb8ea20bbd3c34c8299e694f1b0a1", + "sha256:d11628212fd731b8986f1561d9bb3f8c38d9c15b330c3d8a88963519fbcd553b", + "sha256:d1610260cc672975723fcf7705c69a95f3b88802a594c9867781bedd9b13422c", + "sha256:d4651de7316ec8560afe430fb042c0782ed8ac54c0be43a515944d7c78fddac8", + "sha256:da338e2728410d74ddeb1479ec67cfba73311607037455a40f92b6f5c62bf11d", + "sha256:de727ea906033b30527b4a99498f19aca3f4d1073230a958679a5b726e2784e0", + "sha256:e2e2db5c6ef376e97c912733dfc24406f5949474d03e800d5f07b6aca4d870af", + "sha256:e669913cb2179507628419ec4f0e453e48ce6f924de5884d396f18c31836089c", + "sha256:eb4a573a8499685d62545e806d8fd143c84ac8b3439f925cd92c8763f0ed9bd7", + "sha256:f146648941cadaaaf01254a75651a23c08159d009d36c5af42a7cc200a5e53ec", + "sha256:f3ff6abde52e702397949054cb5b06c1c75b5d6542f6a2ce029e46f71ffbbbf2", + "sha256:f5aa9da520e4bb8cee8189f2f541701405e7690745094ded7a37b425d60527ea", + "sha256:f5fdb00d65ec44b10cc6b9b6318ef1363b81647a4aa3270ca39565eadb2d1201", + "sha256:f685003d836ad0e5d4f08d1e024ee3ac7816eb2f873b2266306eef858f058133", + "sha256:fee86542dc4ee8229e023003e3939b4d58cc2453922cf127778b69505fc9064b" + ], + "index": "pypi", + "version": "==23.2.0" }, "requests": { "hashes": [ - "sha256:bc7861137fbce630f17b03d3ad02ad0bf978c844f3536d0edda6499dafce2b6f", - "sha256:d568723a7ebd25875d8d1eaf5dfa068cd2fc8194b2e483d7b1f7c81918dbec6b" + "sha256:7c5599b102feddaa661c826c56ab4fee28bfd17f5abca1ebbe3e7f19d7c97983", + "sha256:8fefa2a1a1365bf5520aac41836fbee479da67864514bdb821f31ce07ce65349" ], "index": "pypi", - "version": "==2.28.0" + "version": "==2.28.1" }, "scons": { "hashes": [ @@ -1094,11 +1077,11 @@ }, "sentry-sdk": { "hashes": [ - "sha256:259535ba66933eacf85ab46524188c84dcb4c39f40348455ce15e2c0aca68863", - "sha256:778b53f0a6c83b1ee43d3b7886318ba86d975e686cb2c7906ccc35b334360be1" + "sha256:b82ad57306d5546713f15d5d70daea0408cf7f998c7566db16e0e6257e51e561", + "sha256:ddbd191b6f4e696b7845b4d87389898ae1207981faf114f968a57363aa6be03c" ], "index": "pypi", - "version": "==1.5.12" + "version": "==1.6.0" }, "setproctitle": { "hashes": [ @@ -1179,11 +1162,11 @@ }, "setuptools": { "hashes": [ - "sha256:5a844ad6e190dccc67d6d7411d119c5152ce01f7c76be4d8a1eaa314501bba77", - "sha256:bf8a748ac98b09d32c9a64a995a6b25921c96cc5743c1efa82763ba80ff54e91" + "sha256:16923d366ced322712c71ccb97164d07472abeecd13f3a6c283f6d5d26722793", + "sha256:db3b8e2f922b2a910a29804776c643ea609badb6a32c4bcc226fd4fd902cce65" ], "markers": "python_version >= '3.7'", - "version": "==62.4.0" + "version": "==63.1.0" }, "six": { "hashes": [ @@ -1227,11 +1210,11 @@ }, "tomlkit": { "hashes": [ - "sha256:0f4050db66fd445b885778900ce4dd9aea8c90c4721141fde0d6ade893820ef1", - "sha256:71ceb10c0eefd8b8f11fe34e8a51ad07812cb1dc3de23247425fbc9ddc47b9dd" + "sha256:1c5bebdf19d5051e2e1de6cf70adfc5948d47221f097fcff7a3ffc91e953eaf5", + "sha256:61901f81ff4017951119cd0d1ed9b7af31c821d6845c8c477587bbdcd5e5854e" ], - "markers": "python_version >= '3.6' and python_version < '4.0'", - "version": "==0.11.0" + "markers": "python_version >= '3.6' and python_version < '4'", + "version": "==0.11.1" }, "tqdm": { "hashes": [ @@ -1243,19 +1226,19 @@ }, "typing-extensions": { "hashes": [ - "sha256:6657594ee297170d19f67d55c05852a874e7eb634f4f753dbd667855e07c1708", - "sha256:f1c24655a0da0d1b67f07e17a5e6b2a105894e6824b92096378bb3668ef02376" + "sha256:25642c956049920a5aa49edcdd6ab1e06d7e5d467fc00e0506c44ac86fbfca02", + "sha256:e6d2677a32f47fc7eb2795db1dd15c1f34eff616bcaf2cfb5e997f854fa1c4a6" ], - "markers": "python_version < '3.10'", - "version": "==4.2.0" + "markers": "python_version >= '3.7'", + "version": "==4.3.0" }, "urllib3": { "hashes": [ - "sha256:44ece4d53fb1706f667c9bd1c648f5469a2ec925fcf3a776667042d645472c14", - "sha256:aabaf16477806a5e1dd19aa41f8c2b7950dd3c746362d7e3223dbe6de6ac448e" + "sha256:8298d6d56d39be0e3bc13c1c97d133f9b45d797169a0e11cdd0e0489d786f7ec", + "sha256:879ba4d1e89654d9769ce13121e0f94310ea32e8d2f8cf587b77c08bbcdb30d6" ], "index": "pypi", - "version": "==1.26.9" + "version": "==1.26.10" }, "utm": { "hashes": [ @@ -1266,11 +1249,11 @@ }, "websocket-client": { "hashes": [ - "sha256:50b21db0058f7a953d67cc0445be4b948d7fc196ecbeb8083d68d94628e4abf6", - "sha256:722b171be00f2b90e1d4fb2f2b53146a536ca38db1da8ff49c972a4e1365d0ef" + "sha256:5d55652dc1d0b3c734f044337d929aaf83f4f9138816ec680c1aefefb4dc4877", + "sha256:d58c5f284d6a9bf8379dab423259fe8f85b70d5fa5d2916d5791a84594b122b1" ], "index": "pypi", - "version": "==1.3.2" + "version": "==1.3.3" }, "werkzeug": { "hashes": [ @@ -1443,11 +1426,11 @@ }, "babel": { "hashes": [ - "sha256:7aed055f0c04c9e7f51a2f75261e41e1c804efa724cb65b60a970dd4448d469d", - "sha256:81a3beca4d0cd40a9cfb9e2adb2cf39261c2f959b92e7a74750befe5d79afd7b" + "sha256:7614553711ee97490f732126dc077f8d0ae084ebc6a96e23db1482afabdb2c51", + "sha256:ff56f4892c1c4bf0d814575ea23471c230d544203c7748e8c68f0089478d48eb" ], "markers": "python_version >= '3.6'", - "version": "==2.10.2" + "version": "==2.10.3" }, "bcrypt": { "hashes": [ @@ -1468,11 +1451,11 @@ }, "breathe": { "hashes": [ - "sha256:553aeffb00efc2cf96c4c9ed388d6ee8036ecd6d1bd9bd0c656fc25ca271bd3c", - "sha256:c4b9ff4d5298fd91518d336ede28b6a2d8cacc685d0eae17eb20e760e06bb904" + "sha256:48804dcf0e607a89fb6ad88c729ef12743a42db03ae9489be4ef8f7c4011774a", + "sha256:ac0768a5e84addad3e632028fe67749c567aba2b29088493b64c2c1634bcdba1" ], "index": "pypi", - "version": "==4.33.1" + "version": "==4.34.0" }, "carla": { "hashes": [ @@ -1490,67 +1473,81 @@ }, "certifi": { "hashes": [ - "sha256:9c5705e395cd70084351dd8ad5c41e65655e08ce46f2ec9cf6c2c08390f71eb7", - "sha256:f1d53542ee8cbedbe2118b5686372fb33c297fcd6379b050cca0ef13a597382a" + "sha256:84c85a9078b11105f04f3036a9482ae10e4621616db313fe045dd24743a0820d", + "sha256:fe86415d55e84719d75f8b69414f6438ac3547d2078ab91b67e779ef69378412" ], "markers": "python_version >= '3.6'", - "version": "==2022.5.18.1" + "version": "==2022.6.15" }, "cffi": { "hashes": [ - "sha256:00c878c90cb53ccfaae6b8bc18ad05d2036553e6d9d1d9dbcf323bbe83854ca3", - "sha256:0104fb5ae2391d46a4cb082abdd5c69ea4eab79d8d44eaaf79f1b1fd806ee4c2", - "sha256:06c48159c1abed75c2e721b1715c379fa3200c7784271b3c46df01383b593636", - "sha256:0808014eb713677ec1292301ea4c81ad277b6cdf2fdd90fd540af98c0b101d20", - "sha256:10dffb601ccfb65262a27233ac273d552ddc4d8ae1bf93b21c94b8511bffe728", - "sha256:14cd121ea63ecdae71efa69c15c5543a4b5fbcd0bbe2aad864baca0063cecf27", - "sha256:17771976e82e9f94976180f76468546834d22a7cc404b17c22df2a2c81db0c66", - "sha256:181dee03b1170ff1969489acf1c26533710231c58f95534e3edac87fff06c443", - "sha256:23cfe892bd5dd8941608f93348c0737e369e51c100d03718f108bf1add7bd6d0", - "sha256:263cc3d821c4ab2213cbe8cd8b355a7f72a8324577dc865ef98487c1aeee2bc7", - "sha256:2756c88cbb94231c7a147402476be2c4df2f6078099a6f4a480d239a8817ae39", - "sha256:27c219baf94952ae9d50ec19651a687b826792055353d07648a5695413e0c605", - "sha256:2a23af14f408d53d5e6cd4e3d9a24ff9e05906ad574822a10563efcef137979a", - "sha256:31fb708d9d7c3f49a60f04cf5b119aeefe5644daba1cd2a0fe389b674fd1de37", - "sha256:3415c89f9204ee60cd09b235810be700e993e343a408693e80ce7f6a40108029", - "sha256:3773c4d81e6e818df2efbc7dd77325ca0dcb688116050fb2b3011218eda36139", - "sha256:3b96a311ac60a3f6be21d2572e46ce67f09abcf4d09344c49274eb9e0bf345fc", - "sha256:3f7d084648d77af029acb79a0ff49a0ad7e9d09057a9bf46596dac9514dc07df", - "sha256:41d45de54cd277a7878919867c0f08b0cf817605e4eb94093e7516505d3c8d14", - "sha256:4238e6dab5d6a8ba812de994bbb0a79bddbdf80994e4ce802b6f6f3142fcc880", - "sha256:45db3a33139e9c8f7c09234b5784a5e33d31fd6907800b316decad50af323ff2", - "sha256:45e8636704eacc432a206ac7345a5d3d2c62d95a507ec70d62f23cd91770482a", - "sha256:4958391dbd6249d7ad855b9ca88fae690783a6be9e86df65865058ed81fc860e", - "sha256:4a306fa632e8f0928956a41fa8e1d6243c71e7eb59ffbd165fc0b41e316b2474", - "sha256:57e9ac9ccc3101fac9d6014fba037473e4358ef4e89f8e181f8951a2c0162024", - "sha256:59888172256cac5629e60e72e86598027aca6bf01fa2465bdb676d37636573e8", - "sha256:5e069f72d497312b24fcc02073d70cb989045d1c91cbd53979366077959933e0", - "sha256:64d4ec9f448dfe041705426000cc13e34e6e5bb13736e9fd62e34a0b0c41566e", - "sha256:6dc2737a3674b3e344847c8686cf29e500584ccad76204efea14f451d4cc669a", - "sha256:74fdfdbfdc48d3f47148976f49fab3251e550a8720bebc99bf1483f5bfb5db3e", - "sha256:75e4024375654472cc27e91cbe9eaa08567f7fbdf822638be2814ce059f58032", - "sha256:786902fb9ba7433aae840e0ed609f45c7bcd4e225ebb9c753aa39725bb3e6ad6", - "sha256:8b6c2ea03845c9f501ed1313e78de148cd3f6cad741a75d43a29b43da27f2e1e", - "sha256:91d77d2a782be4274da750752bb1650a97bfd8f291022b379bb8e01c66b4e96b", - "sha256:91ec59c33514b7c7559a6acda53bbfe1b283949c34fe7440bcf917f96ac0723e", - "sha256:920f0d66a896c2d99f0adbb391f990a84091179542c205fa53ce5787aff87954", - "sha256:a5263e363c27b653a90078143adb3d076c1a748ec9ecc78ea2fb916f9b861962", - "sha256:abb9a20a72ac4e0fdb50dae135ba5e77880518e742077ced47eb1499e29a443c", - "sha256:c2051981a968d7de9dd2d7b87bcb9c939c74a34626a6e2f8181455dd49ed69e4", - "sha256:c21c9e3896c23007803a875460fb786118f0cdd4434359577ea25eb556e34c55", - "sha256:c2502a1a03b6312837279c8c1bd3ebedf6c12c4228ddbad40912d671ccc8a962", - "sha256:d4d692a89c5cf08a8557fdeb329b82e7bf609aadfaed6c0d79f5a449a3c7c023", - "sha256:da5db4e883f1ce37f55c667e5c0de439df76ac4cb55964655906306918e7363c", - "sha256:e7022a66d9b55e93e1a845d8c9eba2a1bebd4966cd8bfc25d9cd07d515b33fa6", - "sha256:ef1f279350da2c586a69d32fc8733092fd32cc8ac95139a00377841f59a3f8d8", - "sha256:f54a64f8b0c8ff0b64d18aa76675262e1700f3995182267998c31ae974fbc382", - "sha256:f5c7150ad32ba43a07c4479f40241756145a1f03b43480e058cfd862bf5041c7", - "sha256:f6f824dc3bce0edab5f427efcfb1d63ee75b6fcb7282900ccaf925be84efb0fc", - "sha256:fd8a250edc26254fe5b33be00402e6d287f562b6a5b2152dec302fa15bb3e997", - "sha256:ffaa5c925128e29efbde7301d8ecaf35c8c60ffbcd6a1ffd3a552177c8e5e796" - ], - "index": "pypi", - "version": "==1.15.0" + "sha256:00a9ed42e88df81ffae7a8ab6d9356b371399b91dbdf0c3cb1e84c03a13aceb5", + "sha256:03425bdae262c76aad70202debd780501fabeaca237cdfddc008987c0e0f59ef", + "sha256:04ed324bda3cda42b9b695d51bb7d54b680b9719cfab04227cdd1e04e5de3104", + "sha256:0e2642fe3142e4cc4af0799748233ad6da94c62a8bec3a6648bf8ee68b1c7426", + "sha256:173379135477dc8cac4bc58f45db08ab45d228b3363adb7af79436135d028405", + "sha256:198caafb44239b60e252492445da556afafc7d1e3ab7a1fb3f0584ef6d742375", + "sha256:1e74c6b51a9ed6589199c787bf5f9875612ca4a8a0785fb2d4a84429badaf22a", + "sha256:2012c72d854c2d03e45d06ae57f40d78e5770d252f195b93f581acf3ba44496e", + "sha256:21157295583fe8943475029ed5abdcf71eb3911894724e360acff1d61c1d54bc", + "sha256:2470043b93ff09bf8fb1d46d1cb756ce6132c54826661a32d4e4d132e1977adf", + "sha256:285d29981935eb726a4399badae8f0ffdff4f5050eaa6d0cfc3f64b857b77185", + "sha256:30d78fbc8ebf9c92c9b7823ee18eb92f2e6ef79b45ac84db507f52fbe3ec4497", + "sha256:320dab6e7cb2eacdf0e658569d2575c4dad258c0fcc794f46215e1e39f90f2c3", + "sha256:33ab79603146aace82c2427da5ca6e58f2b3f2fb5da893ceac0c42218a40be35", + "sha256:3548db281cd7d2561c9ad9984681c95f7b0e38881201e157833a2342c30d5e8c", + "sha256:3799aecf2e17cf585d977b780ce79ff0dc9b78d799fc694221ce814c2c19db83", + "sha256:39d39875251ca8f612b6f33e6b1195af86d1b3e60086068be9cc053aa4376e21", + "sha256:3b926aa83d1edb5aa5b427b4053dc420ec295a08e40911296b9eb1b6170f6cca", + "sha256:3bcde07039e586f91b45c88f8583ea7cf7a0770df3a1649627bf598332cb6984", + "sha256:3d08afd128ddaa624a48cf2b859afef385b720bb4b43df214f85616922e6a5ac", + "sha256:3eb6971dcff08619f8d91607cfc726518b6fa2a9eba42856be181c6d0d9515fd", + "sha256:40f4774f5a9d4f5e344f31a32b5096977b5d48560c5592e2f3d2c4374bd543ee", + "sha256:4289fc34b2f5316fbb762d75362931e351941fa95fa18789191b33fc4cf9504a", + "sha256:470c103ae716238bbe698d67ad020e1db9d9dba34fa5a899b5e21577e6d52ed2", + "sha256:4f2c9f67e9821cad2e5f480bc8d83b8742896f1242dba247911072d4fa94c192", + "sha256:50a74364d85fd319352182ef59c5c790484a336f6db772c1a9231f1c3ed0cbd7", + "sha256:54a2db7b78338edd780e7ef7f9f6c442500fb0d41a5a4ea24fff1c929d5af585", + "sha256:5635bd9cb9731e6d4a1132a498dd34f764034a8ce60cef4f5319c0541159392f", + "sha256:59c0b02d0a6c384d453fece7566d1c7e6b7bae4fc5874ef2ef46d56776d61c9e", + "sha256:5d598b938678ebf3c67377cdd45e09d431369c3b1a5b331058c338e201f12b27", + "sha256:5df2768244d19ab7f60546d0c7c63ce1581f7af8b5de3eb3004b9b6fc8a9f84b", + "sha256:5ef34d190326c3b1f822a5b7a45f6c4535e2f47ed06fec77d3d799c450b2651e", + "sha256:6975a3fac6bc83c4a65c9f9fcab9e47019a11d3d2cf7f3c0d03431bf145a941e", + "sha256:6c9a799e985904922a4d207a94eae35c78ebae90e128f0c4e521ce339396be9d", + "sha256:70df4e3b545a17496c9b3f41f5115e69a4f2e77e94e1d2a8e1070bc0c38c8a3c", + "sha256:7473e861101c9e72452f9bf8acb984947aa1661a7704553a9f6e4baa5ba64415", + "sha256:8102eaf27e1e448db915d08afa8b41d6c7ca7a04b7d73af6514df10a3e74bd82", + "sha256:87c450779d0914f2861b8526e035c5e6da0a3199d8f1add1a665e1cbc6fc6d02", + "sha256:8b7ee99e510d7b66cdb6c593f21c043c248537a32e0bedf02e01e9553a172314", + "sha256:91fc98adde3d7881af9b59ed0294046f3806221863722ba7d8d120c575314325", + "sha256:94411f22c3985acaec6f83c6df553f2dbe17b698cc7f8ae751ff2237d96b9e3c", + "sha256:98d85c6a2bef81588d9227dde12db8a7f47f639f4a17c9ae08e773aa9c697bf3", + "sha256:9ad5db27f9cabae298d151c85cf2bad1d359a1b9c686a275df03385758e2f914", + "sha256:a0b71b1b8fbf2b96e41c4d990244165e2c9be83d54962a9a1d118fd8657d2045", + "sha256:a0f100c8912c114ff53e1202d0078b425bee3649ae34d7b070e9697f93c5d52d", + "sha256:a591fe9e525846e4d154205572a029f653ada1a78b93697f3b5a8f1f2bc055b9", + "sha256:a5c84c68147988265e60416b57fc83425a78058853509c1b0629c180094904a5", + "sha256:a66d3508133af6e8548451b25058d5812812ec3798c886bf38ed24a98216fab2", + "sha256:a8c4917bd7ad33e8eb21e9a5bbba979b49d9a97acb3a803092cbc1133e20343c", + "sha256:b3bbeb01c2b273cca1e1e0c5df57f12dce9a4dd331b4fa1635b8bec26350bde3", + "sha256:cba9d6b9a7d64d4bd46167096fc9d2f835e25d7e4c121fb2ddfc6528fb0413b2", + "sha256:cc4d65aeeaa04136a12677d3dd0b1c0c94dc43abac5860ab33cceb42b801c1e8", + "sha256:ce4bcc037df4fc5e3d184794f27bdaab018943698f4ca31630bc7f84a7b69c6d", + "sha256:cec7d9412a9102bdc577382c3929b337320c4c4c4849f2c5cdd14d7368c5562d", + "sha256:d400bfb9a37b1351253cb402671cea7e89bdecc294e8016a707f6d1d8ac934f9", + "sha256:d61f4695e6c866a23a21acab0509af1cdfd2c013cf256bbf5b6b5e2695827162", + "sha256:db0fbb9c62743ce59a9ff687eb5f4afbe77e5e8403d6697f7446e5f609976f76", + "sha256:dd86c085fae2efd48ac91dd7ccffcfc0571387fe1193d33b6394db7ef31fe2a4", + "sha256:e00b098126fd45523dd056d2efba6c5a63b71ffe9f2bbe1a4fe1716e1d0c331e", + "sha256:e229a521186c75c8ad9490854fd8bbdd9a0c9aa3a524326b55be83b54d4e0ad9", + "sha256:e263d77ee3dd201c3a142934a086a4450861778baaeeb45db4591ef65550b0a6", + "sha256:ed9cb427ba5504c1dc15ede7d516b84757c3e3d7868ccc85121d9310d27eed0b", + "sha256:fa6693661a4c91757f4412306191b6dc88c1703f780c8234035eac011922bc01", + "sha256:fcd131dd944808b5bdb38e6f5b53013c5aa4f334c5cad0c72742f6eba4b73db0" + ], + "index": "pypi", + "version": "==1.15.1" }, "cfgv": { "hashes": [ @@ -1562,11 +1559,11 @@ }, "charset-normalizer": { "hashes": [ - "sha256:2857e29ff0d34db842cd7ca3230549d1a697f96ee6d3fb071cfa6c7393832597", - "sha256:6881edbebdb17b39b4eaaa821b438bf6eddffb4468cf344f09f89def34a8b1df" + "sha256:5189b6f22b01957427f35b6a08d9a0bc45b46d3788ef5a92e978433c7a35f8a5", + "sha256:575e708016ff3a5e3681541cb9d79312c416835686d054a23accb873b254f413" ], - "markers": "python_full_version >= '3.5.0'", - "version": "==2.0.12" + "markers": "python_version >= '3.6'", + "version": "==2.1.0" }, "control": { "hashes": [ @@ -1624,31 +1621,31 @@ }, "cryptography": { "hashes": [ - "sha256:093cb351031656d3ee2f4fa1be579a8c69c754cf874206be1d4cf3b542042804", - "sha256:0cc20f655157d4cfc7bada909dc5cc228211b075ba8407c46467f63597c78178", - "sha256:1b9362d34363f2c71b7853f6251219298124aa4cc2075ae2932e64c91a3e2717", - "sha256:1f3bfbd611db5cb58ca82f3deb35e83af34bb8cf06043fa61500157d50a70982", - "sha256:2bd1096476aaac820426239ab534b636c77d71af66c547b9ddcd76eb9c79e004", - "sha256:31fe38d14d2e5f787e0aecef831457da6cec68e0bb09a35835b0b44ae8b988fe", - "sha256:3b8398b3d0efc420e777c40c16764d6870bcef2eb383df9c6dbb9ffe12c64452", - "sha256:3c81599befb4d4f3d7648ed3217e00d21a9341a9a688ecdd615ff72ffbed7336", - "sha256:419c57d7b63f5ec38b1199a9521d77d7d1754eb97827bbb773162073ccd8c8d4", - "sha256:46f4c544f6557a2fefa7ac8ac7d1b17bf9b647bd20b16decc8fbcab7117fbc15", - "sha256:471e0d70201c069f74c837983189949aa0d24bb2d751b57e26e3761f2f782b8d", - "sha256:59b281eab51e1b6b6afa525af2bd93c16d49358404f814fe2c2410058623928c", - "sha256:731c8abd27693323b348518ed0e0705713a36d79fdbd969ad968fbef0979a7e0", - "sha256:95e590dd70642eb2079d280420a888190aa040ad20f19ec8c6e097e38aa29e06", - "sha256:a68254dd88021f24a68b613d8c51d5c5e74d735878b9e32cc0adf19d1f10aaf9", - "sha256:a7d5137e556cc0ea418dca6186deabe9129cee318618eb1ffecbd35bee55ddc1", - "sha256:aeaba7b5e756ea52c8861c133c596afe93dd716cbcacae23b80bc238202dc023", - "sha256:dc26bb134452081859aa21d4990474ddb7e863aa39e60d1592800a8865a702de", - "sha256:e53258e69874a306fcecb88b7534d61820db8a98655662a3dd2ec7f1afd9132f", - "sha256:ef15c2df7656763b4ff20a9bc4381d8352e6640cfeb95c2972c38ef508e75181", - "sha256:f224ad253cc9cea7568f49077007d2263efa57396a2f2f78114066fd54b5c68e", - "sha256:f8ec91983e638a9bcd75b39f1396e5c0dc2330cbd9ce4accefe68717e6779e0a" - ], - "index": "pypi", - "version": "==37.0.2" + "sha256:190f82f3e87033821828f60787cfa42bff98404483577b591429ed99bed39d59", + "sha256:2be53f9f5505673eeda5f2736bea736c40f051a739bfae2f92d18aed1eb54596", + "sha256:30788e070800fec9bbcf9faa71ea6d8068f5136f60029759fd8c3efec3c9dcb3", + "sha256:3d41b965b3380f10e4611dbae366f6dc3cefc7c9ac4e8842a806b9672ae9add5", + "sha256:4c590ec31550a724ef893c50f9a97a0c14e9c851c85621c5650d699a7b88f7ab", + "sha256:549153378611c0cca1042f20fd9c5030d37a72f634c9326e225c9f666d472884", + "sha256:63f9c17c0e2474ccbebc9302ce2f07b55b3b3fcb211ded18a42d5764f5c10a82", + "sha256:6bc95ed67b6741b2607298f9ea4932ff157e570ef456ef7ff0ef4884a134cc4b", + "sha256:7099a8d55cd49b737ffc99c17de504f2257e3787e02abe6d1a6d136574873441", + "sha256:75976c217f10d48a8b5a8de3d70c454c249e4b91851f6838a4e48b8f41eb71aa", + "sha256:7bc997818309f56c0038a33b8da5c0bfbb3f1f067f315f9abd6fc07ad359398d", + "sha256:80f49023dd13ba35f7c34072fa17f604d2f19bf0989f292cedf7ab5770b87a0b", + "sha256:91ce48d35f4e3d3f1d83e29ef4a9267246e6a3be51864a5b7d2247d5086fa99a", + "sha256:a958c52505c8adf0d3822703078580d2c0456dd1d27fabfb6f76fe63d2971cd6", + "sha256:b62439d7cd1222f3da897e9a9fe53bbf5c104fff4d60893ad1355d4c14a24157", + "sha256:b7f8dd0d4c1f21759695c05a5ec8536c12f31611541f8904083f3dc582604280", + "sha256:d204833f3c8a33bbe11eda63a54b1aad7aa7456ed769a982f21ec599ba5fa282", + "sha256:e007f052ed10cc316df59bc90fbb7ff7950d7e2919c9757fd42a2b8ecf8a5f67", + "sha256:f2dcb0b3b63afb6df7fd94ec6fbddac81b5492513f7b0436210d390c14d46ee8", + "sha256:f721d1885ecae9078c3f6bbe8a88bc0786b6e749bf32ccec1ef2b18929a05046", + "sha256:f7a6de3e98771e183645181b3627e2563dcde3ce94a9e42a3f427d2255190327", + "sha256:f8c0a6e9e1dd3eb0414ba320f85da6b0dcbd543126e30fcc546e7372a7fbf3b9" + ], + "index": "pypi", + "version": "==37.0.4" }, "cycler": { "hashes": [ @@ -1742,11 +1739,11 @@ }, "fonttools": { "hashes": [ - "sha256:c0fdcfa8ceebd7c1b2021240bd46ef77aa8e7408cf10434be55df52384865f8e", - "sha256:f829c579a8678fa939a1d9e9894d01941db869de44390adb49ce67055a06cc2a" + "sha256:9a1c52488045cd6c6491fd07711a380f932466e317cb8e016fc4e99dc7eac2f0", + "sha256:d73f25b283cd8033367451122aa868a23de0734757a01984e4b30b18b9050c72" ], "markers": "python_version >= '3.7'", - "version": "==4.33.3" + "version": "==4.34.4" }, "ft4222": { "hashes": [ @@ -1805,24 +1802,24 @@ "sha256:84d9dd047ffa80596e0f246e2eab0b391788b0503584e8945f2368256d2735ff", "sha256:9d643ff0a55b762d5cdb124b8eaa99c66322e2157b69160bc32796e824360e6d" ], - "markers": "python_full_version >= '3.5.0'", + "markers": "python_version >= '3.5'", "version": "==3.3" }, "imagesize": { "hashes": [ - "sha256:1db2f82529e53c3e929e8926a1fa9235aa82d0bd0c580359c67ec31b2fddaa8c", - "sha256:cd1750d452385ca327479d45b64d9c7729ecf0b3969a58148298c77092261f9d" + "sha256:0d8d18d08f840c19d0ee7ca1fd82490fdc3729b7ac93f49870406ddde8ef8d8b", + "sha256:69150444affb9cb0d5cc5a92b3676f0b2fb7cd9ae39e947a5e11a36b4497cd4a" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==1.3.0" + "version": "==1.4.1" }, "importlib-metadata": { "hashes": [ - "sha256:5d26852efe48c0a32b0509ffbc583fda1a2266545a78d104a6f4aff3db17d700", - "sha256:c58c8eb8a762858f49e18436ff552e83914778e50e9d2f1660535ffb364552ec" + "sha256:637245b8bab2b6502fcbc752cc4b7a6f6243bb02b31c5c26156ad103d3d45670", + "sha256:7401a975809ea1fdc658c3aa4f78cc2195a0e019c5cbc4c06122884e9ae80c23" ], "markers": "python_version < '3.10'", - "version": "==4.11.4" + "version": "==4.12.0" }, "iniconfig": { "hashes": [ @@ -2076,38 +2073,39 @@ }, "nodeenv": { "hashes": [ - "sha256:3ef13ff90291ba2a4a7a4ff9a979b63ffdd00a464dbe04acf0ea6471517a4c2b", - "sha256:621e6b7076565ddcacd2db0294c0381e01fd28945ab36bcf00f41c5daf63bef7" + "sha256:27083a7b96a25f2f5e1d8cb4b6317ee8aeda3bdd121394e5ac54e498028a042e", + "sha256:e0e7f7dfb85fc5394c6fe1e8fa98131a2473e04311a45afb6508f7cf1836fa2b" ], - "version": "==1.6.0" + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3, 3.4, 3.5, 3.6'", + "version": "==1.7.0" }, "numpy": { "hashes": [ - "sha256:0791fbd1e43bf74b3502133207e378901272f3c156c4df4954cad833b1380207", - "sha256:1ce7ab2053e36c0a71e7a13a7475bd3b1f54750b4b433adc96313e127b870887", - "sha256:2d487e06ecbf1dc2f18e7efce82ded4f705f4bd0cd02677ffccfb39e5c284c7e", - "sha256:37431a77ceb9307c28382c9773da9f306435135fae6b80b62a11c53cfedd8802", - "sha256:3e1ffa4748168e1cc8d3cde93f006fe92b5421396221a02f2274aab6ac83b077", - "sha256:425b390e4619f58d8526b3dcf656dde069133ae5c240229821f01b5f44ea07af", - "sha256:43a8ca7391b626b4c4fe20aefe79fec683279e31e7c79716863b4b25021e0e74", - "sha256:4c6036521f11a731ce0648f10c18ae66d7143865f19f7299943c985cdc95afb5", - "sha256:59d55e634968b8f77d3fd674a3cf0b96e85147cd6556ec64ade018f27e9479e1", - "sha256:64f56fc53a2d18b1924abd15745e30d82a5782b2cab3429aceecc6875bd5add0", - "sha256:7228ad13744f63575b3a972d7ee4fd61815b2879998e70930d4ccf9ec721dce0", - "sha256:9ce7df0abeabe7fbd8ccbf343dc0db72f68549856b863ae3dd580255d009648e", - "sha256:a911e317e8c826ea632205e63ed8507e0dc877dcdc49744584dfc363df9ca08c", - "sha256:b89bf9b94b3d624e7bb480344e91f68c1c6c75f026ed6755955117de00917a7c", - "sha256:ba9ead61dfb5d971d77b6c131a9dbee62294a932bf6a356e48c75ae684e635b3", - "sha256:c1d937820db6e43bec43e8d016b9b3165dcb42892ea9f106c70fb13d430ffe72", - "sha256:cc7f00008eb7d3f2489fca6f334ec19ca63e31371be28fd5dad955b16ec285bd", - "sha256:d4c5d5eb2ec8da0b4f50c9a843393971f31f1d60be87e0fb0917a49133d257d6", - "sha256:e96d7f3096a36c8754207ab89d4b3282ba7b49ea140e4973591852c77d09eb76", - "sha256:f0725df166cf4785c0bc4cbfb320203182b1ecd30fee6e541c8752a92df6aa32", - "sha256:f3eb268dbd5cfaffd9448113539e44e2dd1c5ca9ce25576f7c04a5453edc26fa", - "sha256:fb7a980c81dd932381f8228a426df8aeb70d59bbcda2af075b627bbc50207cba" - ], - "index": "pypi", - "version": "==1.22.4" + "sha256:092f5e6025813e64ad6d1b52b519165d08c730d099c114a9247c9bb635a2a450", + "sha256:196cd074c3f97c4121601790955f915187736f9cf458d3ee1f1b46aff2b1ade0", + "sha256:1c29b44905af288b3919803aceb6ec7fec77406d8b08aaa2e8b9e63d0fe2f160", + "sha256:2b2da66582f3a69c8ce25ed7921dcd8010d05e59ac8d89d126a299be60421171", + "sha256:5043bcd71fcc458dfb8a0fc5509bbc979da0131b9d08e3d5f50fb0bbb36f169a", + "sha256:58bfd40eb478f54ff7a5710dd61c8097e169bc36cc68333d00a9bcd8def53b38", + "sha256:79a506cacf2be3a74ead5467aee97b81fca00c9c4c8b3ba16dbab488cd99ba10", + "sha256:94b170b4fa0168cd6be4becf37cb5b127bd12a795123984385b8cd4aca9857e5", + "sha256:97a76604d9b0e79f59baeca16593c711fddb44936e40310f78bfef79ee9a835f", + "sha256:98e8e0d8d69ff4d3fa63e6c61e8cfe2d03c29b16b58dbef1f9baa175bbed7860", + "sha256:ac86f407873b952679f5f9e6c0612687e51547af0e14ddea1eedfcb22466babd", + "sha256:ae8adff4172692ce56233db04b7ce5792186f179c415c37d539c25de7298d25d", + "sha256:bd3fa4fe2e38533d5336e1272fc4e765cabbbde144309ccee8675509d5cd7b05", + "sha256:d0d2094e8f4d760500394d77b383a1b06d3663e8892cdf5df3c592f55f3bff66", + "sha256:d54b3b828d618a19779a84c3ad952e96e2c2311b16384e973e671aa5be1f6187", + "sha256:d6ca8dabe696c2785d0c8c9b0d8a9b6e5fdbe4f922bde70d57fa1a2848134f95", + "sha256:d8cc87bed09de55477dba9da370c1679bd534df9baa171dd01accbb09687dac3", + "sha256:f0f18804df7370571fb65db9b98bf1378172bd4e962482b857e612d1fec0f53e", + "sha256:f1d88ef79e0a7fa631bb2c3dda1ea46b32b1fe614e10fedd611d3d5398447f2f", + "sha256:f9c3fc2adf67762c9fe1849c859942d23f8d3e0bee7b5ed3d4a9c3eeb50a2f07", + "sha256:fc431493df245f3c627c0c05c2bd134535e7929dbe2e602b80e42bf52ff760bc", + "sha256:fe8b9683eb26d2c4d5db32cd29b38fdcf8381324ab48313b5b69088e0e355379" + ], + "index": "pypi", + "version": "==1.23.0" }, "opencv-python-headless": { "hashes": [ @@ -2130,6 +2128,33 @@ "markers": "python_version >= '3.6'", "version": "==21.3" }, + "pandas": { + "hashes": [ + "sha256:07238a58d7cbc8a004855ade7b75bbd22c0db4b0ffccc721556bab8a095515f6", + "sha256:0daf876dba6c622154b2e6741f29e87161f844e64f84801554f879d27ba63c0d", + "sha256:16ad23db55efcc93fa878f7837267973b61ea85d244fc5ff0ccbcfa5638706c5", + "sha256:1d9382f72a4f0e93909feece6fef5500e838ce1c355a581b3d8f259839f2ea76", + "sha256:24ea75f47bbd5574675dae21d51779a4948715416413b30614c1e8b480909f81", + "sha256:2893e923472a5e090c2d5e8db83e8f907364ec048572084c7d10ef93546be6d1", + "sha256:2ff7788468e75917574f080cd4681b27e1a7bf36461fe968b49a87b5a54d007c", + "sha256:41fc406e374590a3d492325b889a2686b31e7a7780bec83db2512988550dadbf", + "sha256:48350592665ea3cbcd07efc8c12ff12d89be09cd47231c7925e3b8afada9d50d", + "sha256:605d572126eb4ab2eadf5c59d5d69f0608df2bf7bcad5c5880a47a20a0699e3e", + "sha256:6dfbf16b1ea4f4d0ee11084d9c026340514d1d30270eaa82a9f1297b6c8ecbf0", + "sha256:6f803320c9da732cc79210d7e8cc5c8019aad512589c910c66529eb1b1818230", + "sha256:721a3dd2f06ef942f83a819c0f3f6a648b2830b191a72bbe9451bcd49c3bd42e", + "sha256:755679c49460bd0d2f837ab99f0a26948e68fa0718b7e42afbabd074d945bf84", + "sha256:78b00429161ccb0da252229bcda8010b445c4bf924e721265bec5a6e96a92e92", + "sha256:958a0588149190c22cdebbc0797e01972950c927a11a900fe6c2296f207b1d6f", + "sha256:a3924692160e3d847e18702bb048dc38e0e13411d2b503fecb1adf0fcf950ba4", + "sha256:d51674ed8e2551ef7773820ef5dab9322be0828629f2cbf8d1fc31a0c4fed640", + "sha256:d5ebc990bd34f4ac3c73a2724c2dcc9ee7bf1ce6cf08e87bb25c6ad33507e318", + "sha256:d6c0106415ff1a10c326c49bc5dd9ea8b9897a6ca0c8688eb9c30ddec49535ef", + "sha256:e48fbb64165cda451c06a0f9e4c7a16b534fcabd32546d531b3c240ce2844112" + ], + "index": "pypi", + "version": "==1.4.3" + }, "parameterized": { "hashes": [ "sha256:41bbff37d6186430f77f900d777e5bb6a24928a1c46fb1de692f8b52b8833b5c", @@ -2148,47 +2173,67 @@ }, "pillow": { "hashes": [ - "sha256:088df396b047477dd1bbc7de6e22f58400dae2f21310d9e2ec2933b2ef7dfa4f", - "sha256:09e67ef6e430f90caa093528bd758b0616f8165e57ed8d8ce014ae32df6a831d", - "sha256:0b4d5ad2cd3a1f0d1df882d926b37dbb2ab6c823ae21d041b46910c8f8cd844b", - "sha256:0b525a356680022b0af53385944026d3486fc8c013638cf9900eb87c866afb4c", - "sha256:1d4331aeb12f6b3791911a6da82de72257a99ad99726ed6b63f481c0184b6fb9", - "sha256:20d514c989fa28e73a5adbddd7a171afa5824710d0ab06d4e1234195d2a2e546", - "sha256:2b291cab8a888658d72b575a03e340509b6b050b62db1f5539dd5cd18fd50578", - "sha256:3f6c1716c473ebd1649663bf3b42702d0d53e27af8b64642be0dd3598c761fb1", - "sha256:42dfefbef90eb67c10c45a73a9bc1599d4dac920f7dfcbf4ec6b80cb620757fe", - "sha256:488f3383cf5159907d48d32957ac6f9ea85ccdcc296c14eca1a4e396ecc32098", - "sha256:4d45dbe4b21a9679c3e8b3f7f4f42a45a7d3ddff8a4a16109dff0e1da30a35b2", - "sha256:53c27bd452e0f1bc4bfed07ceb235663a1df7c74df08e37fd6b03eb89454946a", - "sha256:55e74faf8359ddda43fee01bffbc5bd99d96ea508d8a08c527099e84eb708f45", - "sha256:59789a7d06c742e9d13b883d5e3569188c16acb02eeed2510fd3bfdbc1bd1530", - "sha256:5b650dbbc0969a4e226d98a0b440c2f07a850896aed9266b6fedc0f7e7834108", - "sha256:66daa16952d5bf0c9d5389c5e9df562922a59bd16d77e2a276e575d32e38afd1", - "sha256:6e760cf01259a1c0a50f3c845f9cad1af30577fd8b670339b1659c6d0e7a41dd", - "sha256:7502539939b53d7565f3d11d87c78e7ec900d3c72945d4ee0e2f250d598309a0", - "sha256:769a7f131a2f43752455cc72f9f7a093c3ff3856bf976c5fb53a59d0ccc704f6", - "sha256:7c150dbbb4a94ea4825d1e5f2c5501af7141ea95825fadd7829f9b11c97aaf6c", - "sha256:8844217cdf66eabe39567118f229e275f0727e9195635a15e0e4b9227458daaf", - "sha256:8a66fe50386162df2da701b3722781cbe90ce043e7d53c1fd6bd801bca6b48d4", - "sha256:9370d6744d379f2de5d7fa95cdbd3a4d92f0b0ef29609b4b1687f16bc197063d", - "sha256:937a54e5694684f74dcbf6e24cc453bfc5b33940216ddd8f4cd8f0f79167f765", - "sha256:9c857532c719fb30fafabd2371ce9b7031812ff3889d75273827633bca0c4602", - "sha256:a4165205a13b16a29e1ac57efeee6be2dfd5b5408122d59ef2145bc3239fa340", - "sha256:b3fe2ff1e1715d4475d7e2c3e8dabd7c025f4410f79513b4ff2de3d51ce0fa9c", - "sha256:b6617221ff08fbd3b7a811950b5c3f9367f6e941b86259843eab77c8e3d2b56b", - "sha256:b761727ed7d593e49671d1827044b942dd2f4caae6e51bab144d4accf8244a84", - "sha256:baf3be0b9446a4083cc0c5bb9f9c964034be5374b5bc09757be89f5d2fa247b8", - "sha256:c17770a62a71718a74b7548098a74cd6880be16bcfff5f937f900ead90ca8e92", - "sha256:c67db410508b9de9c4694c57ed754b65a460e4812126e87f5052ecf23a011a54", - "sha256:d78ca526a559fb84faaaf84da2dd4addef5edb109db8b81677c0bb1aad342601", - "sha256:e9ed59d1b6ee837f4515b9584f3d26cf0388b742a11ecdae0d9237a94505d03a", - "sha256:f054b020c4d7e9786ae0404278ea318768eb123403b18453e28e47cdb7a0a4bf", - "sha256:f372d0f08eff1475ef426344efe42493f71f377ec52237bf153c5713de987251", - "sha256:f3f6a6034140e9e17e9abc175fc7a266a6e63652028e157750bd98e804a8ed9a", - "sha256:ffde4c6fabb52891d81606411cbfaf77756e3b561b566efd270b3ed3791fde4e" - ], - "index": "pypi", - "version": "==9.1.1" + "sha256:0030fdbd926fb85844b8b92e2f9449ba89607231d3dd597a21ae72dc7fe26927", + "sha256:030e3460861488e249731c3e7ab59b07c7853838ff3b8e16aac9561bb345da14", + "sha256:0ed2c4ef2451de908c90436d6e8092e13a43992f1860275b4d8082667fbb2ffc", + "sha256:136659638f61a251e8ed3b331fc6ccd124590eeff539de57c5f80ef3a9594e58", + "sha256:13b725463f32df1bfeacbf3dd197fb358ae8ebcd8c5548faa75126ea425ccb60", + "sha256:1536ad017a9f789430fb6b8be8bf99d2f214c76502becc196c6f2d9a75b01b76", + "sha256:15928f824870535c85dbf949c09d6ae7d3d6ac2d6efec80f3227f73eefba741c", + "sha256:17d4cafe22f050b46d983b71c707162d63d796a1235cdf8b9d7a112e97b15bac", + "sha256:1802f34298f5ba11d55e5bb09c31997dc0c6aed919658dfdf0198a2fe75d5490", + "sha256:1cc1d2451e8a3b4bfdb9caf745b58e6c7a77d2e469159b0d527a4554d73694d1", + "sha256:1fd6f5e3c0e4697fa7eb45b6e93996299f3feee73a3175fa451f49a74d092b9f", + "sha256:254164c57bab4b459f14c64e93df11eff5ded575192c294a0c49270f22c5d93d", + "sha256:2ad0d4df0f5ef2247e27fc790d5c9b5a0af8ade9ba340db4a73bb1a4a3e5fb4f", + "sha256:2c58b24e3a63efd22554c676d81b0e57f80e0a7d3a5874a7e14ce90ec40d3069", + "sha256:2d33a11f601213dcd5718109c09a52c2a1c893e7461f0be2d6febc2879ec2402", + "sha256:337a74fd2f291c607d220c793a8135273c4c2ab001b03e601c36766005f36885", + "sha256:37ff6b522a26d0538b753f0b4e8e164fdada12db6c6f00f62145d732d8a3152e", + "sha256:3d1f14f5f691f55e1b47f824ca4fdcb4b19b4323fe43cc7bb105988cad7496be", + "sha256:408673ed75594933714482501fe97e055a42996087eeca7e5d06e33218d05aa8", + "sha256:4134d3f1ba5f15027ff5c04296f13328fecd46921424084516bdb1b2548e66ff", + "sha256:4ad2f835e0ad81d1689f1b7e3fbac7b01bb8777d5a985c8962bedee0cc6d43da", + "sha256:50dff9cc21826d2977ef2d2a205504034e3a4563ca6f5db739b0d1026658e004", + "sha256:510cef4a3f401c246cfd8227b300828715dd055463cdca6176c2e4036df8bd4f", + "sha256:5aed7dde98403cd91d86a1115c78d8145c83078e864c1de1064f52e6feb61b20", + "sha256:69bd1a15d7ba3694631e00df8de65a8cb031911ca11f44929c97fe05eb9b6c1d", + "sha256:6bf088c1ce160f50ea40764f825ec9b72ed9da25346216b91361eef8ad1b8f8c", + "sha256:6e8c66f70fb539301e064f6478d7453e820d8a2c631da948a23384865cd95544", + "sha256:727dd1389bc5cb9827cbd1f9d40d2c2a1a0c9b32dd2261db522d22a604a6eec9", + "sha256:74a04183e6e64930b667d321524e3c5361094bb4af9083db5c301db64cd341f3", + "sha256:75e636fd3e0fb872693f23ccb8a5ff2cd578801251f3a4f6854c6a5d437d3c04", + "sha256:7761afe0126d046974a01e030ae7529ed0ca6a196de3ec6937c11df0df1bc91c", + "sha256:7888310f6214f19ab2b6df90f3f06afa3df7ef7355fc025e78a3044737fab1f5", + "sha256:7b0554af24df2bf96618dac71ddada02420f946be943b181108cac55a7a2dcd4", + "sha256:7c7b502bc34f6e32ba022b4a209638f9e097d7a9098104ae420eb8186217ebbb", + "sha256:808add66ea764ed97d44dda1ac4f2cfec4c1867d9efb16a33d158be79f32b8a4", + "sha256:831e648102c82f152e14c1a0938689dbb22480c548c8d4b8b248b3e50967b88c", + "sha256:93689632949aff41199090eff5474f3990b6823404e45d66a5d44304e9cdc467", + "sha256:96b5e6874431df16aee0c1ba237574cb6dff1dcb173798faa6a9d8b399a05d0e", + "sha256:9a54614049a18a2d6fe156e68e188da02a046a4a93cf24f373bffd977e943421", + "sha256:a138441e95562b3c078746a22f8fca8ff1c22c014f856278bdbdd89ca36cff1b", + "sha256:a647c0d4478b995c5e54615a2e5360ccedd2f85e70ab57fbe817ca613d5e63b8", + "sha256:a9c9bc489f8ab30906d7a85afac4b4944a572a7432e00698a7239f44a44e6efb", + "sha256:ad2277b185ebce47a63f4dc6302e30f05762b688f8dc3de55dbae4651872cdf3", + "sha256:b6d5e92df2b77665e07ddb2e4dbd6d644b78e4c0d2e9272a852627cdba0d75cf", + "sha256:bc431b065722a5ad1dfb4df354fb9333b7a582a5ee39a90e6ffff688d72f27a1", + "sha256:bdd0de2d64688ecae88dd8935012c4a72681e5df632af903a1dca8c5e7aa871a", + "sha256:c79698d4cd9318d9481d89a77e2d3fcaeff5486be641e60a4b49f3d2ecca4e28", + "sha256:cb6259196a589123d755380b65127ddc60f4c64b21fc3bb46ce3a6ea663659b0", + "sha256:d5b87da55a08acb586bad5c3aa3b86505f559b84f39035b233d5bf844b0834b1", + "sha256:dcd7b9c7139dc8258d164b55696ecd16c04607f1cc33ba7af86613881ffe4ac8", + "sha256:dfe4c1fedfde4e2fbc009d5ad420647f7730d719786388b7de0999bf32c0d9fd", + "sha256:ea98f633d45f7e815db648fd7ff0f19e328302ac36427343e4432c84432e7ff4", + "sha256:ec52c351b35ca269cb1f8069d610fc45c5bd38c3e91f9ab4cbbf0aebc136d9c8", + "sha256:eef7592281f7c174d3d6cbfbb7ee5984a671fcd77e3fc78e973d492e9bf0eb3f", + "sha256:f07f1f00e22b231dd3d9b9208692042e29792d6bd4f6639415d2f23158a80013", + "sha256:f3fac744f9b540148fa7715a435d2283b71f68bfb6d4aae24482a890aed18b59", + "sha256:fa768eff5f9f958270b081bb33581b4b569faabf8774726b283edb06617101dc", + "sha256:fac2d65901fb0fdf20363fbd345c01958a742f2dc62a8dd4495af66e3ff502a4" + ], + "index": "pypi", + "version": "==9.2.0" }, "platformdirs": { "hashes": [ @@ -2426,11 +2471,11 @@ }, "requests": { "hashes": [ - "sha256:bc7861137fbce630f17b03d3ad02ad0bf978c844f3536d0edda6499dafce2b6f", - "sha256:d568723a7ebd25875d8d1eaf5dfa068cd2fc8194b2e483d7b1f7c81918dbec6b" + "sha256:7c5599b102feddaa661c826c56ab4fee28bfd17f5abca1ebbe3e7f19d7c97983", + "sha256:8fefa2a1a1365bf5520aac41836fbee479da67864514bdb821f31ce07ce65349" ], "index": "pypi", - "version": "==2.28.0" + "version": "==2.28.1" }, "reverse-geocoder": { "hashes": [ @@ -2468,6 +2513,14 @@ "index": "pypi", "version": "==1.8.1" }, + "setuptools": { + "hashes": [ + "sha256:16923d366ced322712c71ccb97164d07472abeecd13f3a6c283f6d5d26722793", + "sha256:db3b8e2f922b2a910a29804776c643ea609badb6a32c4bcc226fd4fd902cce65" + ], + "markers": "python_version >= '3.7'", + "version": "==63.1.0" + }, "six": { "hashes": [ "sha256:1e61c37477a1626458e36f7b1d82aa5c9b094fa4802892072e49de9c60c4c926", @@ -2492,11 +2545,11 @@ }, "sphinx": { "hashes": [ - "sha256:7bf8ca9637a4ee15af412d1a1d9689fec70523a68ca9bb9127c2f3eeb344e2e6", - "sha256:ebf612653238bcc8f4359627a9b7ce44ede6fdd75d9d30f68255c7383d3a6226" + "sha256:b18e978ea7565720f26019c702cd85c84376e948370f1cd43d60265010e1c7b0", + "sha256:d3e57663eed1d7c5c50895d191fdeda0b54ded6f44d5621b50709466c338d1e8" ], "index": "pypi", - "version": "==4.5.0" + "version": "==5.0.2" }, "sphinx-rtd-theme": { "hashes": [ @@ -2570,6 +2623,15 @@ "index": "pypi", "version": "==3.5.4" }, + "tabulate": { + "hashes": [ + "sha256:0ba055423dbaa164b9e456abe7920c5e8ed33fcc16f6d1b2f2d152c8e1e8b4fc", + "sha256:436f1c768b424654fce8597290d2764def1eea6a77cfa5c33be00b1bc0f4f63d", + "sha256:6c57f3f3dd7ac2782770155f3adb2db0b1a269637e42f27599925e64b114f519" + ], + "index": "pypi", + "version": "==0.8.10" + }, "tenacity": { "hashes": [ "sha256:43242a20e3e73291a28bcbcacfd6e000b02d3857a9a9fff56b297a27afdc932f", @@ -2596,27 +2658,27 @@ }, "typing-extensions": { "hashes": [ - "sha256:6657594ee297170d19f67d55c05852a874e7eb634f4f753dbd667855e07c1708", - "sha256:f1c24655a0da0d1b67f07e17a5e6b2a105894e6824b92096378bb3668ef02376" + "sha256:25642c956049920a5aa49edcdd6ab1e06d7e5d467fc00e0506c44ac86fbfca02", + "sha256:e6d2677a32f47fc7eb2795db1dd15c1f34eff616bcaf2cfb5e997f854fa1c4a6" ], - "markers": "python_version < '3.10'", - "version": "==4.2.0" + "markers": "python_version >= '3.7'", + "version": "==4.3.0" }, "urllib3": { "hashes": [ - "sha256:44ece4d53fb1706f667c9bd1c648f5469a2ec925fcf3a776667042d645472c14", - "sha256:aabaf16477806a5e1dd19aa41f8c2b7950dd3c746362d7e3223dbe6de6ac448e" + "sha256:8298d6d56d39be0e3bc13c1c97d133f9b45d797169a0e11cdd0e0489d786f7ec", + "sha256:879ba4d1e89654d9769ce13121e0f94310ea32e8d2f8cf587b77c08bbcdb30d6" ], "index": "pypi", - "version": "==1.26.9" + "version": "==1.26.10" }, "virtualenv": { "hashes": [ - "sha256:e617f16e25b42eb4f6e74096b9c9e37713cf10bf30168fb4a739f3fa8f898a3a", - "sha256:ef589a79795589aada0c1c5b319486797c03b67ac3984c48c669c0e4f50df3a5" + "sha256:288171134a2ff3bfb1a2f54f119e77cd1b81c29fc1265a2356f3e8d14c7d58c4", + "sha256:b30aefac647e86af6d82bfc944c556f8f1a9c90427b2fb4e3bfbf338cb82becf" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3, 3.4'", - "version": "==20.14.1" + "version": "==20.15.1" }, "zipp": { "hashes": [ diff --git a/selfdrive/debug/can_table.py b/selfdrive/debug/can_table.py index e8cd084a32..11d070e708 100755 --- a/selfdrive/debug/can_table.py +++ b/selfdrive/debug/can_table.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 import argparse -import pandas as pd # pylint: disable=import-error +import pandas as pd import cereal.messaging as messaging From d8089fb94e9ad1ab54bc3baf1acbb430b305f612 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 7 Jul 2022 23:07:21 -0700 Subject: [PATCH 238/302] Add video for 2020 Lexus ES Hybrid --- selfdrive/car/toyota/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 9324e6baf5..8149bfd063 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -152,7 +152,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { CAR.LEXUS_CTH: ToyotaCarInfo("Lexus CT Hybrid 2017-18", "LSS", footnotes=[Footnote.DSU]), CAR.LEXUS_ESH: ToyotaCarInfo("Lexus ES Hybrid 2017-18", "LSS", footnotes=[Footnote.DSU]), CAR.LEXUS_ES_TSS2: ToyotaCarInfo("Lexus ES 2019-21"), - CAR.LEXUS_ESH_TSS2: ToyotaCarInfo("Lexus ES Hybrid 2019-22"), + CAR.LEXUS_ESH_TSS2: ToyotaCarInfo("Lexus ES Hybrid 2019-22", video_link="https://youtu.be/BZ29osRVJeg?t=12"), CAR.LEXUS_IS: ToyotaCarInfo("Lexus IS 2017-19"), CAR.LEXUS_NX: ToyotaCarInfo("Lexus NX 2018-19", footnotes=[Footnote.DSU]), CAR.LEXUS_NXH: ToyotaCarInfo("Lexus NX Hybrid 2018-19", footnotes=[Footnote.DSU]), From ed47032a6d51d1aeaf4cd553ae9b350e04672558 Mon Sep 17 00:00:00 2001 From: Lee Jong Mun <43285072+crwusiz@users.noreply.github.com> Date: Fri, 8 Jul 2022 16:03:57 +0900 Subject: [PATCH 239/302] Add Korean translations (#25073) * Add Korean translations Signed-off-by: crwusiz * line error fix Signed-off-by: crwusiz * space error retry Signed-off-by: crwusiz * " fix Signed-off-by: crwusiz * translation --release * main_ko.qm remove * main_ko.qm remake * Update ko and fix zh * fix Linguist warnings * commit noun Co-authored-by: Shane Smiskol --- selfdrive/ui/translations/languages.json | 3 +- selfdrive/ui/translations/main_ko.qm | Bin 0 -> 19159 bytes selfdrive/ui/translations/main_ko.ts | 1212 ++++++++++++++++++++++ 3 files changed, 1214 insertions(+), 1 deletion(-) create mode 100644 selfdrive/ui/translations/main_ko.qm create mode 100644 selfdrive/ui/translations/main_ko.ts diff --git a/selfdrive/ui/translations/languages.json b/selfdrive/ui/translations/languages.json index e62de24a1e..b8c3a50fd7 100644 --- a/selfdrive/ui/translations/languages.json +++ b/selfdrive/ui/translations/languages.json @@ -1,4 +1,5 @@ { "English": "", - "中文(简体)": "main_zh" + "中文(简体)": "main_zh", + "한국어": "main_ko" } diff --git a/selfdrive/ui/translations/main_ko.qm b/selfdrive/ui/translations/main_ko.qm new file mode 100644 index 0000000000000000000000000000000000000000..62ddb3be2b89c6c73e82458ae86c02825c925de5 GIT binary patch literal 19159 zcmcJ0eSB2ang2;Llb6Zlg;yyJcnKh|LP!LZB338K0D+LiWCF3qT_%~EWXxn{oVf#J zOZR7g>QAlc;ucrBOI_E(s=pmrNP;97Xp&|!i3=FOQ2P;fS(aMt+ScysuG?ze?{m(b zJ9l0Z+dtNPDio(}@%N%1VagRzVOz)6gm!;CGo zF=l<7u@Wm|o1bFrc6_g_!}I%$-Cx33W&xgUjLrNA&nNI6^COlF_v|MHB{`! ze7CS~ytaq2(lzX%!7^9b={4rz8USh*Dsu`R2 z5&P+P0>E3IGW%=G8Cz7HGUug5j4hd!vgSGLPsy2-`$v{Bwm2o_uO{$*-HDX*HUse1 zq`aH@1I7w=qf)bXXY7vuo4UcIfUXx(8}qT=lJ?Z^zmo;{ z*HTaJ1zmUiXX=@X=NQW`OuckJ@XoWOULC_e7rmW&?d4g(w=Zqphep7EmR9)8y;x6s zTHt=*Tl>AVzt07|%U7gzy-|bl`_oQ!0lxUxX~RqY3^Ml1w6~}K7xwMBv`+(v!PVOh z)(?&|HlxC@y~M&S<(5{J!rcW6m>=fPeMIvfRa>|4)q#JFp*j?K8HT&OlD=#)lVy-jbWfhe@7H zd3a(SnO0+G%WlA*Gk$Y*F690D#%KN#beQfD&-vBjdFwOcS^Avu;GaVdvQHWh{l6!$ z-d`I3A$$$|`3vLF=iqbdVdIY$TwpBkJI42}f{wyp8~^pOG3@&f#MAOy<8M9(T`Mco zQy17EPj95>{;G(vTaTx&|6l{wV@%)Jb(*pDrRfi*fbWamOaH;AzXKolruP?p5A?p8 z{+sFv$X7>3;WF@P>9&l+b05Qg-=Fah?tjJn4`=+U_7(8$v5ZgN{R;Tx%lNOKgD+`U zGJbpa&#>PMGs~6@W7{$_H>ZK_{0B1SU;GyIel_#iz+W-;)mJnB=I?=TMo#95pDx7r zhqE$r{si*#t*nIyGjUEH$g=!bKkgy$@t{|<7X zA*bZ+6NWsKc2iUA;AB}GMC3MXW&zgrOB`O?9GbBCHs^V0-YHO zb$i3g#a<@$=P@Z9JpJe;qc(I}t=#1CD3aankm|h-yD}M?=}|P{JwsQSRT6x?5=h(=Cpjc6YPvsFIak9$!0N^Hmsn z4)r!_qYS0?=JqMUFZGUHh=N#=uy3328N zmEE?!!8io@Dgv9Vw8_3NLlNOl_=(=d8Vy-iw<7x_@MtRP=MIcADMG@T@_yF;)aA9< zX+5R_fypiJl9UKNlGpC{gUODmkegTqwoMxSY;dnemZ_pfvN#+*+3%lfXns6R8iMH> zPo$dPgNC``eceA{(h=8SNw^#fGfXH}=A5cape1y*9E_d2p9#twY*N1m&B&1dg znVbwbxd>;M%grvQTduLU%3Rd*gWl21FU$i+Mhlq47PAs|o)aw*_;y8VjX<&qYc z5P=CuYP$Y==vw$bocTFDSB9=IDfF!)EHuuf?w^DkCX~>gzOz8?VO}OPH~w`p7rrUP zUOEL6JD4;y2dsW-=tS3O*9}&r5mEMlCm?kM{LmTA&9YaKAl;Hp_I3EV62amfPGXZ^ za=Il57vxv*NCCerdAzdQ>vVaPqNF5m7E_1!g&UZ3wD@Ro5GIG#&yMlu9YTTO%_{ZH z>b^Zp3bMZ7_@Usnq{J?lK&?-5$UB|QvgGtjUXK$;$^o_w9g`N{!AV}ciaxK7P(`3M zcDL-}yD@jvFfvYT8GWMn>_o%RmEg<7lB1Ph+^Vr;p~WXlonVVUpnlk8cY`q=Ot%Z` z_q4R!t1dYf`D~$$nKTJvX;Q>KuC|k7U3C6HU+|2%H#4jZHt+)zB%M3S9Jfy~hhJ8t zX1mMTB+gFq>2AB&OH*}SrM(C%Jy&Q~x^4_z>Hjz>w^mIt;Z7$hCEekl_ket`U`0?s2!myi}AY9hy7RGinI$W72u$l zssHm0go(ypwoUAa)l*>e(z8oXj_Gw@*T03zLl`mPi~4rcH@2G0a#%Um zL;MUI_`5aqPQVd`{N36JTrW62xad6hN3_#f1Wbv33FaOf7|Ks@*@E!c9B~f^-$xm<3RGG4HsdT zQ)z<>vl`9;u?fD6_HKp#> zBKVAM6sZsDzG!lbPY@B1P}8)}xC+w2sB%Rc`Cnlrn??F}gUuwk+| zBLUKUu5oa$5NalAGvrpukWae;xwOOJB%Q-d2WxB^E22MbWKM+$8(@`+inx?zsc&Q- z-(%CzoS|!D)4rIin{Gy}+$=kHk|pyrJuEjX{&jrLxS{6m-QxrO7bcuBgQr93dt7|5 zLv|_lNyc6>hxY_ahOWho&F2{jnzw~^JL#+@R>mrs72$KOwn}4JrPWePY{}ee_eOnr z^JPOg$fQ%RkEZCd7cDHpe*s+g?_YJNk6A?V!+Zft(tcP3>3jfHh z7Oo;|hT`hLpB*a9%hh}blgWuW;_40wrxd$k8hd)^O3$x*AHrJOn1Vkq^RspE*;aB4 zZg`9`J}H2WVk`nyr?$eK8(~Och1@HeI#i)^ z9ond)!!DV;K4*uFV5Q05>~q4g@jz?UIa}SN%G{n^>!dbC@%q=TTnX*v2G$}zuE_38 zWNH4`1!kh?qG!(7KxlKgQX_F@6++y=}a&u8--|1`> zYbuo$?uEx<%@-7rsK5@5=(sZ5?SYo(ggK((mV_`v@Y>NVjhUH|v=}ka6qg&D9m)BS zNK)1(F8)C#i?T@iY|o@9DCWL6(7RTcPHq0&?LLGnQ=%|WG#o8PY6dH2h1x(PrD6(` zQEkGpt$=2)V74f9WyMyJsmrR`*}C27hD8;o2Y?pVpaG_BwKNdYI4~3Zs~RW+t1i$o z*40?8JjjXz&SdR4t1DTXhSkvCv9c`*+H}Bqb#Q4N-sE6XsIsqLLzgaDDy_A`V@JH{ z^Vl7ma3ItL#lmI?*gBd$J03VQl6#G!uCFP#*tnIBhfdweOxS|x-+E{z7rra36RVKf zJ!}bbDogOj&)-pOO7BQ-`4Fo*p?_BJh_wa3uLE2OTZ56i+1-HpdK`9|XFZ^uUxKd* zRFJMC4M{lHuwos~KTr>bC=Q)A_^hf^*JBrng8v=b3MsuxjxR#a{Wu?mbj-$;z9SP2 zly%bF-}_lDlis$8{73N7fiX4QECPT2H|ZlAF@?<_bryQ$?17V?scNl3SgXsMV83jq z6yjz7%-+TzJ6cRD>pP2t;V*`+j4XovnT&FJPg14hctkc+6qCgNTkmm6N~c%8XGzHt z$***}@TtS@YjwI;kUzanDp}**efN^DtKgEf-sOygYw{>a;;xg{6m!Up9v+WRVw@z8 zo04!)bZs8Dyndz2`3Imbb2*#ar9!*IAyJN81O$cLfcl&5Zm#z4uZ011AYvC^x%d4C zPE+dfw1Wrj6c@x;R$3S*o=m0$yDZC?MdVGLaP*w*GKi7vUax+}^(#Ftu}IPz<{G<` z@(nc}Z@|m7OkpHmd)v_mAr20Y&I&>dE*%K<^bHE}jBFdbjYbO^qTvuHNq7y&_EOFx z`9x+`a=bifz^P>6!y3wIB~qtsr~D`O)#F0~jz;Iyko#eAYV| zI(JCtV37bL@%TjCdRCUoARJs%y&mE8bjTe|u!ZoQ<9A>Z(#*kv{(|s6oRxy{tJ=!) zkb#k1h$bOzvag-n?fC`*cSc5*S$Fl7sQ<@-G;64R0ys#_j4|GC!>epjliFRd%9 zttb^PLsA0rc~L?N@4*vAiP32IY+hUXfG+PZ*eofv8Ug6nT=N1}a==%rRJZJNX%op=^qbU<_O?bHGXPBW!8LGa9&O zIPCs5M9fK+oRG@VNXgQYF$u%wNA%XY%%jDZZ3uvMg%@_OhT_X=7hHV_ZN^IoMg*g( z%9*s*r-z9t?`4#UA|O$#1Db+&I;iE5l?>guv=qlct;1g)7CA@CKXeaALPTwSg`8fg z#g6dTQ6#CgdYA*krMIx3uR3E@8?`AE`9a79f5=n$Co2sA>>b)9}i z?f?a95T_flGhwqtnjMQI{`Eh8v7da9E<>L}1)5W@^}uU7)-&=tnIZ}uDS0Q@)3Zzz z8}S{LSn@_9qbR}6BuZOHyef@0S*6WKw1G3u)>hd^>_T$i&ogjTx+PO1X z04FQL2=mDgg+s~REo3hfmQ+?RdJjMY&qhM2D0W0&NJWWgJz;5L@j7{rC)f}p%WA1Q zx7OL*W|McvB&TRQHRh(n(4ihmGM`%~@|AvFTxN=f&)N`EG(4VcSmyCX7kfv}jz@Fg z8EQ;B*$C6%-U$Q7+zj<-6J^$UT9jSLoK7~#aN*^nOasrbd0J6%;PAC;edp%N4C1eU3PCZFJ3uUPX*Pecq9P^0| zo_FZE)YJd5C^5%W-K$DvMAAs)$P%0;%>_kBxg1$Q<@%%F^CL;-cKX{;cITY|B0oU_ z-t3`@p`V-~2htTzmtP1+lwy&E-vMegE)%_j()iW5T*BP4HV=A@qzLQjn5Y>2Q^cNeS~NK z^`mA-M)Aa#C!i#qX+E5h01tvGD3y>q@PJ+gm?;pJH5&5D(Cy&q(AJ!=(DLL)u{>%N zb(H6J-5BZVZR~+MBU=!ir5x1*7dBMdz}0=+EcuaP2}(UTGBBFd)lFAR389_>EUzA} zXeF^KEM0z0h#?(yDw>3MUno9)m)Ix{aezrZb3#4%<*BayB&Iymsp@r&3C zBoHyCB}0uN6Q@FwF6z@5t+ln)ygU>`ae7$kwjIAqqdCoL+mwijj)(?g*jQc7Q_Hc4 z*hYlR(NH;UV-1gxV}K0D|3X(5Fl?&Wm^fKFQsg#f)uv0U6e-_WLI9lI zM;1*OPVUilDrQt~*iczfWlaDzj6S2IDz%!|Ok<`?A6XiMD!sZYDJBzGU;%06x=tix zjisvGk}zpHB};X+*YrA6@5&O{VHjE3J*=(NV6$$mNx)?w&8)#>Y_o2vKrt`@%*3|C zFl24U;U~ggjLp z1zNh4jH$X#+J;Iz+>A*^Jr`Dln+{tO*A6RmbA&AJ5|;!&i8P^bpQurEP=ud|M6MBN zBrOcRjYmE``5LvNkyu9kD{4}Ne>EB|KT%1IxZ&r!f0CflTWxThT(oqwp6R-0QMl!K zzm|ZDdP-}N;<S6ZlY-kUegp28-Us)Sqs@GbSCmCUg*{6)DH>n`PR@#Ih8(llHd}vN2#?~gC zEixq(TC~VYbDPS7$q1lwjy5*UQqEPmsm|X<;e*ekHUO(Ky$LQzQ=~;1E{VRGbFQec za=#6SWK*Dt8lHV_^bpeA@hBk|CzfdwXH-^O%GJ}H06AI^^lFf3>f2hqjcc=b!2FT@ zXO9R`q-07k+W&&CyGH`lmq=3NkPr+dBZ(@fbqpn;@k82lnRRuWq%CqMkC@{pET$4U z<;BBF-{WA%5}w?os-jRHoL%H9Cv4JU$`KQ5q$P_{8FF}Jzk7*-CP^oVL@*#2n2g9f zf8ROL56+UzyfAj=HoG6~4pKW-IOV)4W-|I;%nd8O8Nt1jjHEo4ew`HJBaelEKxDUq zpNt@9KYobT-_3YQTxD;_KDd?wi6eU_8p*>x{b=aJXx1yd4^8{PqF*OLh0432C1Pic zfq{=L3jY+V^^I!vyO@&6*dRLDp^K)*Lx*Cbp?kRZA$Xh+s!5ya2DT%3fd{`1%7y|s z7zV{Jk<5s?1f4?4wRrJDw3*DPw|N$5)o3|8InARA#shM4GJz2 z8x=_wM3B_ZB6oOQo=%yXTrgXeb(^(TvisW!l9Pav9)_c~6^E58zId^w4o!Xzh`riL zFsWC0usD*-ET{;POyYTc1Kp|6V2zem6z@2gjc!F~_c{!8uR{aNQ15ai0W=RC8h7WNJfNRWFl$bW%Z1ocOa9Y>JWX;Z zZ?as0Eyi~F>@6+g;?7Rw75HTmdXG{Y%v?v34r{0l(VM9@U;ELc%lFr;CjFw0*X$r0 zeD>0TF63ZGz2WC6txV=vM%u64v&ReMW% z;U5e>+da&rcN#HOv=eVJrlBq^$?v789|wb)Pk8c9Mh*xiQ#6@OwuG}w2PM+H<5bk8 zn4N2k=n_c1z?Q9QD4g*hKrl`yfe_ z60yull%_a*k!x|903=6rjHg&g&r+v|%1y-6tI&~Tr{76QBnbE`qFs^-4Y-4e24fGZ-!k-96D}=MssrU4?%82;cD13*&sAFF zS^xyN1%r6X)=v3aq{tv2xYh<|5ZA=CjHaFU|4DxI?b%&W35s(kZf~M(nfrKj4k)|A z@vK6L(Ay?0T~o}3Y}q7Y#m{pXCOy&wLwK#Z5BEgcdTwB?-rNul1qv$ zqIv|`VmC#3hW1F1uBt8dQcd)lNvJY-tuHusfYep6U@&q;BzjICRM*EVFzDezA&K&t z$?l5K(cqUwoE=E!;WDBQQg<7~?rO!g5T&hSl5MzcWYMUBtsGfI#ldbyfl(~u;ttfU z@M?5S(yI`A$4W0R$|i1x`OQx+6!*Unhie+)+A5=n)+~v#T5_IW5A}3UyZF%=GrSyE z@6EBNAT&2|Z^I$PMLk0}dBRALP@!etOZy>iZzfX{Lsy0lU1+48;OD9#>c!C6rHdNT z-_*-l9Rq`OO2fRoaF_Qacz}i26OGVsw6VVt?-V)~iG3e0~mB5rT z@_NJ@(}eLN@r1Tg(^!&UR6}{p<*=iJ7MtDd3*ed=uPnk&^P|BJZM!UcBl3c~u5fax zzE~tKCfXG$L#iq8NcTT=r;y`B4m(#L0ZssXEcNP15u#wb8;w-0pbM{6H%e0M?HC{< zZHMv-S1m-g8tU<@h|mv_kS|drHmT~dAfoWdQc|~2*N4RTNGUdP>xjubq*cqe8tXP} zC;cY#VkW8qUMk26s-Ycqmeos^RrqgcURLkwY3!cloKRn5oa2I%Qi->8_pG%xt3-XtcL86WuTnUG` zzqz`1@nzf46>&v1;(Ji(TinnbcM<$(0XnkiaO@5a_kWcuqsMTi68COtFGNxvTGGl& z3F=I_*eTWYEYKF?jV^{e!(b-A!>)?K61r&Ouv4OduD6hgL1KiBKxUZMOO8h?;v#~; ztxw2PQN(XpCxlJK>6a|l(gl;Thv#7;Av<|R{92CI7og?G)e>O{agr#Zgy5E;nG06? z%#Oa@q`kG2ka{5y5%DJxn@i0Tkz(4o3mRfSMtloW@PBfwlQF4%1$Iy8BLY2 z@?e|VF%mN(z9gl)P#6QJOH7hHXr$x`9-zB~-^t>oy2%E{)J${Kfg4fRu~6nDp(=7H54059TtdgE6#eBH9*~zM;Byqqumf2b>?RKR??5{Ok=L uAC>Hd@ThGLq9tCBZcY>lrNiO1#^2qUQ-?-WekYpj4l1a0HNqdag#Q85A*7H1 literal 0 HcmV?d00001 diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts new file mode 100644 index 0000000000..fd643224cc --- /dev/null +++ b/selfdrive/ui/translations/main_ko.ts @@ -0,0 +1,1212 @@ + + + + + AbstractAlert + + + Close + 닫기 + + + + Snooze Update + 업데이트 일시중지 + + + + Reboot and Update + 업데이트 및 재부팅 + + + + AdvancedNetworking + + + Back + 뒤로 + + + + Enable Tethering + 테더링 사용 + + + + Tethering Password + 테더링 비밀번호 + + + + + EDIT + 편집 + + + + Enter new tethering password + 새 테더링 비밀번호 입력 + + + + IP Address + IP 주소 + + + + Enable Roaming + 로밍 사용 + + + + APN Setting + APN 설정 + + + + Enter APN + APN 입력 + + + + leave blank for automatic configuration + 자동 구성을 위해 비워둠 + + + + ConfirmationDialog + + + + Ok + 확인 + + + + Cancel + 취소 + + + + DeclinePage + + + You must accept the Terms and Conditions in order to use openpilot. + 당신은 반드시 약관에 동의해야만 openpilot을 사용할 수 있습니다. + + + + Back + 뒤로 + + + + Decline, uninstall %1 + 거절,삭제 %1 + + + + DevicePanel + + + Dongle ID + Dongle ID + + + + N/A + N/A + + + + Serial + Serial + + + + Driver Camera + 운전자 카메라 + + + + PREVIEW + 미리보기 + + + + Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off) + 운전자 카메라를 미리 보면서 최적의 운전자 모니터링 경험을 위해 기기 장착 위치를 최적화할수 있습니다. (차량은 반드시 닫아야 합니다) + + + + Reset Calibration + 캘리브레이션 재설정 + + + + RESET + 재설정 + + + + Are you sure you want to reset calibration? + 캘리브레이션을 재설정하시겠습니까? + + + + Review Training Guide + 트레이닝 가이드 다시보기 + + + + REVIEW + 다시보기 + + + + Review the rules, features, and limitations of openpilot + openpilot의 규칙, 기능, 제한 다시보기 + + + + Are you sure you want to review the training guide? + 트레이닝 가이드를 다시보시겠습니까? + + + + Regulatory + 규제 + + + + VIEW + 보기 + + + Change Language + 언어변경 + + + CHANGE + 변경 + + + Select a language + 언어선택 + + + + Reboot + 재부팅 + + + + Power Off + 전원 종료 + + + + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. + openpilot은 장치를 왼쪽 또는 오른쪽 4° 이내, 위쪽 5° 또는 아래쪽 8° 이내로 설치해야 합니다. openpilot은 지속적으로 보정되므로 리셋이 거의 필요하지 않습니다. + + + + Your device is pointed %1° %2 and %3° %4. + 사용자의 기기가 %1° %2 및 %3° %4를 가리키고 있습니다. + + + + down + 아래 + + + + up + + + + + left + 왼쪽 + + + + right + 오른쪽 + + + + Are you sure you want to reboot? + 재부팅 하시겠습니까? + + + + Disengage to Reboot + 재부팅 하려면 해제하세요 + + + + Are you sure you want to power off? + 전원을 종료하시겠습니까? + + + + Disengage to Power Off + 전원을 종료하려면 해제하세요 + + + + DriveStats + + + Drives + 주행수 + + + + Hours + 시간 + + + + ALL TIME + 전체 시간 + + + + PAST WEEK + 지난주 + + + + KM + Km + + + + Miles + Miles + + + + DriverViewScene + + + camera starting + 카메라 시작중 + + + + InputDialog + + + Cancel + 취소 + + + + Need at least + 최소 필요 + + + + characters! + 문자! + + + + Installer + + + Installing... + 설치중... + + + + Receiving objects: + 수신중: + + + + Resolving deltas: + 델타병합: + + + + Updating files: + 파일갱신: + + + + MapPanel + + + Current Destination + 현재 목적지 + + + + CLEAR + CLEAR + + + + Recent Destinations + 최근 목적지 + + + + Try the Navigation Beta + 네비게이션(베타)을 사용해보세요 + + + + Get turn-by-turn directions displayed and more with a comma +prime subscription. Sign up now: https://connect.comma.ai + 자세한 경로안내를 확인하시려면 comma prime을 구독하세요. +즉시등록:https://connect.comma.ai + + + + No home +location set + 집 +설정되지않음 + + + + No work +location set + 회사 +설정되지않음 + + + + no recent destinations + 최근 경로 없음 + + + + MultiOptionDialog + + Select + 선택 + + + Cancel + 취소 + + + + Networking + + + Advanced + 고급 + + + + Enter password + 비밀번호를 입력하세요 + + + + + for " + 하기위한 " + + + + Wrong password + 비밀번호가 틀렸습니다 + + + + NvgWindow + + + km/h + km/h + + + + mph + mph + + + + + MAX + MAX + + + + + SPEED + SPEED + + + + + LIMIT + LIMIT + + + + OffroadHome + + + UPDATE + 업데이트 + + + + ALERTS + 알림 + + + + ALERT + 알림 + + + + PairingPopup + + + Pair your device to your comma account + 장치를 콤마 계정과 페어링합니다 + + + + + <ol type='1' style='margin-left: 15px;'> + <li style='margin-bottom: 50px;'>Go to https://connect.comma.ai on your phone</li> + <li style='margin-bottom: 50px;'>Click "add new device" and scan the QR code on the right</li> + <li style='margin-bottom: 50px;'>Bookmark connect.comma.ai to your home screen to use it like an app</li> + </ol> + + + <ol type='1' style='margin-left: 15px;'> + <li style='margin-bottom: 50px;'>https://connect.comma.ai에 접속하세요</li> + <li style='margin-bottom: 50px;'>"새 장치 추가"를 클릭하고 오른쪽 QR 코드를 검색합니다.</li> + <li style='margin-bottom: 50px;'>connect.comma.ai을 앱처럼 사용하려면 홈 화면에 바로가기를 만드십시오.</li> + </ol> + + + + + PrimeAdWidget + + + Upgrade Now + 지금 업그레이드 + + + + Become a comma prime member at connect.comma.ai + connect.comma.ai에서 comma prime에 가입합니다 + + + + PRIME FEATURES: + PRIME 기능: + + + + Remote access + 원격 접속 + + + + 1 year of storage + 1년간 저장 + + + + Developer perks + 개발자 혜택 + + + + PrimeUserWidget + + + ✓ SUBSCRIBED + ✓ 구독함 + + + + comma prime + comma prime + + + + CONNECT.COMMA.AI + CONNECT.COMMA.AI + + + + COMMA POINTS + COMMA POINTS + + + + QObject + + + Reboot + 재부팅 + + + + Exit + 종료 + + + + dashcam + dashcam + + + + openpilot + openpilot + + + + %1 minute%2 ago + %1 분%2 전 + + + + %1 hour%2 ago + %1 시간%2 전 + + + + %1 day%2 ago + %1 일%2 전 + + + + Reset + + + Reset failed. Reboot to try again. + 초기화 실패. 재부팅후 다시 시도하세요. + + + + Are you sure you want to reset your device? + 장치를 초기화 하시겠습니까? + + + + Resetting device... + 장치 초기화중... + + + + System Reset + 장치 초기화 + + + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + 장치를 초기화 합니다. 확인버튼을 누르면 모든 내용과 설정이 초기화됩니다. 취소를 누르면 다시 부팅합니다. + + + + Cancel + 취소 + + + + Reboot + 재부팅 + + + + Confirm + 확인 + + + + Unable to mount data partition. Press confirm to reset your device. + 데이터 파티션을 마운트할 수 없습니다. 확인 버튼을 눌러 장치를 리셋합니다. + + + + RichTextDialog + + + Ok + 확인 + + + + SettingsWindow + + + × + × + + + + Device + 장치 + + + + + Network + 네트워크 + + + + Toggles + 토글 + + + + Software + 소프트웨어 + + + + Navigation + 네비게이션 + + + + Setup + + + WARNING: Low Voltage + 경고: 전압이 낮습니다 + + + + Power your device in a car with a harness or proceed at your own risk. + 하네스 보드에 차량의 전원을 연결하세요. + + + + Power off + 전원 종료 + + + + + + Continue + 계속 + + + + Getting Started + 시작 + + + + Before we get on the road, let’s finish installation and cover some details. + 출발하기 전에 설치를 완료하고 몇 가지 세부 사항을 살펴보겠습니다. + + + + Connect to Wi-Fi + wifi 연결 + + + + + Back + 뒤로 + + + + Continue without Wi-Fi + wifi 없이 계속 + + + + Waiting for internet + 네트워크 접속을 기다립니다 + + + + Choose Software to Install + 설치할 소프트웨어를 선택하세요 + + + + Dashcam + Dashcam + + + + Custom Software + Custom Software + + + + Enter URL + URL 입력 + + + + for Custom Software + for Custom Software + + + + Downloading... + 다운로드중... + + + + Download Failed + 다운로드 실패 + + + + Ensure the entered URL is valid, and the device’s internet connection is good. + 입력된 URL이 유효하고 장치의 인터넷 연결이 잘 되어 있는지 확인합니다. + + + + Reboot device + 재부팅 + + + + Start over + 다시 시작 + + + + SetupWidget + + + Finish Setup + 설치완료 + + + + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. + 장치를 (connect.comma.ai)에서 페어링하고 comma prime 오퍼를 청구합니다. + + + + Pair device + 페어링 + + + + Sidebar + + + + CONNECT + 연결 + + + + OFFLINE + 오프라인 + + + + + ONLINE + 온라인 + + + + ERROR + 오류 + + + + + + TEMP + 온도 + + + + HIGH + 높음 + + + + GOOD + 경고 + + + + OK + 좋음 + + + + VEHICLE + 차량 + + + + NO + NO + + + + PANDA + PANDA + + + + GPS + GPS + + + + SEARCH + 검색중 + + + + -- + -- + + + + Wi-Fi + Wi-Fi + + + + ETH + 이더넷 + + + + 2G + 2G + + + + 3G + 3G + + + + LTE + LTE + + + + 5G + 5G + + + + SoftwarePanel + + + Git Branch + Git 브렌치 + + + + Git Commit + Git 커밋 + + + + OS Version + OS 버전 + + + + Version + 버전 + + + + Last Update Check + 최신 업데이트 검사 + + + + The last time openpilot successfully checked for an update. The updater only runs while the car is off. + 이전에 openpilot에서 업데이트를 성공적으로 확인한 시간입니다. 업데이트 프로그램은 차량 연결이 해제되었을때만 작동합니다. + + + + Check for Update + 업데이트 확인 + + + + CHECKING + 검사중 + + + + Uninstall + 삭제 + + + + UNINSTALL + 삭제 + + + + Are you sure you want to uninstall? + 삭제하시겠습니까? + + + + failed to fetch update + 업데이트를 가져올수없습니다 + + + + + CHECK + 확인 + + + + SshControl + + + SSH Keys + SSH 키 + + + + Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. + 경고:이렇게 하면 GitHub 설정의 모든 공용 키에 대한 SSH 액세스 권한이 부여됩니다. 자신의 사용자 이름이 아닌 GitHub 사용자 이름을 입력하지 마십시오. comma 직원은 GitHub 사용자 이름을 추가하도록 요청하지 않습니다. + + + + + ADD + 추가 + + + + Enter your GitHub username + GitHub 사용자 ID + + + + LOADING + 로딩 + + + + REMOVE + 제거 + + + + Username '%1' has no keys on GitHub + 사용자 이름 '%1' GitHub에 키가 없습니다 + + + + Request timed out + 요청 시간 초과 + + + + Username '%1' doesn't exist on GitHub + 사용자 이름 '%1' GitHub에 없습니다 + + + + SshToggle + + + Enable SSH + SSH 사용 + + + + TermsPage + + + Terms & Conditions + 약관 + + + + Decline + 거절 + + + + Scroll to accept + 스크롤 허용 + + + + Agree + 동의 + + + + TogglesPanel + + + Enable openpilot + openpilot 사용 + + + + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. + 어댑티브 크루즈 컨트롤 및 차선 유지 운전자 보조를 위해 openpilot 시스템을 사용하십시오. 이 기능을 사용하려면 항상 주의를 기울여야 합니다. 이 설정을 변경하면 차량 전원이 꺼질 때 적용됩니다. + + + + Enable Lane Departure Warnings + 차선 이탈 경고 사용 + + + + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). + 차량이 50km/h(31mph) 이상의 속도로 주행하는 동안 방향 지시등이 활성화되지 않은 상태에서 감지된 차선 위를 주행할 경우 차선이탈 경고를 사용합니다. + + + + Enable Right-Hand Drive + 우측핸들 사용 + + + + Allow openpilot to obey left-hand traffic conventions and perform driver monitoring on right driver seat. + openpilot이 좌측 교통 규칙을 준수하고 우측 운전석에서 운전자 모니터링을 수행합니다. + + + + Use Metric System + 미터법 사용 + + + + Display speed in km/h instead of mph. + mph가 아닌 km/h로 속도 표시. + + + + Record and Upload Driver Camera + 운전자 카메라 기록 및 업로드 + + + + Upload data from the driver facing camera and help improve the driver monitoring algorithm. + 운전자 카메라에서 데이터를 업로드하고 운전자 모니터링 알고리즘을 개선합니다. + + + + Disengage On Accelerator Pedal + 가속페달 조작시 해제 + + + + When enabled, pressing the accelerator pedal will disengage openpilot. + 활성화된 경우 가속 페달을 누르면 openpilot이 해제됩니다. + + + + Show ETA in 24h format + 24시간 형식으로 ETA 표시 + + + + Use 24h format instead of am/pm + 오전/오후 대신 24시간 형식 사용 + + + + openpilot Longitudinal Control + openpilot Longitudinal Control + + + + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! + openpilot은 차량'의 레이더를 무력화시키고 가속페달과 브레이크의 제어를 인계받을 것이다. 경고: AEB를 비활성화합니다! + + + + Updater + + + Update Required + 업데이트 필요 + + + + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. + OS 업데이트가 필요합니다. 장치를 wifi에 연결하여 가장 빠른 업데이트 경험을 제공합니다. 다운로드 크기는 약 1GB입니다. + + + + Connect to Wi-Fi + wifi 연결 + + + + Install + 설치 + + + + Back + 뒤로 + + + + Loading... + 로딩중... + + + + Reboot + 재부팅 + + + + Update failed + 업데이트 실패 + + + + WifiUI + + + + Scanning for networks... + 네트워크 검색 중... + + + + CONNECTING... + 연결중... + + + + FORGET + 저장안함 + + + + Forget Wi-Fi Network " + wifi 네트워크 저장안함" + + + From c9fa5ef11a6d47a886b30f65b2064b2d6ae05807 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 8 Jul 2022 00:23:46 -0700 Subject: [PATCH 240/302] AGNOS 5.2 (#25011) * AGNOS 5.2 * casync manifest --- launch_env.sh | 2 +- system/hardware/tici/agnos.json | 16 +++++++++------- 2 files changed, 10 insertions(+), 8 deletions(-) diff --git a/launch_env.sh b/launch_env.sh index 769613bc79..ac84d6dcbd 100755 --- a/launch_env.sh +++ b/launch_env.sh @@ -7,7 +7,7 @@ export OPENBLAS_NUM_THREADS=1 export VECLIB_MAXIMUM_THREADS=1 if [ -z "$AGNOS_VERSION" ]; then - export AGNOS_VERSION="5.1" + export AGNOS_VERSION="5.2" fi if [ -z "$PASSIVE" ]; then diff --git a/system/hardware/tici/agnos.json b/system/hardware/tici/agnos.json index 004a0f9dfb..853d3ab434 100644 --- a/system/hardware/tici/agnos.json +++ b/system/hardware/tici/agnos.json @@ -1,9 +1,9 @@ [ { "name": "boot", - "url": "https://commadist.azureedge.net/agnosupdate/boot-bb71f49294150c4233b89e2a10768a5a3de003203ecd02e3f845821b35cd409f.img.xz", - "hash": "bb71f49294150c4233b89e2a10768a5a3de003203ecd02e3f845821b35cd409f", - "hash_raw": "bb71f49294150c4233b89e2a10768a5a3de003203ecd02e3f845821b35cd409f", + "url": "https://commadist.azureedge.net/agnosupdate/boot-243ddbb9e2256aa7af7fed0daf8cff4017a3c838c759373a634b8539f271bfb8.img.xz", + "hash": "243ddbb9e2256aa7af7fed0daf8cff4017a3c838c759373a634b8539f271bfb8", + "hash_raw": "243ddbb9e2256aa7af7fed0daf8cff4017a3c838c759373a634b8539f271bfb8", "size": 14780416, "sparse": false, "full_check": true, @@ -41,12 +41,14 @@ }, { "name": "system", - "url": "https://commadist.azureedge.net/agnosupdate/system-11fdbc9e8a9cd27f98346d7e1039bc5b3032d0e892ff95fa1258673ff1809bca.img.xz", - "hash": "45b4719a9e580617cf840036b24fb0dcd32491edd9654d8d74c28d91ff362d36", - "hash_raw": "11fdbc9e8a9cd27f98346d7e1039bc5b3032d0e892ff95fa1258673ff1809bca", + "url": "https://commadist.azureedge.net/agnosupdate/system-59622eddd068d49f2e9df69ef5115e3f205ad369539690a5b240c8c93796dd13.img.xz", + "hash": "44da205d17b44b2be7c94854a6bb3efb2928ec9a9889fe62af8b322d2295b74f", + "hash_raw": "59622eddd068d49f2e9df69ef5115e3f205ad369539690a5b240c8c93796dd13", "size": 10737418240, "sparse": true, "full_check": false, - "has_ab": true + "has_ab": true, + "casync_caibx": "https://commadist.azureedge.net/agnosupdate/system-59622eddd068d49f2e9df69ef5115e3f205ad369539690a5b240c8c93796dd13.caibx", + "casync_store": "https://commadist.azureedge.net/agnosupdate/system-59622eddd068d49f2e9df69ef5115e3f205ad369539690a5b240c8c93796dd13" } ] From 5b4e39990ac4d098f874c8f1e378e2ab855c0036 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 8 Jul 2022 00:41:17 -0700 Subject: [PATCH 241/302] Add Japanese translations (#25078) * Add Japanese translations * test japanese * update tr file * test for unfinished translation tags * add compiled QM add compiled QM * mark as finished * remove from tests, needs some design decisions Co-authored-by: PONPC --- selfdrive/ui/tests/test_translations.py | 10 + selfdrive/ui/translations/main_ja.qm | Bin 0 -> 19159 bytes selfdrive/ui/translations/main_ja.ts | 1207 +++++++++++++++++++++++ 3 files changed, 1217 insertions(+) create mode 100644 selfdrive/ui/translations/main_ja.qm create mode 100644 selfdrive/ui/translations/main_ja.ts diff --git a/selfdrive/ui/tests/test_translations.py b/selfdrive/ui/tests/test_translations.py index 2dedf3d785..3230a99543 100755 --- a/selfdrive/ui/tests/test_translations.py +++ b/selfdrive/ui/tests/test_translations.py @@ -61,6 +61,16 @@ class TestTranslations(unittest.TestCase): self.assertEqual(cur_translations, new_translations, f"{file} ({name}) {file_ext.upper()} translation file out of date. Run selfdrive/ui/update_translations.py --release to update the translation files") + def test_unfinished_translations(self): + for name, file in self.translation_files.items(): + with self.subTest(name=name, file=file): + if not len(file): + raise self.skipTest(f"{name} translation has no defined file") + + cur_translations = self._read_translation_file(TRANSLATIONS_DIR, file, "ts") + self.assertTrue(b"" not in cur_translations, + f"{file} ({name}) translation file has unfinished translations. Finish translations or mark them as completed in Qt Linguist") + if __name__ == "__main__": unittest.main() diff --git a/selfdrive/ui/translations/main_ja.qm b/selfdrive/ui/translations/main_ja.qm new file mode 100644 index 0000000000000000000000000000000000000000..552545cf879ed5c9a4009e63d334dee10c479e33 GIT binary patch literal 19159 zcmcJ0dwf*Ywf{~sGf5^-9!77<;{YO{B-!D0El};`K@v$O$xK49h&Y)!^I#_DjPnRY zFDfnG@=~~=prUrS{gXhf5+H0@9_S);cm;c0f$qOIcxA&zPQ=Yxy+dq4~i80%^7%TjgvCDtJSWy7a zSMc0`=U?%>i?J&vGiJf>l}|HfZD4HvGCc8b{&qaqXfX7gS<6`QA;8rzR{kr-W;q#a z-NIPozc6;qR^Y*VryI|g80&3htmJY$gN#i+hv)6Uhj9sfz9_~lU%i(xc1C*^9oC++ zlG@X8j9Kn}i?M>!S}dR`w~gJ^2P` zn!}2v)xh7*im&)RK6f!*g=bk8Ydd-~WA%)+z58Rv7Qe~bO9vU7AhBzf>;)Yle*^e* z#ah-K*@N|svYtO;{>jIfYtx5}Em_F=3ZKLG|IYdbH)9giNy7c&HFw(JgJ+psmIyd z+mpb%w4mnm^BKEzS-~aWxRkLupDS2=C-!GSZ9(tz^YH!O3icnv_shx(e$!_G-Wv)| z6n=-XDPJmhZ{ZfkY8wmffnPE<_b-LB-#&$L?-#DHCqUQN3$LrjdK;fA{QB=p0e^Sl zQ#(P|LVw}UJMLtxx~A}Vy}&zlUg7IUvA+!!g(tst5%BFRn)<#K@b4GR+;KJ5b8k_y z7x+G3P;{UY^v+*f^u&`r7=K^U(@y}t(NT1G&MlA=OVP^{|Au`VE&3?=Ah=p*X?^d1 zF*eC#x#8g-f}W$6PzS!Qe#0_y>MF*hBFk4TXBoTl2Fu+Y&tSa%ta?cMJbjwwz6UKm{h|M(Yc!2WZ{N!+^rQqa4g)4HDI$vy*5 ztfRzj9r14j{CVrmiz*@ScUgDr10D8m?Ky3+_MASXJ)8Dh@7o1AD0|uZz(3!P_5P>z zv0t5JjK5<2#i!tN;ZxSO$W!P>82T|X^;OnDRY-&Fj8>wfU<_Tv9{;vc}LEyaI34Zak;U;N3k zKViQwE@_^380TO~$u&iwyV_kM|M?TpTUv5QazA6A`+CVY4*=h!*(E=Idlo(qmKIm6 zgZy|)XWdtVb9JE9@z((07nk<0d<*o3N>_aad~5!7>6+`n=gXv0-}6nN>#EW_*~N^p zM@xVIniF#6EPZ`~3O#j&-EjrFxGy?@h&dUyJ7#7@K{IeaD}w@cB9W z*Zz+EoqfQ5_cPxCJqPUfo#=u|LhNIKOuLF9H~6joA;| zr$IhnvmdTm4tn0Vzw1qaf6lUkCvO3~uWZ(#UqT+ADqDLBdSKR+vKxPA0lg2EZ62Ns z{#{)5{QKCSIU{99y1=JNAC*r&gn8@Nl+Snq-_L%lyzUDlkdK?oS2Savul`>7HCL|1 zeqC0+vI*;7e!P6uUf`RyvwX-&^c*X{>*E28zoPt!f5ADMdT;sBZ-HNpmF2&F4bO(o z^4FdRU6#`owg)f8xt~?hF!fc?zp~=|Q`DlhupgIGs#W$jn7-if;^XMWTSzQil9JPEzS_g1dl34TrdL*=%6 zajxezRDS(WU&KBhul)W4z`Nu?<5I0oa1n8%xNMC4eafPiay@3>=w z>lh#4ettiHj=#!(#n160#^4Dqc~Dgol1K4L{ZXGMF&3f{|A+G9J=cW?jiD88MOAN- z#~)VC9IS^qnY6ub&39dy?igDYDV&tOEBT&id2 z0%T6)&+{kwX;U=SI+{K?5tL&WKxA;MS9aZNP*U2eB;=R`o{hH_Nq!u=+>$}cZ}~y~ z0oHevk7nVUqTy5I4N@XSl@#^F<6ymSyeZ0A2kU_t9p&%yg9dr_jvmS3^Tp(Ne7wPv z%_uXFOf>i-_53#|sl4f?u!RRUpLQL~60A89*)uFlgAtDsmi%f=@+1@LkS7uHN?uj* zhXTnMKB&rggxdL|{7vlTPx%>xJXt$d6!4&oGJ2W{t*l7wH4%OGzc9 z#1o!KM4H`5#U1ZPz9X5BHUO zs_3_MzudN&ck(8_o!^4bg~sH~*Q!ZrC>e(q@p|QGLV~1AeR6ClF4PKG;0qD6;!;SF zAYzc^geoQDvZO|3B^rvTiF#8~moo|K>J_Z}AXl{&v&Y4A0e%UJw}tvQi}>isQo*T~ z9P;K%pf4u*5Jb*iNbieMbP#BdN0B397o@=ab#5Ns z_ldF_tSaVSDAO;0S;b)sfDtRtPd8XG%Mp{M5wIhk)L%Au6fi`^q#Lkq)$hMrUuyOg zHQE%0wk8f|B9_KP91{xM9P4}ys}ShZ{5X#7IsO#?6U1l~>guPk2S>oN+_|n8XRf%M zki4EqXiz&x=F?uPPkTg6_@dB@k6;&}h_>y>n{MGa(+!76NkN=o) zIPQx3IN$C(!F#*AZdG8L+3t|L276f$VEa#CWST3d_>25m&G>e^_fO)Z-dDQs)upS9@a65W2YeG~W6>UXnSlU@-|yP>w{QwGyGB5Ii4Ur3|S_ zg*+LY@wiZQ!txBtP>4F7Ayo+_RI>h(yfF$lK!!D`m*x)3!H^f5FO=sX^r7EB&y?RK zspD#pYjw4{TZMB24WF$`O7iy7HqKVsG$}U_+r|;%YGD2Wq{Pr8#wfc>4kRNUEONwj z0ktMNNY_9H4)~&^UYgVD#T3;gP+CMlu3kxd#22}=o$N~~jW$vmrpPYOw}wn2yT_#U z>u&p$NvHzQVQdq@g0RKVeGakIcA4Uc%aU z+-G^1En<)J0;e5si^W?R-mb)(a`WL;f92urbvVN&9)vm8P4{ftKfHy9gEPWj-p_Z! z*tWnkQDAHf23I1M38W5#fm7u-^B~`YSV8kn*5EzupM2MFGo+Y&V={z&5;jFYzBtx6 zdg2hnDcBH71mUJEf;&L$fWIQeLV=(bA?ZIZ#*azpftYk9-iWvL=}jgN1HL8{LQ+k} zBO_^ZsRZVO0EoCy766NRVln`9qI~AgN1^+yu|rltis=>=I_(BnVKQn8W7*WOy~Kbj zaddV{eH~q`1Zx-8#0{y93zw%v*RaP8aGQV-E`Bbs#ox4dj{#_Hhr4AC$HHvLfGb?t zWj3>ozX5xfJ`L8c5RRA`q@}lgciIIm?QyvKq=DAfm1eMZ&3aNSY!FbT>vg!xu~Z~l zB~}?*1w-KW%8KTNmmqw-#QnGP1;)^F$s6=gq%FtdGibiD4kemQWP}43h$8afCk9xz zb6<}zPwNr(DoiqFt8~hcOiuz5>48x(oo^zTmW~eUk;tt###eM`Apz`9eZ7#fQvDk_ zCU*N0{(X3dKj9Da$DmwC-LH24(OGxCHiLvoF4-%GhRK4dgX?8)BED46k%MR=j^@w# z8Gd}*n~|GxP)vk+S0e(2PmUx!<`^dPWBl7B0DP1(4mmigMUH}~@RL-S(qO|Ppiqs~ zTbnyu9WG*8NtY*@_Ug;ye;=63mEpe(ZyDeQ^rYrwEGENeZ-M;|DMqxIJ$56xE8F9n zIA0%Z@4cOG*&0Oj5#D=0siYfzxw?^$uDc6L%MG>E35C_A#UzlUI9!u%s7^Qc@NHmm zkR|XJWpTC?zFGtGLMbZvlkt|oF4E^A{CV*1VIhOg;Wn5`*c_#9aHNi&k`Ic_tHoKq zP&^v(jF8a491W?6MM!l?9%!baA&+E_#zI3ff|S9yHx`0Bqe6qZLji@y1a z3!0$1ZNutC{|!`>BDw&o@&McQ+x*QXDbC(op;@vww}$_3xEIgH+W8BxwojyDCWG}C z_r*qp0dabULji3)O>#o`;MtgJ18mJ<__ex_8PPNBlYy;9QDFfDS-!N$nUG~6c{7HU zq*7+YMte@)teTIN`$1NVa!Hxlp4`E;8G}3b?%CZh;$0C{8?#pq#1OWOi^dL%jcfwK zotefkE2U&+no(?VE!o$ThU@I;(lU3Y&f&m7NP&$NipmmT*UmA(in<)D30W@C?&;S* zWB^&+J*}-GxXJ-5A#21M{7nX^B|Ov+G(l+BOi~tX(NNS3)W)P8{=RDrls3uH+3M2# zbi|o4)#Gc&K@f|{g)P=#-9$lIF0h5PVH$0JPm7~ZSngcN!hd3RFg^XZ92z8o&j~gn z5VDlk>xo9O?f}G_fPpjKzv5c2r3!`9seT~N>lXoYAPQ!y6aQd zx1^~^q>#0F4*wrGU(R}&i~kS`1DTHPkMdi0J;QG$&Hq13+l6cfXnYMcolGvfYY>6< zaY5}H_y#n?xh??DU&R^}*t8Wq+sV5BB9TKx;YZ^hNYPvpHHIfxE3JH6h<`e^(aE=_qt$2eTdbykHRDW zjMFr!Y8X5SQ=E`xU1?#0crum}Y_lw57A;pAg8LT=%OFPbM5CEAE^kmH+9FAFl=pZ- zlxgTuqsgeyGt-Q$N)TIpfIkFB5nkTzS-z#@uB5h%T}C6d`O~41AV>2Wklm$BhxsIx ztnvB;SGr$cvpO(6BN~{{D2>P-%6wv1)ff_QG`^yT91w?ZAmj_kTBT~~g~S*sU&yc2 z)y>^bXKQm`y}(=V=pcGbai%EJx81-{rb(pO-!TW5%$dZbo#(bcY7DD9b>AMz-QVPH zc6BsqPJ!vP)l^(zlKeKFC^fjc3=HM78zrA-gsKJsm1ZvP?H2KnIB65LaTE^cjjX`P zAQaOWL-i?Lw!DE=7>EjFG9iyK)UuoPer!-^Y26qSXEcklak6|_aOM0Eq~|H*_zv)s z2F_xiCmuw!oWEcMj^`k3XW=tGfMO~N3dW#PBkhtmOs{shrUs^qtnO#6KnSIz=_pYO zup+e7)yM_n?hHuF#;3R6VNhG#td;eM)(oI=_?7{+NMA|#+D3T*M)el_TgMBv%<8(G zJluQ7cK_B+VQ#zm4ajP>WaOu23hE`l2O+JmUeYV_Q2PnQ8J++NA0lSYm@lo-JN20< zPezVLcHobwJ(X_KxTS~x8K|nU*#}XYJ&DSe*bajuY;`?$!rQAw6eC2AokEK>aw%05BC9)-X<7vjbMQO+fJj8DR1P!mKhm;0Cx zE^&f+Al&D`qVHhQTJ7u&-G*v`y~s8)iNq`%t7H}`A(1)xFX9-&qe9z;|~ zMQQPP-qN(iXUKjo!KNkXN>|7m?2|WUCZ|eL^ckCNgLy;Elcc}Wtz{_V8F5$T7@@E| z9RiOvw4A?0YC&`&JZ8*StVgV4kNO!BK}W#nhci++C2rN9*nq6*Si?$Co!#y~&)d@z z^{D~W*Mz+`TUjA{)qpL0?yj*ATg(ggR`5#qvX=9;Tyb^5!7dQyQ!mu>(KS1r|BRDg zfHU9CeS9TXMB-?4`y>8Jp(`?L>CPq@F*4FMvINJ-a551#&PVnyaq6~v;z)fdp?DC* zbW!Km@((2BUX|*BadLosNJoSsaZNzdG+vfP8Pzp2xD1bQBahP|HW*Ud98}R;B&FC+ z2S(2v5~DI!U(E&(0@kq=EX2d!2REgAeX5~Y$;qX$1EIPVB88MO(zav$UXU5W%)eD}>t5nPqb3KxbW!TCYqEPA7CT zCLN?^AE9N}v3}-aoxGD;n-E(!=^4p%nYB|0#IqnzJEUUk#8|E9LUG`zP;3+_=9{jb zRz-9=P$>+$mUObz@9Lx)$S}%y5LyyU`c<<(LVl_HBBnsPp`l4KkbR^90aevXAQ@{Z z*H@6;z@#@sVWJ$il_0UYnmSn0d`6m7lv_~Rh@t5tXMjCj7&eCJb!^mPbAanNpI-Za zcRu3$1gv~nu>ebWz zVg%#_6{vVP_bgYZbU3=ZM30}b0E7#or%z*f&LZr+cL?FnYyz|k=18PIa-hp8nRUJv zm5EOV(s{SZ0}hw7!`Ze}>QpyKt5hWOwXiN@=W4ShOB~kGb+@ly=d3dbojl-yt)pZ< z)}4}y916xitdnTu_y@LH?{g7R5$R%M`tlW;A{F|PrY#e186nN&G>`co5Lby7KVy8E zh?mn`&KtfnJskP0bS7VWPiOfhHur+T?>q>dK?2h3+4!Q!+=Y-?lbJ+OD<4fR-2UPi z;RXUwLO}C)V1ZFc?|5Nd9WlDt zje7i`M=L&A5Ms3%Of6i{W&*J=6Jntm#Nted#U>D0MyXhjK=Y=u@$VwTknV!9wz^#1 zqIi@=vkftBA4_`~MXi19dAN|Q-kmPkSlYU~MH)H>Q5*VW-Ny2Z+ImEUodsmse?pmO zfLPi)+VUr}u})CbYCsirYU$x@L4x4Q}>Xe#jut+T(DxIPxbAP1%&LDA?Sn?KS7K!=lW~r~z2| zTDyAkF;Q=jFDsW=-A8%k1YHyHU_+;1rQ< zMauO`*DbT-R%>&6YqMay38;-scZR|(5x~&gv`7kNqKfu`^Q$Vr(-?mRd%`WGw1@o0_OJ zl124|PO6h@1WRHCV=TBD87eo3ruMp@P;i$fyW1_TLUkX`$rxj|AorcyNZT1;6z=OO zIMHg)72!XH2diD*6dD;W16L?T1dR^YKNGh1orI0rYVLeNZ&~X^Jd z6Nv;PhBoL8^ufuB(6Z5-meE;@BCp6A`jZjrMWNkGe{MSn~R(nUHR-u-Z zB)WAs1d)&s&Kr3u@X(;ke4Lm&G^6dn-fy%sk1^VA zvUkPfZ`>s$FB~0)DA8wSYz&%fv|J2@EPgrR4eHDpg9Hnef{d|6juxTj?e2Jx!jYJ& zH4$H~pOAKzWP{kqcOY_4@^gI^T6cb?u{LnkYSmid2jUpDCkLr*I;Nl>k!Z=CqFe+T zze1t{ou&qo;?8bIi+<*FM_4E$V?d%!u&aBO(15vsHSm2NgKea!_F1@gC$VV{WhDF1 zyLV%fIvz>-d=f%0GXm{6Y;M-hq&-Pv(h|43U0NxRhzLD*+9hc=!Q+`D(yORkif(XC z;Rtq8K)7c0z+9ndGmGo9DMwB0lIF}t{mG}wab->dO_(8&im*dtsu`(^(lbj_XkOI% zs0Te~);&qnqW-Mxd4rxf+A5?lRyqEx|3UsX)kjf*+ew-rXFf&b(ZV8<)3a>7k-a-W z#YXBFO0gH4BdVyVLN>ZTfR@=o9YvbH!JP@4^X+SE0H3iIQ-NHMltmyN_370CMZ^!! z!ABX%NFvC(FSq6l1RVRvR0Vd%MW4UkkzlN%~5mEVM+G*5*KW zE{qdmbp%id6kvUHtHQV)Vxik123WCv2gC$$BDU-?p&ZVTp2@;q?e;=Np-2nW$oS^!bXNF4xnFX}9bW z{m`93n05&5Yk_TV?(>n*8$6qqzAMnJNDeR?*Yv1mTI!K~TEA~T+WFMX0?ji7Mh3wc z6$Q_3t#gGwi@vjbZ(ug2q7E=A9;I9Y4hprlh?Jp>oD+(%XkQs?A$Pv8=?}ZF+}yas zzq*l1nR!>^rs=}li5oKLlcSt9U3bw>uu$ar3z>*c;g?~Uj#6u1&Rx5UQ+MsC)3&ai z_C)kyl1SxanvyS7P?)(mQy1?HfiOq5&)>9rI$OvZwH}}IC89G0ok8bI`REc^LOI5egAV=ePWJk;VIYKs<^ z5IVQL1D(EZ^`gEK^6>C`n3Bp68w8v%tD@~PPpt3P8ZW7&fjgaOTvky>m!ZD~aTSu1 zCMXjL&ktL%A&7PXq0&+p3m~?B3=)Z94`qdsZi77FdK{cZTr@NCq#n^rD8u7-&uLq9Yygj7gC=KYp@Nhn9^U=g{}bPNn!HSQo3L2I9bOhPO)p<;JPYE?yX79V@fCdr^9c_U|FWZ@C-FXMFBW}8z!P1gCzJ&k2hqGosw=aKGGrH#b>q8@n! zr#Ii===DvU=R)`&il))T+Q}mkmmROal7}Pj;+kWp=)czDGQbLNYxLSu|A)eR3Fbv+ z>mbf3`H1{FwW8!+jr=!SJ#C<&g`~JvRTUAK&x77uY_T_%#I-b0v4kxahd>;3qCGl3T9_fcYY@La<;xDL1&Gd7D5kJ2se{(v*E1y|aqn z#)HC2<{PjT1EkAjQ6fbZAxdRljb^P4CS^IJWH~io4NcGb%|3(KW1Nk-rUcRzv>gLq z9{!NDJ4$&=)_vPhDboy;NO^;MiKGv`;SutFD8Mrp=~(_W{$m8CPjeL)w;BfT3pU9dJ1N}&|P^_yX$h^|m zM`}G)+KbaAL7+#!UQFE>f(@eUK8?D_ HImG`LJd!}I literal 0 HcmV?d00001 diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts new file mode 100644 index 0000000000..fbb654bc4c --- /dev/null +++ b/selfdrive/ui/translations/main_ja.ts @@ -0,0 +1,1207 @@ + + + + + AbstractAlert + + + Close + 閉じる + + + + Snooze Update + 更新停止 + + + + Reboot and Update + 再起動してアップデート + + + + AdvancedNetworking + + + Back + もどる + + + + Enable Tethering + テザリングを有効化 + + + + Tethering Password + テザリングパスワード + + + + + EDIT + 編集 + + + + Enter new tethering password + 新しいテザリングパスワードを入力 + + + + IP Address + IPアドレス + + + + Enable Roaming + ローミングを有効化 + + + + APN Setting + APN 設定 + + + + Enter APN + APN 入力 + + + + leave blank for automatic configuration + 空欄で自動設定 + + + + ConfirmationDialog + + + + Ok + OK + + + + Cancel + キャンセル + + + + DeclinePage + + + You must accept the Terms and Conditions in order to use openpilot. + openpilotを利用するためには、利用規約に同意する必要があります。 + + + + Back + 戻る + + + + Decline, uninstall %1 + 拒否してアンインストール %1 + + + + DevicePanel + + + Dongle ID + ドングル ID + + + + N/A + N/A + + + + Serial + シリアル + + + + Driver Camera + ドライバーカメラ + + + + PREVIEW + プレビュー + + + + Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off) + ドライバーカメラのプレビューにより、デバイスの取り付け位置を最適化し、最高のドライバーモニタリング体験を提供します。(車両の電源を切る必要があります) + + + + Reset Calibration + キャリブレーションリセット + + + + RESET + リセット + + + + Are you sure you want to reset calibration? + 本当にキャリブレーションをリセットしますか? + + + + Review Training Guide + トレーニングガイドを見る + + + + REVIEW + レビュー + + + + Review the rules, features, and limitations of openpilot + openpilot 規約 機能 制約を見る + + + + Are you sure you want to review the training guide? + 本当にトレーニングガイドを見ますか? + + + + Regulatory + レギュレーション + + + + VIEW + ビュー + + + Change Language + 言語を変更 + + + CHANGE + 変更 + + + Select a language + 言語を選択する + + + + Reboot + 再起動 + + + + Power Off + 電源を切る + + + + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. + openpilot は、左右に4°、上に5°、下に8°の範囲に設置する必要があります。openpilot は継続的に校正されているので、手動でリセットする必要はほとんどありません。 + + + + Your device is pointed %1° %2 and %3° %4. + デバイスは %1° %2 と %3° %4を示しています。 + + + + down + + + + + up + + + + + left + + + + + right + + + + + Are you sure you want to reboot? + 本当に再起動しますか? + + + + Disengage to Reboot + 再起動するために離脱します + + + + Are you sure you want to power off? + 本当に電源を切っても良いですか? + + + + Disengage to Power Off + 電源を切るために離脱します + + + + DriveStats + + + Drives + ドライブ + + + + Hours + 時間 + + + + ALL TIME + 累計 + + + + PAST WEEK + 先週 + + + + KM + km + + + + Miles + マイル + + + + DriverViewScene + + + camera starting + カメラ起動 + + + + InputDialog + + + Cancel + キャンセル + + + + Need at least + 最低限必要なもの + + + + characters! + 記号! + + + + Installer + + + Installing... + インストール... + + + + Receiving objects: + オブジェクトを受信中: + + + + Resolving deltas: + リゾルブ解決中: + + + + Updating files: + ファイルを更新中: + + + + MapPanel + + + Current Destination + 現在の目的地 + + + + CLEAR + クリア + + + + Recent Destinations + 最近の目的地 + + + + Try the Navigation Beta + ベータ版ナビゲーション + + + + Get turn-by-turn directions displayed and more with a comma +prime subscription. Sign up now: https://connect.comma.ai + より詳細な案内や表示に関する情報を得ることができます。 詳しくはこちら:https://connect.comma.ai + + + + No home +location set + 自宅の登録なし +位置を設定 + + + + No work +location set + 職場の登録なし +位置を設定 + + + + no recent destinations + 最寄りの目的地がありません + + + + MultiOptionDialog + + Select + 選択 + + + + Networking + + + Advanced + 詳細 + + + + Enter password + パスワードを入力 + + + + + for " + のため " + + + + Wrong password + パスワードが間違っています + + + + NvgWindow + + + km/h + km/時 + + + + mph + マイル/時 + + + + + MAX + 最大 + + + + + SPEED + 速度 + + + + + LIMIT + 制限 + + + + OffroadHome + + + UPDATE + 更新 + + + + ALERTS + 警告 + + + + ALERT + 警告 + + + + PairingPopup + + + Pair your device to your comma account + デバイスとアカウントを連携する + + + + + <ol type='1' style='margin-left: 15px;'> + <li style='margin-bottom: 50px;'>Go to https://connect.comma.ai on your phone</li> + <li style='margin-bottom: 50px;'>Click "add new device" and scan the QR code on the right</li> + <li style='margin-bottom: 50px;'>Bookmark connect.comma.ai to your home screen to use it like an app</li> + </ol> + + + <ol type='1' style='margin-left: 15px;'> + <li style='margin-bottom: 50px;'>モバイルでアクセス https://connect.comma.ai</li> + <li style='margin-bottom: 50px;'>“新しいデバイスを追加”をクリックし,QRコードを読み込みます</li> + <li style='margin-bottom: 50px;'>connect.comma.aiをホーム画面にブックマークして、アプリのように使うことができます</li> + </ol> + + + + + PrimeAdWidget + + + Upgrade Now + いますぐアップグレード + + + + Become a comma prime member at connect.comma.ai + connect.comma.ai のプライムメンバーになる + + + + PRIME FEATURES: + 主な機能: + + + + Remote access + リモートアクセス + + + + 1 year of storage + 1年の保存期間 + + + + Developer perks + 開発者特典 + + + + PrimeUserWidget + + + ✓ SUBSCRIBED + ✓ 購読 + + + + comma prime + コンマプライム + + + + CONNECT.COMMA.AI + CONNECT.COMMA.AI + + + + COMMA POINTS + コンマポイント + + + + QObject + + + Reboot + 再起動 + + + + Exit + 退出 + + + + dashcam + ダッシュカム + + + + openpilot + オープンパイロット + + + + %1 minute%2 ago + %1 分%2 前 + + + + %1 hour%2 ago + %1 時間%2 前 + + + + %1 day%2 ago + %1 日%2 前 + + + + Reset + + + Reset failed. Reboot to try again. + 初期化に失敗しました。再起動後に再試行してください。 + + + + Are you sure you want to reset your device? + 本当に初期化しますか? + + + + Resetting device... + デバイスが初期化されます... + + + + System Reset + システムを初期化 + + + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + システムを初期化させます。 すべてのコンテンツと設定が削除されます。 キャンセルを押すと再起動します。 + + + + Cancel + キャンセル + + + + Reboot + 再起動 + + + + Confirm + 確認 + + + + Unable to mount data partition. Press confirm to reset your device. + dataパーティションをマウントできません。 確認を押すとデバイスが初期化されます。 + + + + RichTextDialog + + + Ok + OK + + + + SettingsWindow + + + × + × + + + + Device + デバイス + + + + + Network + ネットワーク + + + + Toggles + 切り替え + + + + Software + ソフトウェア + + + + Navigation + ナビゲーション + + + + Setup + + + WARNING: Low Voltage + 警告:低電圧 + + + + Power your device in a car with a harness or proceed at your own risk. + 自己責任でハーネスから電源を供給してください。 + + + + Power off + 電源を切る + + + + + + Continue + 続ける + + + + Getting Started + はじめに + + + + Before we get on the road, let’s finish installation and cover some details. + その前に、インストールを完了し、いくつかの詳細を説明します。 + + + + Connect to Wi-Fi + Wi-Fiに接続 + + + + + Back + 戻る + + + + Continue without Wi-Fi + Wi-Fi に未接続で続行 + + + + Waiting for internet + インターネット接続を待機中 + + + + Choose Software to Install + インストールするソフトウェアを選びます + + + + Dashcam + ダッシュカム + + + + Custom Software + カスタムソフトウェア + + + + Enter URL + URLを入力 + + + + for Custom Software + カスタムソフトウェア + + + + Downloading... + ダウンロード中... + + + + Download Failed + ダウンロード失敗 + + + + Ensure the entered URL is valid, and the device’s internet connection is good. + 入力されたURLが有効であること、デバイスがインターネットに接続されていることを確認してください。 + + + + Reboot device + デバイスを再起動 + + + + Start over + 再スタート + + + + SetupWidget + + + Finish Setup + セットアップ完了 + + + + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. + デバイスを comma connect (connect.comma.ai)でペアリングし comma prime 特典を申請してください。 + + + + Pair device + デバイスをペアリング + + + + Sidebar + + + + CONNECT + 接続 + + + + OFFLINE + オフライン + + + + + ONLINE + オンライン + + + + ERROR + エラー + + + + + + TEMP + 温度 + + + + HIGH + 高温 + + + + GOOD + 最適 + + + + OK + OK + + + + VEHICLE + 車両 + + + + NO + NO + + + + PANDA + パンダ + + + + GPS + GPS + + + + SEARCH + 検索 + + + + -- + -- + + + + Wi-Fi + Wi-Fi + + + + ETH + ETH + + + + 2G + 2G + + + + 3G + 3G + + + + LTE + LTE + + + + 5G + 5G + + + + SoftwarePanel + + + Git Branch + Git ブランチ + + + + Git Commit + Git コミット + + + + OS Version + OS バージョン + + + + Version + バージョン + + + + Last Update Check + 最終更新確認 + + + + The last time openpilot successfully checked for an update. The updater only runs while the car is off. + openpilotが最後にアップデートの確認に成功してからの時間です。アップデート処理は、車の電源が切れているときのみ実行されます。 + + + + Check for Update + 更新確認 + + + + CHECKING + 確認中 + + + + Uninstall + アンインストール + + + + UNINSTALL + アンインストール + + + + Are you sure you want to uninstall? + 本当にアンインストールしますか? + + + + failed to fetch update + 更新の取得に失敗しました + + + + + CHECK + 確認 + + + + SshControl + + + SSH Keys + SSH 鍵 + + + + Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. + 警告: これは、GitHub の設定にあるすべての公開鍵への SSH アクセスを許可するものです。自分以外のGitHubのユーザー名を入力しないでください。コンマのスタッフがGitHubのユーザー名を追加するようお願いすることはありません。 + + + + + ADD + 追加 + + + + Enter your GitHub username + GitHubのユーザー名を入力してください + + + + LOADING + ローディング + + + + REMOVE + 削除 + + + + Username '%1' has no keys on GitHub + ユーザー名“%1”は GitHub に鍵がありません + + + + Request timed out + リクエストタイムアウト + + + + Username '%1' doesn't exist on GitHub + ユーザー名 '%1' は GitHub に存在しません + + + + SshToggle + + + Enable SSH + SSH を有効化 + + + + TermsPage + + + Terms & Conditions + 利用規約 + + + + Decline + 拒否 + + + + Scroll to accept + スクロールして同意 + + + + Agree + 同意 + + + + TogglesPanel + + + Enable openpilot + openpilot を有効化 + + + + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. + アダプティブクルーズコントロールとレーンキーピングドライバーアシスト(openpilotシステム)。この機能を使用するには、常に注意が必要です。この設定を変更すると、車の電源が切れたときに有効になります。 + + + + Enable Lane Departure Warnings + 車線逸脱警報機能を有効化 + + + + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). + 時速31マイル(50km)を超えるスピードで走行中、方向指示器を作動させずに検出された車線ライン上に車両が触れた場合、車線に戻るアラートを受信します。 + + + + Enable Right-Hand Drive + 右ハンドルを有効化 + + + + Allow openpilot to obey left-hand traffic conventions and perform driver monitoring on right driver seat. + openpilotが左側通行規則を遵守し、右側の運転席でドライバーの監視を行うことを可能にします。 + + + + Use Metric System + メートル法を有効化 + + + + Display speed in km/h instead of mph. + 速度はmphではなくkm/hで表示されます。 + + + + Record and Upload Driver Camera + ドライバーカメラの録画とアップロード + + + + Upload data from the driver facing camera and help improve the driver monitoring algorithm. + ドライバーカメラからのデータをアップロードし、ドライバー監視のアルゴリズム向上に役立てます。 + + + + Disengage On Accelerator Pedal + アクセルペダルで解除する + + + + When enabled, pressing the accelerator pedal will disengage openpilot. + 有効な場合 openpilot はアクセルペダルを踏むと解除されます。 + + + + Show ETA in 24h format + 24時間表示 + + + + Use 24h format instead of am/pm + AM/PMの代わりに24時間形式を使用します + + + + openpilot Longitudinal Control + openpilot による垂直方向の制御 + + + + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! + openpilotは、車のレーダーを無効化し、アクセルとブレーキの制御を引き継ぎます。注意:AEBを無効にします! + + + + Updater + + + Update Required + 更新が必要です + + + + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. + OSのアップデートが必要です。Wi-Fiに接続することで、最速のアップデートを体験できます。ダウンロードサイズは約1GBです。 + + + + Connect to Wi-Fi + Wi-Fiに接続 + + + + Install + インストール + + + + Back + 戻る + + + + Loading... + 読み込み中... + + + + Reboot + 再起動 + + + + Update failed + 更新失敗 + + + + WifiUI + + + + Scanning for networks... + ネットワークをスキャン中... + + + + CONNECTING... + 接続中... + + + + FORGET + 削除 + + + + Forget Wi-Fi Network " + Wi-Fiを削除する” + + + From dccb184fbd4a2b39008471f94056f61bf7a7381d Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 8 Jul 2022 13:39:23 +0200 Subject: [PATCH 242/302] some more release notes --- RELEASES.md | 18 ++++++++++++------ 1 file changed, 12 insertions(+), 6 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index fedff5dbff..d7f4a37476 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -5,17 +5,23 @@ Version 0.8.15 (2022-07-XX) * Effective feedforward that uses road roll * Simplified tuning, all car-specific parameters can be derived from data * Significantly improved control on TSS-P Prius +* New driving model + * Path planning uses end-to-end output instead of lane lines * New driver monitoring model - * takes a larger input frame - * outputs a driver state for both driver and passenger - * automatically determines which side the driver is on (soon) -* Reduced power usage: device runs cooler and fan spins less -* Minor UI updates + * Takes a larger input frame + * Outputs a driver state for both driver and passenger + * Automatically determines which side the driver is on (soon) +* Navigation improvements + * Speed limits shown while navigating + * Faster position fix by using raw GPS measurements +* UI updates * New font * Refreshed max speed design - * Speed limits shown while navigating * More consistent camera view perspective across cars +* Reduced power usage: device runs cooler and fan spins less * AGNOS 5 + * Support for delta updates to reduce data usage on future OS updates + * Support VSCode remote SSH target * Honda Civic 2022 support * Hyundai Tucson 2021 support thanks to bluesforte! * Lexus NX Hybrid 2020 support thanks to AlexandreSato! From b5399fbd3ce3a03bb900f1e8597f0afbd19fa314 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 8 Jul 2022 13:41:42 +0200 Subject: [PATCH 243/302] add multilang to release notes --- RELEASES.md | 1 + 1 file changed, 1 insertion(+) diff --git a/RELEASES.md b/RELEASES.md index d7f4a37476..80709e1482 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -15,6 +15,7 @@ Version 0.8.15 (2022-07-XX) * Speed limits shown while navigating * Faster position fix by using raw GPS measurements * UI updates + * Multilanguage support for settings and home screen * New font * Refreshed max speed design * More consistent camera view perspective across cars From c5e96201f30c7168e531ba5da98775fcd2d668c5 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 8 Jul 2022 13:56:49 +0200 Subject: [PATCH 244/302] RELEASES.md: new driving model goes first --- RELEASES.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index 80709e1482..e0e75f3213 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,12 +1,12 @@ Version 0.8.15 (2022-07-XX) ======================== +* New driving model + * Path planning uses end-to-end output instead of lane lines * New lateral controller based on physical wheel torque model * Much smoother control, consistent across the speed range * Effective feedforward that uses road roll * Simplified tuning, all car-specific parameters can be derived from data * Significantly improved control on TSS-P Prius -* New driving model - * Path planning uses end-to-end output instead of lane lines * New driver monitoring model * Takes a larger input frame * Outputs a driver state for both driver and passenger From b6df0cd2422d63eb58cc6abaa9968954feff2ccb Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 8 Jul 2022 15:44:16 +0200 Subject: [PATCH 245/302] casync: handle hash failure (#25081) * casync: handle hashing failure due to IO errors * fix comment * all exceptions * fix typo * Update system/hardware/tici/agnos.py --- system/hardware/tici/agnos.py | 18 +++++++++++------- 1 file changed, 11 insertions(+), 7 deletions(-) diff --git a/system/hardware/tici/agnos.py b/system/hardware/tici/agnos.py index bd8ce2bf02..750aa630ae 100755 --- a/system/hardware/tici/agnos.py +++ b/system/hardware/tici/agnos.py @@ -186,14 +186,18 @@ def extract_casync_image(target_slot_number: int, partition: dict, cloudlog): sources: List[Tuple[str, casync.ChunkReader, casync.ChunkDict]] = [] - # First source is the current partition. Index file for current version is provided in the manifest - raw_hash = get_raw_hash(seed_path, partition['size']) - caibx_url = f"{CAIBX_URL}{partition['name']}-{raw_hash}.caibx" + # First source is the current partition. try: - cloudlog.info(f"casync fetching {caibx_url}") - sources += [('seed', casync.FileChunkReader(seed_path), casync.build_chunk_dict(casync.parse_caibx(caibx_url)))] - except requests.RequestException: - cloudlog.error(f"casync failed to load {caibx_url}") + raw_hash = get_raw_hash(seed_path, partition['size']) + caibx_url = f"{CAIBX_URL}{partition['name']}-{raw_hash}.caibx" + + try: + cloudlog.info(f"casync fetching {caibx_url}") + sources += [('seed', casync.FileChunkReader(seed_path), casync.build_chunk_dict(casync.parse_caibx(caibx_url)))] + except requests.RequestException: + cloudlog.error(f"casync failed to load {caibx_url}") + except Exception: + cloudlog.exception("casync failed to hash seed partition") # Second source is the target partition, this allows for resuming sources += [('target', casync.FileChunkReader(path), casync.build_chunk_dict(target))] From 7a4c33795a12eefff4c3e5c311f40eae2cf3506b Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 8 Jul 2022 18:20:16 +0200 Subject: [PATCH 246/302] laikad: add residual threshold for pos_fix (#25082) * laikad: add residual threshold for pos_fix * update ref * update test --- selfdrive/locationd/laikad.py | 5 +++-- selfdrive/locationd/test/test_laikad.py | 8 ++++---- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 8 insertions(+), 7 deletions(-) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index e262407e02..67867e82b3 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -28,6 +28,7 @@ from system.swaglog import cloudlog MAX_TIME_GAP = 10 EPHEMERIS_CACHE = 'LaikadEphemeris' CACHE_VERSION = 0.1 +POS_FIX_RESIDUAL_THRESHOLD = 100.0 class Laikad: @@ -89,9 +90,9 @@ class Laikad: def get_est_pos(self, t, processed_measurements): if self.last_pos_fix_t is None or abs(self.last_pos_fix_t - t) >= 2: - min_measurements = 5 if any(p.constellation_id == ConstellationId.GLONASS for p in processed_measurements) else 4 + min_measurements = 6 if any(p.constellation_id == ConstellationId.GLONASS for p in processed_measurements) else 5 pos_fix, pos_fix_residual = calc_pos_fix_gauss_newton(processed_measurements, self.posfix_functions, min_measurements=min_measurements) - if len(pos_fix) > 0: + if len(pos_fix) > 0 and np.median(np.abs(pos_fix_residual)) < POS_FIX_RESIDUAL_THRESHOLD: self.last_pos_fix = pos_fix[:3] self.last_pos_residual = pos_fix_residual self.last_pos_fix_t = t diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py index 3a7c073b55..c10a470d1a 100755 --- a/selfdrive/locationd/test/test_laikad.py +++ b/selfdrive/locationd/test/test_laikad.py @@ -138,7 +138,7 @@ class TestLaikad(unittest.TestCase): laikad = Laikad(auto_update=True, valid_ephem_types=EphemerisType.ULTRA_RAPID_ORBIT) correct_msgs = verify_messages(self.logs, laikad) - correct_msgs_expected = 560 + correct_msgs_expected = 555 self.assertEqual(correct_msgs_expected, len(correct_msgs)) self.assertEqual(correct_msgs_expected, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid])) @@ -159,7 +159,7 @@ class TestLaikad(unittest.TestCase): # Disable fetch_orbits to test NAV only laikad.fetch_orbits = Mock() correct_msgs = verify_messages(self.logs, laikad) - correct_msgs_expected = 560 + correct_msgs_expected = 559 self.assertEqual(correct_msgs_expected, len(correct_msgs)) self.assertEqual(correct_msgs_expected, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid])) @@ -168,8 +168,8 @@ class TestLaikad(unittest.TestCase): downloader_mock.side_effect = IOError laikad = Laikad(auto_update=False) correct_msgs = verify_messages(self.logs, laikad) - self.assertEqual(256, len(correct_msgs)) - self.assertEqual(256, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid])) + self.assertEqual(16, len(correct_msgs)) + self.assertEqual(16, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid])) def test_laika_get_orbits(self): laikad = Laikad(auto_update=False) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 4908b86182..7fced5ad62 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -bd2ea158977f5c26658bed8ac683b72c2c592d06 \ No newline at end of file +0da0928230d11dd4c76293b9e77b027eb4a1e291 \ No newline at end of file From a9401319dfa89fea2d2699aaddc758cbc47b6396 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 8 Jul 2022 18:20:36 +0200 Subject: [PATCH 247/302] nav: use laikad position if locationd is not yet available (#25033) * ui: use laikad position when locationd is not ready * cleanup * same threshold as locationd * use first bearing directly * use in navd too --- selfdrive/navd/navd.py | 19 ++++++-- selfdrive/ui/qt/maps/map.cc | 71 ++++++++++++++++++++++------- selfdrive/ui/qt/maps/map.h | 3 +- selfdrive/ui/qt/maps/map_helpers.cc | 5 ++ selfdrive/ui/qt/maps/map_helpers.h | 1 + selfdrive/ui/ui.cc | 2 +- 6 files changed, 79 insertions(+), 22 deletions(-) diff --git a/selfdrive/navd/navd.py b/selfdrive/navd/navd.py index f02de43c7b..89a1c9bdfb 100755 --- a/selfdrive/navd/navd.py +++ b/selfdrive/navd/navd.py @@ -4,12 +4,14 @@ import os import threading import requests +import numpy as np import cereal.messaging as messaging from cereal import log from common.api import Api from common.params import Params from common.realtime import Ratekeeper +from common.transformations.coordinates import ecef2geodetic from selfdrive.navd.helpers import (Coordinate, coordinate_from_param, distance_along_geometry, maxspeed_to_ms, minimum_distance, @@ -18,6 +20,7 @@ from system.swaglog import cloudlog REROUTE_DISTANCE = 25 MANEUVER_TRANSITION_THRESHOLD = 10 +VALID_POS_STD = 50.0 class RouteEngine: @@ -72,13 +75,21 @@ class RouteEngine: def update_location(self): location = self.sm['liveLocationKalman'] - self.gps_ok = location.gpsOK + laikad = self.sm['gnssMeasurements'] - self.localizer_valid = (location.status == log.LiveLocationKalman.Status.valid) and location.positionGeodetic.valid + locationd_valid = (location.status == log.LiveLocationKalman.Status.valid) and location.positionGeodetic.valid + laikad_valid = laikad.positionECEF.valid and np.linalg.norm(laikad.positionECEF.std) < VALID_POS_STD - if self.localizer_valid: + self.localizer_valid = locationd_valid or laikad_valid + self.gps_ok = location.gpsOK or laikad_valid + + if locationd_valid: self.last_bearing = math.degrees(location.calibratedOrientationNED.value[2]) self.last_position = Coordinate(location.positionGeodetic.value[0], location.positionGeodetic.value[1]) + elif laikad_valid: + geodetic = ecef2geodetic(laikad.positionECEF.value) + self.last_position = Coordinate(geodetic[0], geodetic[1]) + self.last_bearing = None def recompute_route(self): if self.last_position is None: @@ -276,7 +287,7 @@ class RouteEngine: def main(sm=None, pm=None): if sm is None: - sm = messaging.SubMaster(['liveLocationKalman', 'managerState']) + sm = messaging.SubMaster(['liveLocationKalman', 'gnssMeasurements', 'managerState']) if pm is None: pm = messaging.PubMaster(['navInstruction', 'navRoute']) diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc index 4c6a0a4e65..fd47f4188f 100644 --- a/selfdrive/ui/qt/maps/map.cc +++ b/selfdrive/ui/qt/maps/map.cc @@ -1,5 +1,6 @@ #include "selfdrive/ui/qt/maps/map.h" +#include #include #include @@ -7,6 +8,7 @@ #include #include "common/swaglog.h" +#include "common/transformations/coordinates.hpp" #include "selfdrive/ui/qt/maps/map_helpers.h" #include "selfdrive/ui/qt/request_repeater.h" #include "selfdrive/ui/qt/util.h" @@ -22,6 +24,8 @@ const float MAX_PITCH = 50; const float MIN_PITCH = 0; const float MAP_SCALE = 2; +const float VALID_POS_STD = 50.0; // m + const QString ICON_SUFFIX = ".png"; MapWindow::MapWindow(const QMapboxGLSettings &settings) : m_settings(settings), velocity_filter(0, 10, 0.05) { @@ -105,18 +109,53 @@ void MapWindow::updateState(const UIState &s) { update(); if (sm.updated("liveLocationKalman")) { - auto location = sm["liveLocationKalman"].getLiveLocationKalman(); - auto pos = location.getPositionGeodetic(); - auto orientation = location.getCalibratedOrientationNED(); - auto velocity = location.getVelocityCalibrated(); - - localizer_valid = (location.getStatus() == cereal::LiveLocationKalman::Status::VALID) && - pos.getValid() && orientation.getValid() && velocity.getValid(); - - if (localizer_valid) { - last_position = QMapbox::Coordinate(pos.getValue()[0], pos.getValue()[1]); - last_bearing = RAD2DEG(orientation.getValue()[2]); - velocity_filter.update(velocity.getValue()[0]); + auto locationd_location = sm["liveLocationKalman"].getLiveLocationKalman(); + auto locationd_pos = locationd_location.getPositionGeodetic(); + auto locationd_orientation = locationd_location.getCalibratedOrientationNED(); + auto locationd_velocity = locationd_location.getVelocityCalibrated(); + + locationd_valid = (locationd_location.getStatus() == cereal::LiveLocationKalman::Status::VALID) && + locationd_pos.getValid() && locationd_orientation.getValid() && locationd_velocity.getValid(); + + if (locationd_valid) { + last_position = QMapbox::Coordinate(locationd_pos.getValue()[0], locationd_pos.getValue()[1]); + last_bearing = RAD2DEG(locationd_orientation.getValue()[2]); + velocity_filter.update(locationd_velocity.getValue()[0]); + } + } + + if (sm.updated("gnssMeasurements")) { + auto laikad_location = sm["gnssMeasurements"].getGnssMeasurements(); + auto laikad_pos = laikad_location.getPositionECEF(); + auto laikad_pos_ecef = laikad_pos.getValue(); + auto laikad_pos_std = laikad_pos.getStd(); + auto laikad_velocity_ecef = laikad_location.getVelocityECEF().getValue(); + + laikad_valid = laikad_pos.getValid() && Eigen::Vector3d(laikad_pos_std[0], laikad_pos_std[1], laikad_pos_std[2]).norm() < VALID_POS_STD; + + if (laikad_valid && !locationd_valid) { + ECEF ecef = {.x = laikad_pos_ecef[0], .y = laikad_pos_ecef[1], .z = laikad_pos_ecef[2]}; + Geodetic laikad_pos_geodetic = ecef2geodetic(ecef); + last_position = QMapbox::Coordinate(laikad_pos_geodetic.lat, laikad_pos_geodetic.lon); + + // Compute NED velocity + LocalCoord converter(ecef); + ECEF next_ecef = {.x = ecef.x + laikad_velocity_ecef[0], .y = ecef.y + laikad_velocity_ecef[1], .z = ecef.z + laikad_velocity_ecef[2]}; + Eigen::VectorXd ned_vel = converter.ecef2ned(next_ecef).to_vector() - converter.ecef2ned(ecef).to_vector(); + + float velocity = ned_vel.norm(); + velocity_filter.update(velocity); + + // Convert NED velocity to angle + if (velocity > 1.0) { + float new_bearing = fmod(RAD2DEG(atan2(ned_vel[1], ned_vel[0])) + 360.0, 360.0); + if (last_bearing) { + float delta = 0.1 * angle_difference(*last_bearing, new_bearing); // Smooth heading + last_bearing = fmod(*last_bearing + delta + 360.0, 360.0); + } else { + last_bearing = new_bearing; + } + } } } @@ -142,9 +181,7 @@ void MapWindow::updateState(const UIState &s) { initLayers(); - if (!localizer_valid) { - map_instructions->showError("Waiting for GPS"); - } else { + if (locationd_valid || laikad_valid) { map_instructions->noError(); // Update current location marker @@ -154,6 +191,8 @@ void MapWindow::updateState(const UIState &s) { carPosSource["type"] = "geojson"; carPosSource["data"] = QVariant::fromValue(feature1); m_map->updateSource("carPosSource", carPosSource); + } else { + map_instructions->showError("Waiting for GPS"); } if (pan_counter == 0) { @@ -174,7 +213,7 @@ void MapWindow::updateState(const UIState &s) { auto i = sm["navInstruction"].getNavInstruction(); emit ETAChanged(i.getTimeRemaining(), i.getTimeRemainingTypical(), i.getDistanceRemaining()); - if (localizer_valid) { + if (locationd_valid || laikad_valid) { m_map->setPitch(MAX_PITCH); // TODO: smooth pitching based on maneuver distance emit distanceChanged(i.getManeuverDistance()); // TODO: combine with instructionsChanged emit instructionsChanged(i); diff --git a/selfdrive/ui/qt/maps/map.h b/selfdrive/ui/qt/maps/map.h index 7c39b24c3c..ecba867edb 100644 --- a/selfdrive/ui/qt/maps/map.h +++ b/selfdrive/ui/qt/maps/map.h @@ -104,7 +104,8 @@ private: std::optional last_position; std::optional last_bearing; FirstOrderFilter velocity_filter; - bool localizer_valid = false; + bool laikad_valid = false; + bool locationd_valid = false; MapInstructions* map_instructions; MapETA* map_eta; diff --git a/selfdrive/ui/qt/maps/map_helpers.cc b/selfdrive/ui/qt/maps/map_helpers.cc index 2b2c27418e..66acb7a25d 100644 --- a/selfdrive/ui/qt/maps/map_helpers.cc +++ b/selfdrive/ui/qt/maps/map_helpers.cc @@ -116,3 +116,8 @@ std::optional coordinate_from_param(std::string param) { return {}; } } + +double angle_difference(double angle1, double angle2) { + double diff = fmod(angle2 - angle1 + 180.0, 360.0) - 180.0; + return diff < -180.0 ? diff + 360.0 : diff; +} diff --git a/selfdrive/ui/qt/maps/map_helpers.h b/selfdrive/ui/qt/maps/map_helpers.h index 344246bb05..1c08c541c3 100644 --- a/selfdrive/ui/qt/maps/map_helpers.h +++ b/selfdrive/ui/qt/maps/map_helpers.h @@ -26,3 +26,4 @@ QMapbox::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp: QMapbox::CoordinatesCollections coordinate_list_to_collection(QList coordinate_list); std::optional coordinate_from_param(std::string param); +double angle_difference(double angle1, double angle2); diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index f6193f97a6..6fe1d838ed 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -227,7 +227,7 @@ UIState::UIState(QObject *parent) : QObject(parent) { sm = std::make_unique>({ "modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", "roadCameraState", "pandaStates", "carParams", "driverMonitoringState", "sensorEvents", "carState", "liveLocationKalman", - "wideRoadCameraState", "managerState", "navInstruction", "navRoute", + "wideRoadCameraState", "managerState", "navInstruction", "navRoute", "gnssMeasurements", }); Params params; From cf862b6576a8b3f66e26d38080a1c8eec00f0793 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Fri, 8 Jul 2022 19:03:42 +0200 Subject: [PATCH 248/302] Laikad: Fix getting covariances for pos and velocity (#25084) * Fix getting covariances for pos and velocity * ref commit --- selfdrive/locationd/laikad.py | 13 +++++++------ selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 67867e82b3..0954cb4c9f 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -120,11 +120,12 @@ class Laikad: self.update_localizer(est_pos, t, corrected_measurements) kf_valid = all(self.kf_valid(t)) - ecef_pos = self.gnss_kf.x[GStates.ECEF_POS].tolist() - ecef_vel = self.gnss_kf.x[GStates.ECEF_VELOCITY].tolist() + ecef_pos = self.gnss_kf.x[GStates.ECEF_POS] + ecef_vel = self.gnss_kf.x[GStates.ECEF_VELOCITY] - pos_std = np.sqrt(abs(self.gnss_kf.P[GStates.ECEF_POS].diagonal())).tolist() - vel_std = np.sqrt(abs(self.gnss_kf.P[GStates.ECEF_VELOCITY].diagonal())).tolist() + p = self.gnss_kf.P.diagonal() + pos_std = np.sqrt(p[GStates.ECEF_POS]) + vel_std = np.sqrt(p[GStates.ECEF_VELOCITY]) meas_msgs = [create_measurement_msg(m) for m in corrected_measurements] dat = messaging.new_message("gnssMeasurements") @@ -132,8 +133,8 @@ class Laikad: dat.gnssMeasurements = { "gpsWeek": report.gpsWeek, "gpsTimeOfWeek": report.rcvTow, - "positionECEF": measurement_msg(value=ecef_pos, std=pos_std, valid=kf_valid), - "velocityECEF": measurement_msg(value=ecef_vel, std=vel_std, valid=kf_valid), + "positionECEF": measurement_msg(value=ecef_pos.tolist(), std=pos_std.tolist(), valid=kf_valid), + "velocityECEF": measurement_msg(value=ecef_vel.tolist(), std=vel_std.tolist(), valid=kf_valid), "positionFixECEF": measurement_msg(value=self.last_pos_fix, std=self.last_pos_residual, valid=self.last_pos_fix_t == t), "ubloxMonoTime": ublox_mono_time, "correctedMeasurements": meas_msgs diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 7fced5ad62..0d61dbd735 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -0da0928230d11dd4c76293b9e77b027eb4a1e291 \ No newline at end of file +dab90772097a0dd4706677ba4fe5e84b10232099 \ No newline at end of file From c04942795bbb0a2a31f4c05322e6897e279f4ba9 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Fri, 8 Jul 2022 10:16:34 -0700 Subject: [PATCH 249/302] Update RELEASES.md --- RELEASES.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index e0e75f3213..392e9dc486 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,7 +1,9 @@ Version 0.8.15 (2022-07-XX) ======================== * New driving model - * Path planning uses end-to-end output instead of lane lines + * Path planning uses end-to-end output instead of lane lines at all times + * Reduced ping pong + * Improved lane centering * New lateral controller based on physical wheel torque model * Much smoother control, consistent across the speed range * Effective feedforward that uses road roll From 35c8c0e600746e092bb236dabd05491d8be1078a Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 8 Jul 2022 19:19:57 +0200 Subject: [PATCH 250/302] casync: increase chunk download timeout --- system/hardware/tici/casync.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/hardware/tici/casync.py b/system/hardware/tici/casync.py index d0d0da3c6a..9dff64239e 100755 --- a/system/hardware/tici/casync.py +++ b/system/hardware/tici/casync.py @@ -22,7 +22,7 @@ CA_TABLE_HEADER_LEN = 16 CA_TABLE_ENTRY_LEN = 40 CA_TABLE_MIN_LEN = CA_TABLE_HEADER_LEN + CA_TABLE_ENTRY_LEN -CHUNK_DOWNLOAD_TIMEOUT = 10 +CHUNK_DOWNLOAD_TIMEOUT = 60 CHUNK_DOWNLOAD_RETRIES = 3 CAIBX_DOWNLOAD_TIMEOUT = 120 From 0b6cf0481c07323ee427655a5849c90d9c623e64 Mon Sep 17 00:00:00 2001 From: eFini Date: Sat, 9 Jul 2022 03:12:14 +0800 Subject: [PATCH 251/302] Add Traditional Chinese translations (#25077) * Create main_zh-CHT * Update Co-authored-by: Shane Smiskol --- selfdrive/ui/translations/languages.json | 3 +- .../{main_zh.qm => main_zh-CHS.qm} | Bin .../{main_zh.ts => main_zh-CHS.ts} | 0 selfdrive/ui/translations/main_zh-CHT.qm | Bin 0 -> 17741 bytes selfdrive/ui/translations/main_zh-CHT.ts | 1220 +++++++++++++++++ 5 files changed, 1222 insertions(+), 1 deletion(-) rename selfdrive/ui/translations/{main_zh.qm => main_zh-CHS.qm} (100%) rename selfdrive/ui/translations/{main_zh.ts => main_zh-CHS.ts} (100%) create mode 100644 selfdrive/ui/translations/main_zh-CHT.qm create mode 100644 selfdrive/ui/translations/main_zh-CHT.ts diff --git a/selfdrive/ui/translations/languages.json b/selfdrive/ui/translations/languages.json index b8c3a50fd7..48f0948674 100644 --- a/selfdrive/ui/translations/languages.json +++ b/selfdrive/ui/translations/languages.json @@ -1,5 +1,6 @@ { "English": "", - "中文(简体)": "main_zh", + "中文(繁體)": "main_zh-CHT", + "中文(简体)": "main_zh-CHS", "한국어": "main_ko" } diff --git a/selfdrive/ui/translations/main_zh.qm b/selfdrive/ui/translations/main_zh-CHS.qm similarity index 100% rename from selfdrive/ui/translations/main_zh.qm rename to selfdrive/ui/translations/main_zh-CHS.qm diff --git a/selfdrive/ui/translations/main_zh.ts b/selfdrive/ui/translations/main_zh-CHS.ts similarity index 100% rename from selfdrive/ui/translations/main_zh.ts rename to selfdrive/ui/translations/main_zh-CHS.ts diff --git a/selfdrive/ui/translations/main_zh-CHT.qm b/selfdrive/ui/translations/main_zh-CHT.qm new file mode 100644 index 0000000000000000000000000000000000000000..8b055d665e4582f8d1461595d0d88a7eeacfbb49 GIT binary patch literal 17741 zcmcJ0dwi7TmH(5;+%vfWrHEQyf1>3xxASSnam7x3qfNA zqe6%fi-e2US}(M2w=P?4^{1=bqFrIBc9quE;wlxZ{`%8ax~o6=+3fc`@60>zOeS&r z$C?km$;>(DInO!gInTMhYk%sQb?Vdm4xO2M#S2~Eeg0fEW7>xpQ+>tQ!Z2gGUOex? zvmehBcpk>{HOAEVK7W)kO$B46AK`f|V~bYd*$$Xa={e_N#&j<-X8I%k{em&!$Bfku zF;@0H#%|mLyz3Zivg5gnv6iKP9mcbVvFYHU<#v32im@pD{ZppC^Ipc-Iq8`@B0Yt- zrRQ3asgJzRSWW>`pIiaFElhppr+7Zb)UT=;yJ8;G3=81zb*A~@pH=_!z7I@F~WY-o_dXF2)K^vKv<&0v}+%A3T;` z#w`AWkV6l%zK8XvU(RfUe+K;P%%S=@K7WciT-e*9TiM3PA7RWelWl6e2XJ2YzmDI` z*xHxamVbH$>y)rQPYGkw{={~C1$@&h?7OFa$=JH%>_l`cV+(F&C#PE&yZjIA!f*_9 zXXMPhW(i|+59Q2y;3~$hx;$s)e(0yXB&X%&MU0jFP0q2i_)%x!Mc8lIE2{h7FaZ99>L(-MtKvr0 zKQ``Xtl%Bh>n)&rd86vwE70@R531gM=o_GSGWW_qXz;lJAW$ODL`2u7r)DOS! z!PBe$+gA@UHs`eZ$Gwk0p1)N;VeC;80{S1T&tLyz#&oka##NB_ zwHr10`?fQ-@^ej1!F=$)NwcX7`dGeA<2C*x?4(z-?JDqFZq{rgdoo;)C-$LxN;A;C z1MuJ1+_a(q^v5;(#=wWcCq1vIm!4PNBt6&7*4%dhc3?cCdE}1UvES92AN}H8$cJfu z_7&u;+Nb&X++RWNb(*)&fe)cg^Sj$#f!_a3dam84`SL69wPc!BHP?att=ATOS`ImV zPrLS`I-KL%we=^SXY6l&rftuG+)IkJ-}~Y(jD5?ceXjf{WBPpUmzJ}zuV!7zBFJgJ zU-#(j+pw=6>3$UW9oDz%KD9l}*mXI&|9JB<#)_`eef}}zlKZso(zU;beXP^hEIJ8) z@QMD$T<~33tQY_9CCK-j{;t?D#xDDX{=p|eulRobQy1pp?-7G8AHL!8+YR&X)8m{p z8md0?Vt)oh>xTEi@2iH5w?S^#H5uAFAm@2?2G7gY;Ohp%e)dfm!h?o4-ZsOoUNoF5 z4#LO$Z)4Tf@ITtwM$cV3@6A@|>2u=)XQ1!gOU57Wxd-y=H$Gdb0bf5b{>%$J%{1dl@4ZuDQo9b$y=QW#6H?H0SeK|}UskwAmOKW#eK-GPHJ(>Bv5(?{*>_^U#g`Y9d{M*Lvgrk@--X{<@~eUkBal~dN5S5Eajq9!R&f9CZ-5>j zEBL`9pu4QO;Q9ZA-e+qIetE-duxnSL{*Um3y4J!ORXDfH=M>KT;4kni&lWbk4?5-j zg#qsc=;zMD(Km00o_h+9iUG*wbm0r3|IgSpeTYik@3{kPIvEA2D`qZX1KOqw+N)T{}(H=4UbtDd~ZV{Ov$w($) zs0~ELumBlN#rq7x6`za`C0S^HdB<}yjVmM?0kL0*COHv8&PW8}^-M+9$Qq$Ap{=s* z2AP<#(JEAVJYg{snF`gEm6K_*Bn0b!WBsDo=AAp^gB`kEAKT8}-K;R0g?`Z)7X_E! z8R!+dgJHoLiw66gQJ-6I2Ls(cZ!C;If`O@6RNH^uw@2QWwuX$(&k<^fM3~401M7WG ze^9bO^^RxTkI4usi)4M108eVJdFw^D-xmhFS({q3Cb&ipq`_2F9YQFU=%eP~t zARJ^NCb9tj?_+-a6|Gds3)O56#)Q6D1ZUsv7DG`1_9{5Ua9@Nw18mXbBVj}YUqFD- zz#^kTAr=vZU`PyveEwjxJUd%VuynfNi6wsNcLuQaAeQOJ4ujp@*C#fWPIQJubnmXa z&xlX9cG}LSkrgH-8|LoyYiWKv&@(qMmPYgHDQHH-sNi<`eJ;u3vy-2dWO?t4{dr^% z;^y`pX-h1hVu`qqTn9`7mxvFR=oP#%pGVBT)QsWNEe&+E+>h@+MfOL6mxVray)PmL zys&)|w3Q3m(%qd^&a*NpCFLzso1R8Zy1ufKn#R_{qi2u49siyCaTy_heb^U=fz&wr#IQ3v()PLjvm|F3Dc4+4l@(Ndq-gK+GMLV4 ztKHaG+m;ccd)Vd)PH@5}&cWF#LiTr6bwCch9-_kOhu)++@Ds ze$8@k_n!k}JD!aXCGjd%taSgWb}RW7%Q<&WTj}R;9he#oDsQZGk0NwmJa}n-hxHor+a776^eZhb)8l>A( z5O;)djf(Ko9+i?U1Y?lX#;Lu0G8*YZFBJ~aJYtLbpad(uv! z2>k?0)J|c1M*rEp2Utb?cQ<`krf#%}-k9HsjSXaF8Y@VCK*m6HMn}CSb=0#Wnv^G8 zM*fCP(vKr~fa~c1XC+Wc1hU;1On|Mxr1u`M)mP@&9=!D{$H4)m0{8o)XU8%bxD6Q=d7p;~ppFo-` zr0cH5J8tq`X*MQ4U77gwcGpaNnwR)=b@J0n6`k9*(#{e4AHBKmoLfdH5Te^*+|;?J zqu6Vp70FWKLtQVmJf*lgkINUc5Ei$`e9!^+;E7|0+=YW23&tY;fz*W*@Gb!ZFkF7f0TyMH)Mk~9@^L18UJEir@2hVC`@=_gpuK7u2snQ7~TliZFh?SDIPU4 z!J60J)>1Q`O14abyT?fxq!^COr4{oU1EE+{85~a*O;3O{lF{zE*ip;`nYjY92s?B} zVSi4z{;VtL>AEtP2@7Pb{6;A##@$d}&MnE1_(TkIjhft#imN*EN1Wrc6^l)`iEhys zryC{c+9tZAku`k9Ok|tZJG$kQSSSs78r*Qu&yhW%KkA$Wm$Kt+_w+QR;TG|%n%3v4Pf0&@P7 zj_Gj~g`R~&a>If3;m65@V{Z=5_U1a?v)n=My`y0FVsh@xxbw6HqWB51 z2wTG{@I%-E{D}B1%E}eg%0ba5^AxYgm4zE1Q05vaqo?43D{@P@gvS>N`JDr#cw7#B zK}6x?Yy>BKNnf8+FowduJ`v%$E8-6O5I6+kbL>8EfE-aE*uO^TiAF<_H5C=`JpoWH z=Xm8#-$a2Gc^40twI5?fi>3W(ig;ueXP6P11p7pzKj`K%6X30;Ah6|vrDFmCDpY(8 z0i%~4_*JIL$P&{v#?OAb%1p!EDYeLaf71~j;4a`{`YOp9*j12!2=yJdZ64hz?YB+JF-e$gNFm{* zf#*bx0{?Gq&@V&>LgKoGOBV`}=zt%;^*O^{U!aWQ)iuJ>m7yKiF1#)QE(mM=z6>~5 zFp2`<8ewH6hpZ3sjC7LgLkI?_Fa(Fy6AXxJEBwB{f^?1F=k66soF0!r6;~P z#O(}lm)&B+73V?DD*eeL+`n>}>R_-JGU%naJMHeHjdAAbQWJ1#1xcR50}s42K3nFj&}u{GBGlDZIa*Q0 zSTo7W`q8ePdBclaEiz)hP3#Lsu_Y9DrLujNRrN>z)@-!b52n`3YYlnBPME1V*gwfy zMXZKdSTlaAn6R_irj^$;)mWOFs|2g1(d^*2P9axQYeWny6eVzcGnzuR_|1VxGDWW( zG#h1lMKu<)xwghp&gqs{H4;ZzY0gkYqjGF3)5();kZW~P62^tonXu)vVb!6(mk|rj z-*-^3w^rM0Y>m~@g`ahKBbD%(uz8WKS;jTZUn+Q<15~m025D7Yi-l(%QkEiNP*SPD z$p=mkoY2%rHtjvL6i9_YLa!PckDWiXPv%QqyTixNVH!VER=3h1jmaarF%{(K zJkCfDa?J_boCZIi(Snc}G05eL321WZn(7?MWT0Cs5b>!1no?#8xGQKEo0p1hm8#*>$tq&!NXuQr-HPf>3FlDgb|Ovm zlnaTzESz{0F~8G`B0SG_6?9ERmppV@f{aWzS$dK7pGcDxi29o^4Q?l7d50$ZKqM;m zVbw$;q<~(Vgx>Pm-Y?=e(1mzPc7oEVa zv>}DPWipYqg;-$oxqBSqjttYKDj}Q{fx5FY zf-aH2O$xpL-;cc^L+kCq?r1-%c$0!tqAi2#96>L-EBvm@#=DCBMut`W{P1K%CvB%{ zAdf_hQr=eTDz+Azjdy)&-e7AUH|;w}f47ggig@X0f%){{HMnc;9jv_RMTMTt)gtmn z6dyzZ0fZcsA)Q)+dQ|lMtw$p$*aUo$9<)Ds7gox)$rRl|>I6k7VDKRM_W2`{%2Qkw zjqdRLV(%`g*ODg5*)=^uOlSy6fsz3y>Q^KN#m)*w=eZxXRc@a<_}1WwL8mORA~+)o z{s^rsvN zLtR20cbFNpIYOFSEJz}x3WtgXZWul-^^B>E5g+QV@EXL1_z)>@@I>1U$aEH%XAlG( zQEB92bl%`w)Dqhr+&ri-ENg9m_m-(40^dbGPH43?QMEjdHV({-Oo+afyfe2n>Trhx zutRt}(k-f9gy0PZrDC~)Q(kBxo@7xZ#znA5h7i;(;-On*utJpOctIY;?=TwbnZVil zjOedrfK?BlrsQt_DKixXdU%RYCBX=OP<^o6i!lCDV07HH`vO@J{Ok6v7L<_-NT5TW0b8)I+i~Og?6FImULQ4E%reG|wkn&s(OkbqXbScV z8-pkjOKFNiZzejLiE8 z{S+;d$A43V=6cHM(r%$Vp4X)$Hvwg52TuIniX&G=+O4Vf)s0lPG6stxGJ&)>MV<4 zZdwy|tcJTxwOCYTWh6?S9lceT6D^2w{3lz6YFYhM-!7l>+m#vLVi`T<$liS0zsW1; z5;;=(G5}Sl6;?I1Hk*Yv6(->{x7N`xkw&k3>uPx^b-l&Hi=HVGSVzn1F)(JAp>pf3 zJoifjQd=#G8mqdYu|8w5G^yn_Nu|g%5?b$Ka=G$4Dzjw*zuGOIjh$D(=qz=0O^xQ- z34m%d+r1=3%ECKp>C0{TENwZh#hjIre*dWhmygaKPIV8O_Qreju+Clsu-A}fwZ(dYx039c|48hSNX|+ zCe^P}Z+qB#L6)(mrlGcmi#ZFZmOvG5QO|+lQE4+-;PnKbR=_T*=@C(aBe$p+W1Yy9 z3D)XE*;ue?#nhmvu^v^j>M&9YUW3oFqKxN$&75jiaJ(8cuB41Q8=l$NJC}1?edwSp zjN&HhcuI^4ob$;xO1W3K!JD#Gqs1<4L`N1O!X!AWXh~O*?ZKpw5YJ%oN)-u==-EH^ z=C<(>9~$iGu5SB$Pm{u%dL0N({KO!}b`;ZoXv*e<<2#W#MESivZM^HxLEBDwD2d{tyY?$lo5=r z^4R1g80s{6>ZTT^i6T!DTw3%wQ_9jQ1n(B3?w-V!CtFZ_a?=AcgSl1fxf3sU<47VZXqOr_y08>}QK_+4C z0Yi(ZI9$3WOV#?s*~)}f4_s1oqA?EDY}v>?N+zIw__V+JuGf_iY7-d>(IIP^cs0vGfnYSWH*=b3XA_9bXJn0qdIS|am-q&vgvH&WHg7jb{*gK z@s>aFGJP5i$#gK%r|A7V-rI7a(&S$~+GWo7=2qtK-Q}s~;qG18CFXRsnh%`cg)y%aUYi)uv(o2w>1+-&;j=n?&RqlE+ z&1@Qt^QVNI7GxO{L;ctyS&jimS1NHx4P=_XmW89K@}m91!5lPAEzf+bY35r7(&$#={goO?EF3;Bpdk z-C0&{m{_i5LWiy+A2V%Hnhzaawx@~aVj-teOP%@5XsmtD;jS$o96gJs;3K26oo>rM zwn%ZA_^SMVav^8pBhdim)3GeNwDPue7=02G3lk0ojHMTmqbi^XxE!2n)d z5>drKdkX^qlWd}hR^ESV)NZwmohPr6+DO7Mn=t*386c`t(qMbyd~$a>aU=Z275l}b zXSdDmER;!oGx_EVO#zlQkOugq7@5gL8nY6oW%BZVQG%YV`s{?F*w>u4((dZfIglfD z@dcWoBLid0si{Jva+DXEFPM$y8Q#S%yZDTwc>6ymi&f*M&AYw#S!01Ewn~b{kG|dV zCB1h*@)~@ryL#Ldzq#d0rSue9c~}|?qjEFelES!T5M4$Q9>;|jjVK{U`JG2Y5O04E znyTChCC89qe%(Og?td>%@OV2;V@$H9&I;&{^vLzp}+ zA}gjE0H?DY&74q=P`a{`8_1$bOkyTANl}zCTK^$Ax81qj`l_tWIoKFp+TbZ}E4(C3 zjB8Ul!9G!|B}a;e^|s1U2L+5|;^H;jCoaP*tH66zsmb4&_8uJUT1OSx^0E~@6ba(> zne19#reriebWm-5)pCd3Vf#K6Yu&He>yw*^5797sji{G}21THJEm}oVNXq31GsdbWFvY`a86AmH;j^=A^ zXFChGytjL?V}wosjq}r--?)i}MLS2N(i{yLkG*Uz^MB|pwB0*yq9|wIaQC0vN|Vhh zI#-<|u{mOcLNEVH9Flk`=mqX&80g9CXz+$?#FGb6k@7t zBflZ?wi2qpA!>I?97@gkL?~AWLx@{Oa=u? z$R`@}U{=&mu>hqX*$s={7t3hfQY_%jr58@eJ|A@q8xfu^a6fv}cS$CW5u17csrZnz zdorc**`t@4J0*CUVIMrzHGlio{inEVuR`;`n%p`iq>7>AP>NL^)Ik*deawWy7Sb@e z2RS62bPhnel{_cvd$b$6O1+4|2?Fm&LG$Iw`*4k9773aWp{lleZuZT4q&mOnjHQDZ zqyjc2fz&=s)jOpI4Ys3bp_ng3!kve`tn>dM>juWLH;$q0%i9+VI|>KY3GY$Qsud=3 zpbBr;A>2WW38tGkL{b(_$#T;EVcv<>55I+^qAXomysX1BaS~HEQg_P35(Jbl&^X9( zCL1RadL;+sogw(j9X|MO8q!}{U(Ibz*UB?`X{LJ8PFxz)U)8Zn!&FnFMK)KRq9K+B zrk65V#Wc9F2{#*rmgsS(LnpnLOjz;4PC6v%n6xEB7D~HEKb*fu!J8%NC=+S|`3V%M zG(cvRhJgD2;9KT0OuOJmUMD|My+t~n*n+mr*X?U + + + + AbstractAlert + + + Close + 關閉 + + + + Snooze Update + 暫停更新 + + + + Reboot and Update + 重啟並更新 + + + + AdvancedNetworking + + + Back + 回上頁 + + + + Enable Tethering + 啟用網路分享 + + + + Tethering Password + 網路分享密碼 + + + + + EDIT + 編輯 + + + + Enter new tethering password + 輸入新的網路分享密碼 + + + + IP Address + IP 地址 + + + + Enable Roaming + 啟用漫遊 + + + + APN Setting + APN 設置 + + + + Enter APN + 輸入 APN + + + + leave blank for automatic configuration + 留空白將自動配置 + + + + ConfirmationDialog + + + + Ok + 確定 + + + + Cancel + 取消 + + + + DeclinePage + + + You must accept the Terms and Conditions in order to use openpilot. + 您必須先接受條款和條件才能使用 openpilot。 + + + + Back + 回上頁 + + + + Decline, uninstall %1 + 拒絕並卸載 %1 + + + + DevicePanel + + + Dongle ID + Dongle ID + + + + N/A + 無法使用 + + + + Serial + 序號 + + + + Driver Camera + 駕駛監控 + + + + PREVIEW + 預覽 + + + + Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off) + 預覽駕駛監控鏡頭畫面,方便調整設備安裝的位置,以提供更準確的駕駛監控。(車子必須保持在熄火的狀態) + + + + Reset Calibration + 重置校準 + + + + RESET + 重置 + + + + Are you sure you want to reset calibration? + 您確定要重置校準嗎? + + + + Review Training Guide + 觀看使用教學 + + + + REVIEW + 觀看 + + + + Review the rules, features, and limitations of openpilot + 觀看 openpilot 的使用規則、功能和限制 + + + + Are you sure you want to review the training guide? + 您確定要觀看使用教學嗎? + + + + Regulatory + 法規/監管 + + + + VIEW + 觀看 + + + Change Language + 更改語言 + + + CHANGE + 更改 + + + Select a language + 選擇語言 + + + + Reboot + 重新啟動 + + + + Power Off + 關機 + + + + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. + openpilot 需要將裝置固定在左右偏差 4° 以內,朝上偏差 5° 以内或朝下偏差 8° 以内。鏡頭在後台會持續自動校準,很少有需要重置的情况。 + + + + Your device is pointed %1° %2 and %3° %4. + 你的設備目前朝%2 %1° 以及朝%4 %3° 。 + + + + down + + + + + up + + + + + left + + + + + right + + + + + Are you sure you want to reboot? + 您確定要重新啟動嗎? + + + + Disengage to Reboot + 請先取消控車才能重新啟動 + + + + Are you sure you want to power off? + 您確定您要關機嗎? + + + + Disengage to Power Off + 請先取消控車才能關機 + + + + DriveStats + + + Drives + 旅程 + + + + Hours + 小時 + + + + ALL TIME + 總共 + + + + PAST WEEK + 上周 + + + + KM + 公里 + + + + Miles + 英里 + + + + DriverViewScene + + + camera starting + 開啟相機中 + + + + InputDialog + + + Cancel + 取消 + + + + Need at least + 需要至少 + + + + characters! + 個字元! + + + + Installer + + + Installing... + 安裝中… + + + + Receiving objects: + 接收對象: + + + + Resolving deltas: + 分析差異: + + + + Updating files: + 更新檔案: + + + + MapPanel + + + Current Destination + 當前目的地 + + + + CLEAR + 清除 + + + + Recent Destinations + 最近目的地 + + + + Try the Navigation Beta + 試用導航功能 + + + + Get turn-by-turn directions displayed and more with a comma +prime subscription. Sign up now: https://connect.comma.ai + 成為 comma 高級會員來使用導航功能 +立即註冊:https://connect.comma.ai + + + Get turn-by-turn directions displayed and more with a comma +prime subscription. Sign up now: https://connect.comma.ai + 成為 comma 高級會員來使用導航功能,立即註冊:https://connect.comma.ai + + + + No home +location set + 未設定 +住家位置 + + + + No work +location set + 未設定 +工作位置 + + + + no recent destinations + 沒有最近的導航記錄 + + + + MultiOptionDialog + + Select + 選擇 + + + Cancel + 取消 + + + + Networking + + + Advanced + 進階 + + + + Enter password + 輸入密碼 + + + + + for " + 給 " + + + + Wrong password + 密碼錯誤 + + + + NvgWindow + + + km/h + km/h + + + + mph + mph + + + + + MAX + 最高 + + + + + SPEED + 速度 + + + + + LIMIT + 速限 + + + + OffroadHome + + + UPDATE + 更新 + + + + ALERTS + 提醒 + + + + ALERT + 提醒 + + + + PairingPopup + + + Pair your device to your comma account + 將設備與您的 comma 帳號配對 + + + + + <ol type='1' style='margin-left: 15px;'> + <li style='margin-bottom: 50px;'>Go to https://connect.comma.ai on your phone</li> + <li style='margin-bottom: 50px;'>Click "add new device" and scan the QR code on the right</li> + <li style='margin-bottom: 50px;'>Bookmark connect.comma.ai to your home screen to use it like an app</li> + </ol> + + + <ol type='1' style='margin-left: 15px;'> + <li style='margin-bottom: 50px;'>用手機連至 https://connect.comma.ai</li> + <li style='margin-bottom: 50px;'>點選 "add new device" 後掃描右邊的二維碼</li> + <li style='margin-bottom: 50px;'>將 connect.comma.ai 加入您的主屏幕,以便像手機 App 一樣使用它</li> + </ol> + + + + + PrimeAdWidget + + + Upgrade Now + 馬上升級 + + + + Become a comma prime member at connect.comma.ai + 成為 connect.comma.ai 的高級會員 + + + + PRIME FEATURES: + 高級會員特點: + + + + Remote access + 遠程訪問 + + + + 1 year of storage + 一年的雲端行車記錄 + + + + Developer perks + 開發者福利 + + + + PrimeUserWidget + + + ✓ SUBSCRIBED + ✓ 已訂閱 + + + + comma prime + comma 高級會員 + + + + CONNECT.COMMA.AI + CONNECT.COMMA.AI + + + + COMMA POINTS + COMMA 積分 + + + + QObject + + + Reboot + 重新啟動 + + + + Exit + 離開 + + + + dashcam + 行車記錄器 + + + + openpilot + openpilot + + + + %1 minute%2 ago + we don't need %2 + %1 分鐘前 + + + + %1 hour%2 ago + we don't need %2 + %1 小時前 + + + + %1 day%2 ago + we don't need %2 + %1 天前 + + + + Reset + + + Reset failed. Reboot to try again. + 重置失敗。請重新啟動後再試。 + + + + Are you sure you want to reset your device? + 您確定要重置你的設備嗎? + + + + Resetting device... + 重置設備中… + + + + System Reset + 系統重置 + + + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + 系統重置已觸發。請按確認刪除所有內容和設置。按取消恢復啟動。 + + + + Cancel + 取消 + + + + Reboot + 重新啟動 + + + + Confirm + 確認 + + + + Unable to mount data partition. Press confirm to reset your device. + 無法掛載數據分區。請按確認重置您的設備。 + + + + RichTextDialog + + + Ok + 確定 + + + + SettingsWindow + + + × + × + + + + Device + 設備 + + + + + Network + 網路 + + + + Toggles + 設定 + + + + Software + 軟體 + + + + Navigation + 導航 + + + + Setup + + + WARNING: Low Voltage + 警告:電壓過低 + + + + Power your device in a car with a harness or proceed at your own risk. + 請使用車上 harness 提供的電源,若繼續的話您需要自擔風險。 + + + + Power off + 關機 + + + + + + Continue + 繼續 + + + + Getting Started + 入門 + + + + Before we get on the road, let’s finish installation and cover some details. + 在我們上路之前,讓我們完成安裝並介紹一些細節。 + + + + Connect to Wi-Fi + 連接到無線網絡 + + + + + Back + 回上頁 + + + + Continue without Wi-Fi + 在沒有 Wi-Fi 的情況下繼續 + + + + Waiting for internet + 連接至網路中 + + + + Choose Software to Install + 選擇要安裝的軟體 + + + + Dashcam + 行車記錄器 + + + + Custom Software + 定制的軟體 + + + + Enter URL + 輸入網址 + + + + for Custom Software + 定制的軟體 + + + + Downloading... + 下載中… + + + + Download Failed + 下載失敗 + + + + Ensure the entered URL is valid, and the device’s internet connection is good. + 請確定您輸入的是有效的安裝網址,並且確定設備的網路連線狀態良好。 + + + + Reboot device + 重新啟動 + + + + Start over + 重新開始 + + + + SetupWidget + + + Finish Setup + 完成設置 + + + + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. + 將您的設備與 comma connect (connect.comma.ai) 配對並領取您的 comma 高級會員優惠。 + + + + Pair device + 配對設備 + + + + Sidebar + + + + CONNECT + 雲端服務 + + + + OFFLINE + 已離線 + + + + + ONLINE + 已連線 + + + + ERROR + 錯誤 + + + + + + TEMP + 溫度 + + + + HIGH + 偏高 + + + + GOOD + 正常 + + + + OK + 一般 + + + + VEHICLE + 車輛通訊 + + + + NO + 未連線 + + + + PANDA + 車輛通訊 + + + + GPS + GPS + + + + SEARCH + 車輛通訊 + + + + -- + -- + + + + Wi-Fi + + + + + ETH + + + + + 2G + + + + + 3G + + + + + LTE + + + + + 5G + + + + + SoftwarePanel + + + Git Branch + Git 分支 + + + + Git Commit + Git 提交 + + + + OS Version + 系統版本 + + + + Version + 版本 + + + + Last Update Check + 上次檢查時間 + + + + The last time openpilot successfully checked for an update. The updater only runs while the car is off. + 上次成功檢查更新的時間。更新系統只會在車子熄火時執行。 + + + + Check for Update + 檢查更新 + + + + CHECKING + 檢查中 + + + + Uninstall + 卸載 + + + + UNINSTALL + 卸載 + + + + Are you sure you want to uninstall? + 您確定您要卸載嗎? + + + + failed to fetch update + 下載更新失敗 + + + + + CHECK + 檢查 + + + + SshControl + + + SSH Keys + SSH 密鑰 + + + + Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. + 警告:這將授權給 GitHub 帳號中所有公鑰 SSH 訪問權限。切勿輸入非您自己的 GitHub 用戶名。comma 員工「永遠不會」要求您添加他們的 GitHub 用戶名。 + + + + + ADD + 新增 + + + + Enter your GitHub username + 請輸入您 GitHub 的用戶名 + + + + LOADING + 載入中 + + + + REMOVE + 移除 + + + + Username '%1' has no keys on GitHub + GitHub 用戶 '%1' 沒有設定任何密鑰 + + + + Request timed out + 請求超時 + + + + Username '%1' doesn't exist on GitHub + GitHub 用戶 '%1' 不存在 + + + + SshToggle + + + Enable SSH + 啟用 SSH 服務 + + + + TermsPage + + + Terms & Conditions + 條款和條件 + + + + Decline + 拒絕 + + + + Scroll to accept + 滑動至頁尾接受條款 + + + + Agree + 接受 + + + + TogglesPanel + + + Enable openpilot + 啟用 openpilot + + + + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. + 使用 openpilot 的主動式巡航和車道保持功能,開啟後您需要持續集中注意力,設定變更在重新啟動車輛後生效。 + + + + Enable Lane Departure Warnings + 啟用車道偏離警告 + + + + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). + 車速在時速 50 公里 (31 英里) 以上且未打方向燈的情況下,如果偵測到車輛駛出目前車道線時,發出車道偏離警告。 + + + + Enable Right-Hand Drive + 啟用右駕模式 + + + + Allow openpilot to obey left-hand traffic conventions and perform driver monitoring on right driver seat. + openpilot 將對右側駕駛進行監控 (但仍遵守靠左駕的交通慣例)。 + + + + Use Metric System + 使用公制單位 + + + + Display speed in km/h instead of mph. + 啟用後,速度單位顯示將從 mp/h 改為 km/h。 + + + + Record and Upload Driver Camera + 記錄並上傳駕駛監控影像 + + + + Upload data from the driver facing camera and help improve the driver monitoring algorithm. + 上傳駕駛監控的錄像來協助我們提升駕駛監控的準確率。 + + + + Disengage On Accelerator Pedal + 油門取消控車 + + + + When enabled, pressing the accelerator pedal will disengage openpilot. + 啟用後,踩踏油門將會取消 openpilot 控制。 + + + + Show ETA in 24h format + 預計到達時間單位改用 24 小時制 + + + + Use 24h format instead of am/pm + 使用 24 小時制。(預設值為 12 小時制) + + + + openpilot Longitudinal Control + openpilot 縱向控制 + + + + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! + openpilot 將會關閉雷達訊號並接管油門和剎車的控制。注意:這也會關閉自動緊急煞車 (AEB) 系統! + + + + Updater + + + Update Required + 系統更新 + + + + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. + 設備的操作系統需要更新。請將您的設備連接到 Wi-Fi 以獲得最快的更新體驗。下載大小約為 1GB。 + + + + Connect to Wi-Fi + 連接到無線網絡 + + + + Install + 安裝 + + + + Back + 回上頁 + + + + Loading... + 載入中… + + + + Reboot + 重新啟動 + + + + Update failed + 更新失敗 + + + + WifiUI + + + + Scanning for networks... + 掃描無線網路中... + + + + CONNECTING... + 連線中... + + + + FORGET + 清除 + + + + Forget Wi-Fi Network " + 清除 Wi-Fi 網路 " + + + From e0f8f50baa209f0f5fc713100bcec16411cd5925 Mon Sep 17 00:00:00 2001 From: "Mr.one" <84395321+hellokitty-666@users.noreply.github.com> Date: Sat, 9 Jul 2022 03:49:04 +0800 Subject: [PATCH 252/302] Improve Chinese (Simplified) translations (#25075) * Optimize Chinese local translation * update QM Co-authored-by: Shane Smiskol --- selfdrive/ui/translations/main_zh-CHS.qm | Bin 17617 -> 17629 bytes selfdrive/ui/translations/main_zh-CHS.ts | 38 +++++++++++------------ 2 files changed, 19 insertions(+), 19 deletions(-) diff --git a/selfdrive/ui/translations/main_zh-CHS.qm b/selfdrive/ui/translations/main_zh-CHS.qm index 627f6afc204dba0b2c2a87f13cad266e9edcbd4f..be6c51030617f25c54c086e107274a1b0434ea5c 100644 GIT binary patch delta 1770 zcmX9;ZB$g%8h*~1ea_4|b7oG+SD^;X0P$^JzYxI!S13>@2IbOBQ@CSkUNenbmUI0U zF~yFQijpO0S*D9g%a6*G^pb*F+VU$#eaRTuj;(S2d0bE6ZG6+ayOc_P&AWq?)r-K+h8L%G(jNSZB z0x@%d$Cd+W%vrFSc`gHwKgn}RK=EMiokipq>LIQG{D~~I;9j5(VpT1GwjkP;2QkJ9 z;;8>YZ0Z6e9inL{6DklbpA(B9&Iq7?JCrpsKvD&iJ-Yz?Yp4e<5qn{enZ*3_VNW>^ zI88ik67^7wZC(UFl5;V(XFo7_B*tko0COn{hS!h?8>q--2Zu3!jzuLBFyTiM=yw|v z-}n#rSE58d&iKnHnX!b0Q}NWUdcg4$CgpEr!9q;_;B_FY6jQ%$=Ksg=Vi~*ccLsmI z!}G=xy!UOZAIQ!`h0^_Xae()fG;AF$O6!t} zPf*U->(Z7Bj1T)=YAq2=yi&R-?*O9yBJ~bg4&0w2>%MP*_}Aq4?hYV*r<|uRAhBlo znfusq+MDvW^YI!F%#uG_OJ;-I@|XGR0QVO8`(h@J`b}CMn8$~P z+dguWUgBX};{i^KY1j@mhBKYlS|~^R-xJe!1z6;!cs`#Jn&ZT)9ixGPd&Da78!%+4 z*pz>S^OF!ncSaBg^oXtXeL(WR#QR-ktQjIcK2rlkFB6~6uBS-z#6g2<8@I)&D{YMb zC{F$KGxL8UIv)8HQ2$W$;S@1B^P1wSdWotuC}Z65lwBy3rnjw220zoXQzzZF{aYFteGCI4`Nn-<<=dtNI9y?u_YXeA5`}*>A>WHrD|4h z9{E?OV;jE!Mod?yNK`ZSq`IT;F7RNKdL(@_VDD9LjlV!MJMEq%>JqQo8={u6jhF3v z=XR37^CnyKwWyQG!g0F=qRv}ru&Se{Q7OqYOUkVgsn~1?S{T*^+p!f^g|CTBsN_?=Hod<)|>PP`5GM5 znPVM0BjT!BH>3c!l9(68xC5#7eI!|1q zA#u^pe?HN~%adS)9cAIJa+u0%d}!Sz`Mqr;0_O`e_f z^oXk|m+0+teVav3weQ^FA96I~_PV21v6=g>x;=ek*z{NKjLUooQfu6WYbi!Zg1fSo zH!ps#d)w7V>Fx~o?t11O{JT}EM(4Gd5m)Z=Hos<$>*DV8QRZAH0ZcP%=m6`yA__1Ae{?jW#mXseO=O=gEc*soo|=zSTj;m QmkxU&cA6Qe&dkyO1fHhgfdBvi delta 1804 zcmYLJYg80v7=C7UW_D+Gb|w@gNd*>AxvEKs3YJ(XXdsAXp;5}ZQD)jfsZ95jlA=j? zMhy|j62dI=#2S@ZSptQmcF_*Sp$x%G*HdPiiKnNtKl(A}+3(%&y*F-7`>S|nRt>|$UAojFuVY;9|rVS_l=K z`>RkO9-;kF6fAt2iAUhBrUtHa1^lU$TavPhwMyYxiw6kvFhv|hRhj9)2LXC31F zj0~WW9Kd0{QfMK_WS$x63{ z`liXNk`0dSetFY&rd87eI7|rO@c00xHORHkQ%ud08=mFZ2D|0`pPU8~TI7!hNR?PF zABp^e)Isj_5FV({NB+-3MEpE>MqPx^egi_`@ z^<;MrXCq(j33`+-!#-_lJYNl;qHD#UAEW$=R&ilCFl-btodF)wHk~thF4wkRr+n^h zTJ@pbEa-c!wrehzWwTa)jB?t3*Y<7LO1=iPgJWebUB33QmwvLSwQ3{y8oaBu4oTx~ z)M)1yl`_v+r_i#7_m?@N4!5BY=7uwd`^q#n{icz6nh!z3dSm8uBqPXeRP5yD#WWgq z=We6A_ZfQ|7jh>XpN^L$qq#1#914|VgtYYEn#QvQr^`$XRKZB$6R_5JX4Cy z>hCtpDwyYwiTcK&I#y*BmFH-_Jijv`+h!AUT>klEjyR+Z%c@{SrH&N7^=GF}6 REVIEW - 审查 + 重新查看 @@ -180,15 +180,15 @@ VIEW - 看法 + 查看 Change Language - 改变语言 + 切换语言 CHANGE - 改变 + 切换 Select a language @@ -227,7 +227,7 @@ left - 剩下 + 向左 @@ -270,7 +270,7 @@ ALL TIME - 整天 + 全部 @@ -285,7 +285,7 @@ Miles - 迈尔斯 + 英里 @@ -293,7 +293,7 @@ camera starting - 相机启动 + 相机启动中 @@ -324,7 +324,7 @@ Receiving objects: - 接收物体: + 正在接收: @@ -462,12 +462,12 @@ location set ALERTS - 个警报 + 警报 ALERT - 个警报 + 警报 @@ -561,7 +561,7 @@ location set Exit - 出口 + 退出 @@ -571,7 +571,7 @@ location set openpilot - 开放式飞行员 + openpilot @@ -732,7 +732,7 @@ location set Waiting for internet - 等待上网 + 等待网络连接 @@ -857,7 +857,7 @@ location set NO - + 未连接 @@ -1046,12 +1046,12 @@ location set Decline - 衰退 + 拒绝 Scroll to accept - 滚动接受 + 滑动接受 @@ -1084,7 +1084,7 @@ location set Enable Right-Hand Drive - 启用右手驱动 + 启用右舵模式 @@ -1114,7 +1114,7 @@ location set Disengage On Accelerator Pedal - 松开加速踏板 + 踩油门解除 From df251ef50ebfe5c997e14a03fca4ec932bc4c5cf Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 8 Jul 2022 13:00:43 -0700 Subject: [PATCH 253/302] Fix master-ci dirty working tree + CI test (#25087) * check * test for dirty working tree * swap order * fix diff --- .github/workflows/selfdrive_tests.yaml | 7 +++++-- .gitignore | 2 -- Jenkinsfile | 1 + rednose_repo | 2 +- release/check-dirty.sh | 11 +++++++++++ release/files_common | 3 +++ selfdrive/loggerd/.gitignore | 1 + 7 files changed, 22 insertions(+), 5 deletions(-) create mode 100755 release/check-dirty.sh diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 35a08d4fe9..99a21b58f3 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -59,11 +59,14 @@ jobs: TARGET_DIR=$STRIPPED_DIR release/build_devel.sh cp Dockerfile.openpilot_base $STRIPPED_DIR - name: Build Docker image - run: eval "$BUILD" + run: | + eval "$BUILD" + rm $STRIPPED_DIR/Dockerfile.openpilot_base - name: Build openpilot and run checks run: | cd $STRIPPED_DIR ${{ env.RUN }} "CI=1 python selfdrive/manager/build.py && \ + release/check-dirty.sh && \ python -m unittest discover selfdrive/car" build_all: @@ -89,7 +92,7 @@ jobs: - name: Build Docker image run: eval "$BUILD" - name: Build openpilot with all flags - run: ${{ env.RUN }} "scons -j$(nproc) --extras --test" + run: ${{ env.RUN }} "scons -j$(nproc) --extras --test && release/check-dirty.sh" - name: Cleanup scons cache run: | ${{ env.RUN }} "scons -j$(nproc) --extras --test && \ diff --git a/.gitignore b/.gitignore index 0092c4dc94..e1ff5d5008 100644 --- a/.gitignore +++ b/.gitignore @@ -45,8 +45,6 @@ system/proclogd/proclogd selfdrive/ui/_ui selfdrive/test/longitudinal_maneuvers/out selfdrive/visiond/visiond -selfdrive/loggerd/loggerd -selfdrive/loggerd/bootlog selfdrive/sensord/_gpsd selfdrive/sensord/_sensord system/camerad/camerad diff --git a/Jenkinsfile b/Jenkinsfile index 0fa623fbcd..4e13717851 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -115,6 +115,7 @@ pipeline { phone_steps("tici", [ ["build master-ci", "cd $SOURCE_DIR/release && TARGET_DIR=$TEST_DIR EXTRA_FILES='tools/' ./build_devel.sh"], ["build openpilot", "cd selfdrive/manager && ./build.py"], + ["check dirty", "release/check-dirty.sh"], ["test manager", "python selfdrive/manager/test/test_manager.py"], ["onroad tests", "cd selfdrive/test/ && ./test_onroad.py"], ["test car interfaces", "cd selfdrive/car/tests/ && ./test_car_interfaces.py"], diff --git a/rednose_repo b/rednose_repo index 225dbacbaa..3b6bd703b7 160000 --- a/rednose_repo +++ b/rednose_repo @@ -1 +1 @@ -Subproject commit 225dbacbaac312f85eaaee0b97a3acc31f9c6b47 +Subproject commit 3b6bd703b7a7667e4f82d0b81ef9a454819b94bd diff --git a/release/check-dirty.sh b/release/check-dirty.sh new file mode 100755 index 0000000000..9c6389f380 --- /dev/null +++ b/release/check-dirty.sh @@ -0,0 +1,11 @@ +#!/usr/bin/bash +set -e + +DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" +cd $DIR + +if [ ! -z "$(git status --porcelain)" ]; then + echo "Dirty working tree after build:" + git status --porcelain + exit 1 +fi diff --git a/release/files_common b/release/files_common index 260e37e29a..fb91170561 100644 --- a/release/files_common +++ b/release/files_common @@ -231,6 +231,7 @@ selfdrive/locationd/models/gnss_helpers.py selfdrive/locationd/calibrationd.py +system/logcatd/.gitignore system/logcatd/SConscript system/logcatd/logcatd_systemd.cc @@ -239,6 +240,7 @@ system/proclogd/main.cc system/proclogd/proclog.cc system/proclogd/proclog.h +selfdrive/loggerd/.gitignore selfdrive/loggerd/SConscript selfdrive/loggerd/encoder/encoder.cc selfdrive/loggerd/encoder/encoder.h @@ -414,6 +416,7 @@ scripts/stop_updater.sh pyextra/.gitignore pyextra/acados_template/** +rednose/.gitignore rednose/** laika/** diff --git a/selfdrive/loggerd/.gitignore b/selfdrive/loggerd/.gitignore index 6437be5e38..53dc24e6f2 100644 --- a/selfdrive/loggerd/.gitignore +++ b/selfdrive/loggerd/.gitignore @@ -1,3 +1,4 @@ loggerd encoderd +bootlog tests/test_logger From 8ea982264ec4ba7aa47a3228236f943e76a911c5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 8 Jul 2022 13:05:25 -0700 Subject: [PATCH 254/302] remove casync from agnos manifest for now --- system/hardware/tici/agnos.json | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/system/hardware/tici/agnos.json b/system/hardware/tici/agnos.json index 853d3ab434..7ccea95ee7 100644 --- a/system/hardware/tici/agnos.json +++ b/system/hardware/tici/agnos.json @@ -47,8 +47,6 @@ "size": 10737418240, "sparse": true, "full_check": false, - "has_ab": true, - "casync_caibx": "https://commadist.azureedge.net/agnosupdate/system-59622eddd068d49f2e9df69ef5115e3f205ad369539690a5b240c8c93796dd13.caibx", - "casync_store": "https://commadist.azureedge.net/agnosupdate/system-59622eddd068d49f2e9df69ef5115e3f205ad369539690a5b240c8c93796dd13" + "has_ab": true } ] From 1d6623c6092e312d03ce4d434077780e2287a010 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 8 Jul 2022 13:18:12 -0700 Subject: [PATCH 255/302] update release notes --- RELEASES.md | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index 392e9dc486..7e8f80500e 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,18 +1,18 @@ -Version 0.8.15 (2022-07-XX) +Version 0.8.15 (2022-07-20) ======================== * New driving model * Path planning uses end-to-end output instead of lane lines at all times * Reduced ping pong * Improved lane centering * New lateral controller based on physical wheel torque model - * Much smoother control, consistent across the speed range + * Much smoother control that's consistent across the speed range * Effective feedforward that uses road roll * Simplified tuning, all car-specific parameters can be derived from data + * Used on select Toyota and Hyundai models at first * Significantly improved control on TSS-P Prius * New driver monitoring model * Takes a larger input frame * Outputs a driver state for both driver and passenger - * Automatically determines which side the driver is on (soon) * Navigation improvements * Speed limits shown while navigating * Faster position fix by using raw GPS measurements @@ -23,8 +23,8 @@ Version 0.8.15 (2022-07-XX) * More consistent camera view perspective across cars * Reduced power usage: device runs cooler and fan spins less * AGNOS 5 - * Support for delta updates to reduce data usage on future OS updates * Support VSCode remote SSH target + * Support for delta updates to reduce data usage on future OS updates * Honda Civic 2022 support * Hyundai Tucson 2021 support thanks to bluesforte! * Lexus NX Hybrid 2020 support thanks to AlexandreSato! From 5f77451aec3345c80f8cf2e5cd15c0ce911d5612 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 8 Jul 2022 13:46:09 -0700 Subject: [PATCH 256/302] FW fingerprinting updates (#25088) * Print brand along with ecu * fix json decoding * fw_versions updates * add timeout handling back * keep logging the same --- selfdrive/car/car_helpers.py | 6 +++--- selfdrive/car/fw_versions.py | 22 ++++++++++------------ 2 files changed, 13 insertions(+), 15 deletions(-) diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 7f83732153..690072cc4d 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -79,7 +79,7 @@ interfaces = load_interfaces(interface_names) def fingerprint(logcan, sendcan): fixed_fingerprint = os.environ.get('FINGERPRINT', "") skip_fw_query = os.environ.get('SKIP_FW_QUERY', False) - ecu_responses = set() + ecu_rx_addrs = set() if not fixed_fingerprint and not skip_fw_query: # Vin query only reliably works thorugh OBDII @@ -98,7 +98,7 @@ def fingerprint(logcan, sendcan): else: cloudlog.warning("Getting VIN & FW versions") _, vin = get_vin(logcan, sendcan, bus) - ecu_responses = get_present_ecus(logcan, sendcan) + ecu_rx_addrs = get_present_ecus(logcan, sendcan) car_fw = get_fw_versions(logcan, sendcan) exact_fw_match, fw_candidates = match_fw_to_car(car_fw) @@ -166,7 +166,7 @@ def fingerprint(logcan, sendcan): source = car.CarParams.FingerprintSource.fixed cloudlog.event("fingerprinted", car_fingerprint=car_fingerprint, source=source, fuzzy=not exact_match, - fw_count=len(car_fw), ecu_responses=ecu_responses, error=True) + fw_count=len(car_fw), ecu_responses=list(ecu_rx_addrs), error=True) return car_fingerprint, finger, vin, car_fw, source, exact_match diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 03dcece10c..c51d120166 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -290,24 +290,21 @@ def match_fw_to_car(fw_versions, allow_fuzzy=True): versions = get_interface_attr('FW_VERSIONS', ignore_none=True) # Try exact matching first - exact_matches = [True] + exact_matches = [(True, match_fw_to_car_exact)] if allow_fuzzy: - exact_matches.append(False) + exact_matches.append((False, match_fw_to_car_fuzzy)) - for exact_match in exact_matches: + for exact_match, match_func in exact_matches: # For each brand, attempt to fingerprint using FW returned from its queries + matches = set() for brand in versions.keys(): fw_versions_dict = build_fw_dict(fw_versions, filter_brand=brand) + matches |= match_func(fw_versions_dict) - if exact_match: - matches = match_fw_to_car_exact(fw_versions_dict) - else: - matches = match_fw_to_car_fuzzy(fw_versions_dict) + if len(matches): + return exact_match, matches - if len(matches) == 1: - return exact_match, matches - - return True, [] + return True, set() def get_present_ecus(logcan, sendcan): @@ -448,9 +445,10 @@ if __name__ == "__main__": print() print("Found FW versions") print("{") + padding = max([len(fw.brand) for fw in fw_vers]) for version in fw_vers: subaddr = None if version.subAddress == 0 else hex(version.subAddress) - print(f" (Ecu.{version.ecu}, {hex(version.address)}, {subaddr}): [{version.fwVersion}]") + print(f" Brand: {version.brand:{padding}} - (Ecu.{version.ecu}, {hex(version.address)}, {subaddr}): [{version.fwVersion}]") print("}") print() From b5f0cb22a5aab4ea94cdc817bf0331919a265bfb Mon Sep 17 00:00:00 2001 From: realfast Date: Fri, 8 Jul 2022 16:36:02 -0500 Subject: [PATCH 257/302] Add Chrysler FPv2 requests and logging (#24460) * Chrylser FPv2 * Update fw_versions.py * formatting and remove default * fix rx offset * move to end * add fw versions * this won't be fingerprinted on as it returns from Mazda * only log FW versions * add type annotation * fix typing * Skip if FW versions are for read/request-only * Fix crash if no fw versions Fix crash if no fw versions Co-authored-by: Shane Smiskol Co-authored-by: Adeeb Shihadeh --- selfdrive/car/chrysler/values.py | 18 +++++++++++++++++- selfdrive/car/fw_versions.py | 21 ++++++++++++++++++++- selfdrive/car/tests/test_fw_fingerprint.py | 2 ++ 3 files changed, 39 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 40210e68e6..ada4f486fc 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -1,6 +1,7 @@ +import capnp from dataclasses import dataclass from enum import Enum -from typing import Dict, List, Optional, Union +from typing import Dict, List, Optional, Tuple, Union from cereal import car from selfdrive.car import dbc_dict @@ -110,6 +111,21 @@ FINGERPRINTS = { ], } +FW_VERSIONS: Dict[str, Dict[Tuple[capnp.lib.capnp._EnumModule, int, Optional[int]], List[str]]] = { + CAR.RAM_1500: { + (Ecu.combinationMeter, 0x742, None): [], + (Ecu.srs, 0x744, None): [], + (Ecu.esp, 0x747, None): [], + (Ecu.fwdCamera, 0x753, None): [], + (Ecu.fwdCamera, 0x764, None): [], + (Ecu.eps, 0x761, None): [], + (Ecu.fwdRadar, 0x757, None): [], + (Ecu.eps, 0x75A, None): [], + (Ecu.engine, 0x7e0, None): [], + (Ecu.transmission, 0x7e1, None): [], + (Ecu.gateway, 0x18DACBF1, None): [], + } +} DBC = { CAR.PACIFICA_2017_HYBRID: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index c51d120166..04610b96d9 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -92,6 +92,13 @@ SUBARU_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ SUBARU_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) +CHRYSLER_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xf132) +CHRYSLER_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(0xf132) + +CHRYSLER_RX_OFFSET = -0x280 + @dataclass class Request: @@ -188,6 +195,18 @@ REQUESTS: List[Request] = [ [TESTER_PRESENT_RESPONSE, UDS_VERSION_RESPONSE], bus=0, ), + # Chrysler / FCA / Stellantis + Request( + "chrysler", + [CHRYSLER_VERSION_REQUEST], + [CHRYSLER_VERSION_RESPONSE], + rx_offset=CHRYSLER_RX_OFFSET, + ), + Request( + "chrysler", + [CHRYSLER_VERSION_REQUEST], + [CHRYSLER_VERSION_RESPONSE], + ), ] @@ -445,7 +464,7 @@ if __name__ == "__main__": print() print("Found FW versions") print("{") - padding = max([len(fw.brand) for fw in fw_vers]) + padding = max([len(fw.brand) for fw in fw_vers] or [0]) for version in fw_vers: subaddr = None if version.subAddress == 0 else hex(version.subAddress) print(f" Brand: {version.brand:{padding}} - (Ecu.{version.ecu}, {hex(version.address)}, {subaddr}): [{version.fwVersion}]") diff --git a/selfdrive/car/tests/test_fw_fingerprint.py b/selfdrive/car/tests/test_fw_fingerprint.py index 49fa66d36d..cda241c73f 100755 --- a/selfdrive/car/tests/test_fw_fingerprint.py +++ b/selfdrive/car/tests/test_fw_fingerprint.py @@ -27,6 +27,8 @@ class TestFwFingerprint(unittest.TestCase): for _ in range(200): fw = [] for ecu, fw_versions in ecus.items(): + if not len(fw_versions): + raise unittest.SkipTest("Car model has no FW versions") ecu_name, addr, sub_addr = ecu fw.append({"ecu": ecu_name, "fwVersion": random.choice(fw_versions), 'brand': brand, "address": addr, "subAddress": 0 if sub_addr is None else sub_addr}) From c907a0c28aa0958fbc841019eb401a23432ef897 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 8 Jul 2022 14:42:54 -0700 Subject: [PATCH 258/302] add chrysler fw query to release notes --- RELEASES.md | 1 + 1 file changed, 1 insertion(+) diff --git a/RELEASES.md b/RELEASES.md index 7e8f80500e..1e9a1b0423 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -25,6 +25,7 @@ Version 0.8.15 (2022-07-20) * AGNOS 5 * Support VSCode remote SSH target * Support for delta updates to reduce data usage on future OS updates +* Chrysler ECU firmware fingerprinting thanks to realfast! * Honda Civic 2022 support * Hyundai Tucson 2021 support thanks to bluesforte! * Lexus NX Hybrid 2020 support thanks to AlexandreSato! From 76dde007959b633f4140d04e79043c7faef567b9 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Fri, 8 Jul 2022 16:57:50 -0700 Subject: [PATCH 259/302] Update RELEASES.md --- RELEASES.md | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index 1e9a1b0423..588b88827a 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -11,8 +11,9 @@ Version 0.8.15 (2022-07-20) * Used on select Toyota and Hyundai models at first * Significantly improved control on TSS-P Prius * New driver monitoring model - * Takes a larger input frame - * Outputs a driver state for both driver and passenger + * Bigger model, covering full interior view from driver camera + * Works with a wider variety of mounting angles + * 3x more unique comma three training data than previous * Navigation improvements * Speed limits shown while navigating * Faster position fix by using raw GPS measurements From 4c493237d52525d2effb95b5cda96b36a684303c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 8 Jul 2022 19:36:09 -0700 Subject: [PATCH 260/302] Interleave VIN queries (#25090) Interleave the two requests --- selfdrive/car/vin.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/vin.py b/selfdrive/car/vin.py index 7413c3f235..fd1ca61e66 100755 --- a/selfdrive/car/vin.py +++ b/selfdrive/car/vin.py @@ -18,8 +18,8 @@ VIN_UNKNOWN = "0" * 17 def get_vin(logcan, sendcan, bus, timeout=0.1, retry=5, debug=False): - for request, response in ((UDS_VIN_REQUEST, UDS_VIN_RESPONSE), (OBD_VIN_REQUEST, OBD_VIN_RESPONSE)): - for i in range(retry): + for i in range(retry): + for request, response in ((UDS_VIN_REQUEST, UDS_VIN_RESPONSE), (OBD_VIN_REQUEST, OBD_VIN_RESPONSE)): try: query = IsoTpParallelQuery(sendcan, logcan, bus, FUNCTIONAL_ADDRS, [request, ], [response, ], functional_addr=True, debug=debug) for addr, vin in query.get_data(timeout).items(): From 94c8717cac0cfad4603d57a8da108a124019dd73 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Fri, 8 Jul 2022 22:03:21 -0500 Subject: [PATCH 261/302] Add missing HIGHLANDERH_TSS2 ESP & engine f/w (#25066) * Add missing HIGHLANDERH_TSS2 ESP & engine f/w `@pkozlowski#5214` 2022 Highlander Hybrid (Poland) DongleID/route b2e9858e29db492b|2022-07-07--17-57-24 * Fix test_fw_query_on_routes with older routes Co-authored-by: Shane Smiskol --- selfdrive/car/toyota/values.py | 4 +++- selfdrive/debug/test_fw_query_on_routes.py | 5 +++-- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 8149bfd063..2a03999342 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -954,11 +954,13 @@ FW_VERSIONS = { b'\x01F15264873500\x00\x00\x00\x00', b'\x01F152648C6300\x00\x00\x00\x00', b'\x01F152648J4000\x00\x00\x00\x00', + b'\x01F152648J6000\x00\x00\x00\x00', ], (Ecu.engine, 0x700, None): [ + b'\x01896630EE4000\x00\x00\x00\x00', + b'\x01896630EE6000\x00\x00\x00\x00', b'\x01896630E67000\x00\x00\x00\x00', b'\x01896630EA1000\x00\x00\x00\x00', - b'\x01896630EE4000\x00\x00\x00\x00', b'\x01896630EA1000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', b'\x02896630EB3000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', diff --git a/selfdrive/debug/test_fw_query_on_routes.py b/selfdrive/debug/test_fw_query_on_routes.py index 8c8c631c38..9ce0ebb3f5 100755 --- a/selfdrive/debug/test_fw_query_on_routes.py +++ b/selfdrive/debug/test_fw_query_on_routes.py @@ -17,6 +17,7 @@ NO_API = "NO_API" in os.environ VERSIONS = get_interface_attr('FW_VERSIONS', ignore_none=True) SUPPORTED_BRANDS = VERSIONS.keys() SUPPORTED_CARS = [brand for brand in SUPPORTED_BRANDS for brand in interface_names[brand]] +UNKNOWN_BRAND = "unknown" try: from xx.pipeline.c.CarState import migration @@ -126,10 +127,10 @@ if __name__ == "__main__": print("New style (exact):", exact_matches) print("New style (fuzzy):", fuzzy_matches) - padding = max([len(fw.brand) for fw in car_fw]) + padding = max([len(fw.brand or UNKNOWN_BRAND) for fw in car_fw]) for version in sorted(car_fw, key=lambda fw: fw.brand): subaddr = None if version.subAddress == 0 else hex(version.subAddress) - print(f" Brand: {version.brand:{padding}} - (Ecu.{version.ecu}, {hex(version.address)}, {subaddr}): [{version.fwVersion}],") + print(f" Brand: {version.brand or UNKNOWN_BRAND:{padding}} - (Ecu.{version.ecu}, {hex(version.address)}, {subaddr}): [{version.fwVersion}],") print("Mismatches") found = False From 949de4d2b6b293d9f77d83c58212f5dee176cbf1 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 8 Jul 2022 20:25:54 -0700 Subject: [PATCH 262/302] UI: Internationalization support (#21212) * rough multiple language demo * more wrappings * stash * add some bad translations * updates * map from french to spanish still has same problem of needing to call setText on everything * add files * restart UI * use return code * relative path * more translations * don't loop restart * Toggle and prime translations * try on device * try QComboBox with readable style * stash * not yet scrollable * stash * dynamic translations (doesn't work for dynamic widget strings yet) * clean up multiple option selector * store languages in json * try transparent * Try transparent popup * see how this looks * tweaks * clean up * update names * Add Chinese (Simplified) translations * Do missing French translations * unit tests caught that :) * fix test * fix other test (on PC) * add entries to dialog to test * add cancel button, clean up a bit * just chinese * some clean up * use quotes * clean up * Just quit, set timeout to 0 * half a second * use exitcode * don't print if it's expected * this comment is outdated * update translations * Update translations * re-order input classes * Update line numbers * use enabled property for button style * Get rid of ListWidget * Update line numbers * Log failed to load language * Log failed to load language * Move to utils and fix english logging extra line * Update translations * spacing * looks a bit better * try this instead of exitcode fixes fix * only one function * comment * Update line numbers * fixup some japanese translations * clean up multi option dialog * Update line numbers --- common/params.cc | 1 + common/watchdog.cc | 5 +- common/watchdog.h | 4 +- selfdrive/ui/main.cc | 9 ++ selfdrive/ui/qt/offroad/settings.cc | 14 ++ selfdrive/ui/qt/util.cc | 16 +++ selfdrive/ui/qt/util.h | 1 + selfdrive/ui/qt/widgets/input.cc | 86 ++++++++++++ selfdrive/ui/qt/widgets/input.h | 9 ++ selfdrive/ui/tests/test_translations.cc | 1 + selfdrive/ui/translations/main_ja.ts | 6 +- selfdrive/ui/translations/main_ko.qm | Bin 19159 -> 19449 bytes selfdrive/ui/translations/main_ko.ts | 167 ++++++++++++----------- selfdrive/ui/translations/main_zh-CHS.qm | Bin 17629 -> 17919 bytes selfdrive/ui/translations/main_zh-CHS.ts | 167 ++++++++++++----------- selfdrive/ui/translations/main_zh-CHT.qm | Bin 17741 -> 18031 bytes selfdrive/ui/translations/main_zh-CHT.ts | 167 ++++++++++++----------- selfdrive/ui/ui.cc | 2 +- selfdrive/ui/update_translations.py | 2 +- 19 files changed, 404 insertions(+), 253 deletions(-) diff --git a/common/params.cc b/common/params.cc index f93c87cd98..c4f65a9e02 100644 --- a/common/params.cc +++ b/common/params.cc @@ -129,6 +129,7 @@ std::unordered_map keys = { {"IsUpdateAvailable", CLEAR_ON_MANAGER_START}, {"JoystickDebugMode", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF}, {"LaikadEphemeris", PERSISTENT | DONT_LOG}, + {"LanguageSetting", PERSISTENT}, {"LastAthenaPingTime", CLEAR_ON_MANAGER_START}, {"LastGPSPosition", PERSISTENT}, {"LastManagerExitReason", CLEAR_ON_MANAGER_START}, diff --git a/common/watchdog.cc b/common/watchdog.cc index 5a10207828..920df4030a 100644 --- a/common/watchdog.cc +++ b/common/watchdog.cc @@ -1,12 +1,9 @@ #include "common/watchdog.h" -#include "common/timing.h" #include "common/util.h" const std::string watchdog_fn_prefix = "/dev/shm/wd_"; // + -bool watchdog_kick() { +bool watchdog_kick(uint64_t ts) { static std::string fn = watchdog_fn_prefix + std::to_string(getpid()); - - uint64_t ts = nanos_since_boot(); return util::write_file(fn.c_str(), &ts, sizeof(ts), O_WRONLY | O_CREAT) > 0; } diff --git a/common/watchdog.h b/common/watchdog.h index 7ed23aa0d9..12dd2ca035 100644 --- a/common/watchdog.h +++ b/common/watchdog.h @@ -1,3 +1,5 @@ #pragma once -bool watchdog_kick(); +#include + +bool watchdog_kick(uint64_t ts); diff --git a/selfdrive/ui/main.cc b/selfdrive/ui/main.cc index 1eecd78b19..ed54d5aa19 100644 --- a/selfdrive/ui/main.cc +++ b/selfdrive/ui/main.cc @@ -1,6 +1,7 @@ #include #include +#include #include "system/hardware/hw.h" #include "selfdrive/ui/qt/qt_window.h" @@ -13,7 +14,15 @@ int main(int argc, char *argv[]) { qInstallMessageHandler(swagLogMessageHandler); initApp(argc, argv); + QTranslator translator; + QString translation_file = QString::fromStdString(Params().get("LanguageSetting")); + if (!translator.load(translation_file, "translations") && translation_file.length()) { + qCritical() << "Failed to load translation file:" << translation_file; + } + QApplication a(argc, argv); + a.installTranslator(&translator); + MainWindow w; setMainWindow(&w); a.installEventFilter(&w); diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index a03af23951..6bcdd55b0a 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -13,6 +13,7 @@ #endif #include "common/params.h" +#include "common/watchdog.h" #include "common/util.h" #include "system/hardware/hw.h" #include "selfdrive/ui/qt/widgets/controls.h" @@ -133,6 +134,19 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { addItem(regulatoryBtn); } + auto translateBtn = new ButtonControl(tr("Change Language"), tr("CHANGE"), ""); + connect(translateBtn, &ButtonControl::clicked, [=]() { + QMap langs = getSupportedLanguages(); + QString selection = MultiOptionDialog::getSelection(tr("Select a language"), langs.keys(), this); + if (!selection.isEmpty()) { + // put language setting, exit Qt UI, and trigger fast restart + Params().put("LanguageSetting", langs[selection].toStdString()); + qApp->exit(18); + watchdog_kick(0); + } + }); + addItem(translateBtn); + QObject::connect(uiState(), &UIState::offroadTransition, [=](bool offroad) { for (auto btn : findChildren()) { btn->setEnabled(offroad); diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc index cab7299cd6..a7d5438ae4 100644 --- a/selfdrive/ui/qt/util.cc +++ b/selfdrive/ui/qt/util.cc @@ -1,6 +1,9 @@ #include "selfdrive/ui/qt/util.h" #include +#include +#include +#include #include #include #include @@ -36,6 +39,19 @@ std::optional getDongleId() { } } +QMap getSupportedLanguages() { + QFile f("translations/languages.json"); + f.open(QIODevice::ReadOnly | QIODevice::Text); + QString val = f.readAll(); + + QJsonObject obj = QJsonDocument::fromJson(val.toUtf8()).object(); + QMap map; + for (auto key : obj.keys()) { + map[key] = obj[key].toString(); + } + return map; +} + void configFont(QPainter &p, const QString &family, int size, const QString &style) { QFont f(family); f.setPixelSize(size); diff --git a/selfdrive/ui/qt/util.h b/selfdrive/ui/qt/util.h index 9491c6798e..f0e57526c8 100644 --- a/selfdrive/ui/qt/util.h +++ b/selfdrive/ui/qt/util.h @@ -14,6 +14,7 @@ QString getBrand(); QString getBrandVersion(); QString getUserAgent(); std::optional getDongleId(); +QMap getSupportedLanguages(); void configFont(QPainter &p, const QString &family, int size, const QString &style); void clearLayout(QLayout* layout); void setQtSurfaceFormat(); diff --git a/selfdrive/ui/qt/widgets/input.cc b/selfdrive/ui/qt/widgets/input.cc index 755ccfe8c5..a130a8e935 100644 --- a/selfdrive/ui/qt/widgets/input.cc +++ b/selfdrive/ui/qt/widgets/input.cc @@ -1,6 +1,7 @@ #include "selfdrive/ui/qt/widgets/input.h" #include +#include #include "system/hardware/hw.h" #include "selfdrive/ui/qt/util.h" @@ -257,3 +258,88 @@ bool RichTextDialog::alert(const QString &prompt_text, QWidget *parent) { auto d = RichTextDialog(prompt_text, tr("Ok"), parent); return d.exec(); } + +// MultiOptionDialog + +MultiOptionDialog::MultiOptionDialog(const QString &prompt_text, QStringList l, QWidget *parent) : QDialogBase(parent) { + QFrame *container = new QFrame(this); + container->setStyleSheet(R"( + QFrame { background-color: #1B1B1B; } + #confirm_btn[enabled="false"] { background-color: #2B2B2B; } + #confirm_btn:enabled { background-color: #465BEA; } + #confirm_btn:enabled:pressed { background-color: #3049F4; } + )"); + + QVBoxLayout *main_layout = new QVBoxLayout(container); + main_layout->setContentsMargins(55, 50, 55, 50); + + QLabel *title = new QLabel(prompt_text, this); + title->setStyleSheet("font-size: 70px; font-weight: 500;"); + main_layout->addWidget(title, 0, Qt::AlignLeft | Qt::AlignTop); + main_layout->addSpacing(25); + + QWidget *listWidget = new QWidget(this); + QVBoxLayout *listLayout = new QVBoxLayout(listWidget); + listLayout->setSpacing(20); + listWidget->setStyleSheet(R"( + QPushButton { + height: 135; + padding: 0px 50px; + text-align: left; + font-size: 55px; + font-weight: 300; + border-radius: 10px; + background-color: #4F4F4F; + } + QPushButton:checked { background-color: #465BEA; } + )"); + + QButtonGroup *group = new QButtonGroup(listWidget); + group->setExclusive(true); + + QPushButton *confirm_btn = new QPushButton(tr("Select")); + confirm_btn->setObjectName("confirm_btn"); + confirm_btn->setEnabled(false); + + for (QString &s : l) { + QPushButton *selectionLabel = new QPushButton(s); + selectionLabel->setCheckable(true); + QObject::connect(selectionLabel, &QPushButton::toggled, [=](bool checked) { + if (checked) selection = s; + confirm_btn->setEnabled(true); + }); + + group->addButton(selectionLabel); + listLayout->addWidget(selectionLabel); + } + + ScrollView *scroll_view = new ScrollView(listWidget, this); + scroll_view->setVerticalScrollBarPolicy(Qt::ScrollBarAsNeeded); + + main_layout->addWidget(scroll_view); + main_layout->addStretch(1); + main_layout->addSpacing(35); + + // cancel + confirm buttons + QHBoxLayout *blayout = new QHBoxLayout; + main_layout->addLayout(blayout); + blayout->setSpacing(50); + + QPushButton *cancel_btn = new QPushButton(tr("Cancel")); + QObject::connect(cancel_btn, &QPushButton::clicked, this, &ConfirmationDialog::reject); + QObject::connect(confirm_btn, &QPushButton::clicked, this, &ConfirmationDialog::accept); + blayout->addWidget(cancel_btn); + blayout->addWidget(confirm_btn); + + QVBoxLayout *outer_layout = new QVBoxLayout(this); + outer_layout->setContentsMargins(50, 50, 50, 50); + outer_layout->addWidget(container); +} + +QString MultiOptionDialog::getSelection(const QString &prompt_text, const QStringList l, QWidget *parent) { + MultiOptionDialog d = MultiOptionDialog(prompt_text, l, parent); + if (d.exec()) { + return d.selection; + } + return ""; +} diff --git a/selfdrive/ui/qt/widgets/input.h b/selfdrive/ui/qt/widgets/input.h index f81211d0ee..47d8b74efd 100644 --- a/selfdrive/ui/qt/widgets/input.h +++ b/selfdrive/ui/qt/widgets/input.h @@ -68,3 +68,12 @@ public: explicit RichTextDialog(const QString &prompt_text, const QString &btn_text, QWidget* parent); static bool alert(const QString &prompt_text, QWidget *parent); }; + +class MultiOptionDialog : public QDialogBase { + Q_OBJECT + +public: + explicit MultiOptionDialog(const QString &prompt_text, const QStringList l, QWidget *parent); + static QString getSelection(const QString &prompt_text, const QStringList l, QWidget *parent); + QString selection; +}; diff --git a/selfdrive/ui/tests/test_translations.cc b/selfdrive/ui/tests/test_translations.cc index fecb9da44a..ba0612b4c0 100644 --- a/selfdrive/ui/tests/test_translations.cc +++ b/selfdrive/ui/tests/test_translations.cc @@ -41,6 +41,7 @@ void checkWidgetTrWrap(MainWindow &w) { // Tests all strings in the UI are wrapped with tr() TEST_CASE("UI: test all strings wrapped") { + Params().remove("LanguageSetting"); Params().remove("HardwareSerial"); Params().remove("DongleId"); qputenv("TICI", "1"); diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index fbb654bc4c..5c0f54a314 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -528,12 +528,12 @@ location set ✓ SUBSCRIBED - ✓ 購読 + ✓ 購読しました comma prime - コンマプライム + comma prime @@ -543,7 +543,7 @@ location set COMMA POINTS - コンマポイント + COMMA POINTS diff --git a/selfdrive/ui/translations/main_ko.qm b/selfdrive/ui/translations/main_ko.qm index 62ddb3be2b89c6c73e82458ae86c02825c925de5..f6e95b5038f984183d9d4273c581bb6ef6e4b91d 100644 GIT binary patch delta 1948 zcmZWqX;4#F7(ID;FE4p{c>!6pwrB`JMJwQ1tf2}B3RVzBbX-~&FhVJ63$?BpS6px# zT(F{b0d4En0k=}LF1X_pwkRM?;;ivrxA}5*Awdik?Yp+fD{IFmWaKHLx`goljp&pR{{ALpp^sa z8NiVU#4Z53_5l(W1Fv%Y=1?MYCU*ghvx$=cx8FnlSjYt)l*0-CNzgChA#xbRyo~^U z_Mm>h2OYT{jJ^u7umRB7AXawg{`VnXJWQ;Bcv%G6218nEBhkl@_Ut67`7j*(mbeSD zZ3NGG19GQoxS?J{xV0KE=c9ksOdzxZ{qG+Ddgft(iMRGHMnccEB*KeKi{=3#NXjap zBCliccO>9<1Vd*3#`qgZ5l(VG4=Lm4^57z*?konBSd55Y!vnoB@{?IWOc=%-ui`nc zUykTsk$E4C7%xA{4?E0*E!#NpYBqM$h--X1%%WI!FTF` zZnK0q#hpWDD}~Wsym8lbVNZo8Cfg6>A<=CDd*4 zW5T8SfJZDN}5m$@5FRulHhKc*%DW3^uRVZ1OO{J1aQj8YNi{wZn#@8&qkry)Vkfu-kknv}vncX!u!Fp-gIucPfd$4W12W<;I7_(R^>Qqb*`tFvBR?-`4 zvQ)fiA(gl1h)QhQ}F% zz!ZAybA$Fc6tL|wI3L7O!HI_crAL5Br(u+il?c9W*xvY@3NJELgl?b*O-94hr0evY zOSXqlvXH@YN$dHvz(9Fl_H7c#lphb-MhR!jPj0>hv{2X{l+Zpdz=C-80k_ z^^1!eZkvV;Y#`%uQ|f$5*zbaA)M!fH-eF2R&F%}an^vGDO;Tp6u1TcVZkcMmCj*86 zC8`tOCqurHcI6^(K2}-sAb`)nRAMC1ZjrL=o|WTolr_&;>UIZ|!iw#HZ!e|DeRCMi z>!WPG$l8m6%AUn*DB%O8JX|8Ny~+s}H%ggGrP79`y{c6DJ4vWcxj!L?5~i4S2j?(8 z)f{x}6bTJ7kE!SL;INseUK2@poq6sDzEsd+KK+O#>X2bRJBUj8-co&!@!YVMsynch z3+*1Mog=5yEa%j?7}mP)bTuJj4B-4)9T-goB4?tM_tBf z1M{hvPntG0I+iAGr7hXWw(rgGb${5|W2^lU2BX#Hx+UqGMd z*4q1<*$wlob#Z$+PRih)PRp`#gGu%iD~|0xLSxYq&7YV7QHlLy3#O=kcH^nTr}n?F zYK@sRF58uEdz0U}<6P;@VPz*RrK01X*yFYgC~K^h5yHwZEWof{~HSV10MhY delta 1717 zcmX9;eOQfW9KO#v?|VMp^MyW)9O+buR6=QmIw`^=sv&JgG?|PmOEWtxMoP2M@=<9j z+00xkADanSscg+R=3K;4h{F<^Ck%#Zc_!9;1?a7u-+VHbcWc2pd)qx&j5hTVj) zy#%Ru-*RHS_Xcoo6s5Dl0fqjl2?1|BbS4)O*(qGj(Cc>sf)WTSG~qTyAtm~&o$ zr%bl<2KV1REV~>lFz_^4y}ShIH&@m%Vja+TkX%YW3k+_Pd$u+M{$I%>r8E-Dlh5g~ zfE5p4EHA9n@WMX%(Ht`Ke<81m$_09u<=0~v*c2vjtYNQxuE?8;ofvS7!gOEc`8Nu4 z_Bd9wSg|680Y~pp>^G3G_b^4pk!ifYO>wM(=lz~+T`hODMhSDvE1CARuqcY6_P8o! zG>-)a^bs}){{n&C!uF`+bX2?@ja7DZwFm{Jub4ei*wd0k%ol#Xk_VU*ghPut3w|gbJl{m8`F$r=cTrDynRv$S8erTcHZ+om`H6TZvxW^Wv13@L z__~Y4e5WYoZn1RE5vAdg58(Q%GNdDt6^Y6T6(@iYi!wn*eLWhKC9k@vWRCK<&khnU zSH6zEK_e|unZ2mg;CNM8-%L8qKSp&h^$rQ7s2)w!OTFMhCkeZ#H?P~S@}XKtHZ?MPA86`<#VL$yGE}6k+yZS$DV&k+mDx!&~B-q zK8}v;BNf%M=YpGbVBEqXGv&=HnEvQ?>6K+39CE$h*L0HwMC*gPvN)4h^an=r zzuQ{<(R5<4PH!{sr5DolHVbi(#j3v;LNiFW3{F3maii1FcLOW#m1Qu$3I_su8%8(r zmGPTzn4Ck&dR;VR?cxx71sMwOhO(FKhM!6qIAF5j#0&P`<(}bk=vBbEpHcmo&z|bG z(J_qU8yIYKZtDg{q#7r-FphsuV`_3M74eBMZmD0-UN1N9SddC0`Nor ConfirmationDialog - - + + Ok 확인 - + Cancel 취소 @@ -108,149 +108,152 @@ DevicePanel - + Dongle ID Dongle ID - + N/A N/A - + Serial Serial - + Driver Camera 운전자 카메라 - + PREVIEW 미리보기 - + Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off) 운전자 카메라를 미리 보면서 최적의 운전자 모니터링 경험을 위해 기기 장착 위치를 최적화할수 있습니다. (차량은 반드시 닫아야 합니다) - + Reset Calibration 캘리브레이션 재설정 - + RESET 재설정 - + Are you sure you want to reset calibration? 캘리브레이션을 재설정하시겠습니까? - + Review Training Guide 트레이닝 가이드 다시보기 - + REVIEW 다시보기 - + Review the rules, features, and limitations of openpilot openpilot의 규칙, 기능, 제한 다시보기 - + Are you sure you want to review the training guide? 트레이닝 가이드를 다시보시겠습니까? - + Regulatory 규제 - + VIEW 보기 + Change Language - 언어변경 + 언어변경 + CHANGE - 변경 + 변경 + Select a language - 언어선택 + 언어선택 - + Reboot 재부팅 - + Power Off 전원 종료 - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot은 장치를 왼쪽 또는 오른쪽 4° 이내, 위쪽 5° 또는 아래쪽 8° 이내로 설치해야 합니다. openpilot은 지속적으로 보정되므로 리셋이 거의 필요하지 않습니다. - + Your device is pointed %1° %2 and %3° %4. 사용자의 기기가 %1° %2 및 %3° %4를 가리키고 있습니다. - + down 아래 - + up - + left 왼쪽 - + right 오른쪽 - + Are you sure you want to reboot? 재부팅 하시겠습니까? - + Disengage to Reboot 재부팅 하려면 해제하세요 - + Are you sure you want to power off? 전원을 종료하시겠습니까? - + Disengage to Power Off 전원을 종료하려면 해제하세요 @@ -299,17 +302,17 @@ InputDialog - + Cancel 취소 - + Need at least 최소 필요 - + characters! 문자! @@ -389,12 +392,14 @@ location set MultiOptionDialog + Select - 선택 + 선택 + Cancel - 취소 + 취소 @@ -564,27 +569,27 @@ location set 종료 - + dashcam dashcam - + openpilot openpilot - + %1 minute%2 ago %1 분%2 전 - + %1 hour%2 ago %1 시간%2 전 - + %1 day%2 ago %1 일%2 전 @@ -640,7 +645,7 @@ location set RichTextDialog - + Ok 확인 @@ -648,33 +653,33 @@ location set SettingsWindow - + × × - + Device 장치 - - + + Network 네트워크 - + Toggles 토글 - + Software 소프트웨어 - + Navigation 네비게이션 @@ -913,68 +918,68 @@ location set SoftwarePanel - + Git Branch Git 브렌치 - + Git Commit Git 커밋 - + OS Version OS 버전 - + Version 버전 - + Last Update Check 최신 업데이트 검사 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. 이전에 openpilot에서 업데이트를 성공적으로 확인한 시간입니다. 업데이트 프로그램은 차량 연결이 해제되었을때만 작동합니다. - + Check for Update 업데이트 확인 - + CHECKING 검사중 - + Uninstall 삭제 - + UNINSTALL 삭제 - + Are you sure you want to uninstall? 삭제하시겠습니까? - + failed to fetch update 업데이트를 가져올수없습니다 - - + + CHECK 확인 @@ -1062,82 +1067,82 @@ location set TogglesPanel - + Enable openpilot openpilot 사용 - + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. 어댑티브 크루즈 컨트롤 및 차선 유지 운전자 보조를 위해 openpilot 시스템을 사용하십시오. 이 기능을 사용하려면 항상 주의를 기울여야 합니다. 이 설정을 변경하면 차량 전원이 꺼질 때 적용됩니다. - + Enable Lane Departure Warnings 차선 이탈 경고 사용 - + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). 차량이 50km/h(31mph) 이상의 속도로 주행하는 동안 방향 지시등이 활성화되지 않은 상태에서 감지된 차선 위를 주행할 경우 차선이탈 경고를 사용합니다. - + Enable Right-Hand Drive 우측핸들 사용 - + Allow openpilot to obey left-hand traffic conventions and perform driver monitoring on right driver seat. openpilot이 좌측 교통 규칙을 준수하고 우측 운전석에서 운전자 모니터링을 수행합니다. - + Use Metric System 미터법 사용 - + Display speed in km/h instead of mph. mph가 아닌 km/h로 속도 표시. - + Record and Upload Driver Camera 운전자 카메라 기록 및 업로드 - + Upload data from the driver facing camera and help improve the driver monitoring algorithm. 운전자 카메라에서 데이터를 업로드하고 운전자 모니터링 알고리즘을 개선합니다. - + Disengage On Accelerator Pedal 가속페달 조작시 해제 - + When enabled, pressing the accelerator pedal will disengage openpilot. 활성화된 경우 가속 페달을 누르면 openpilot이 해제됩니다. - + Show ETA in 24h format 24시간 형식으로 ETA 표시 - + Use 24h format instead of am/pm 오전/오후 대신 24시간 형식 사용 - + openpilot Longitudinal Control openpilot Longitudinal Control - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot은 차량'의 레이더를 무력화시키고 가속페달과 브레이크의 제어를 인계받을 것이다. 경고: AEB를 비활성화합니다! diff --git a/selfdrive/ui/translations/main_zh-CHS.qm b/selfdrive/ui/translations/main_zh-CHS.qm index be6c51030617f25c54c086e107274a1b0434ea5c..19eccddbc0e919fdadb32a5621f8f7474aded85a 100644 GIT binary patch delta 1961 zcmZWpe^gXu8h&Q(ueo>b+$#ibB4fkw!w3XTP)yK-Km?UEG*@y96ekEV&lxn2+N>cd zQfeui8k#BQYMCee(dsdma>UU5(P}5ovXqgEbTUoX4@E|WgglvRR zEdlcT5Ldnnpf!NPiU3Bu8Nk$EA#S`3STu#9f3B_T3n2UIa8R#y2kk;!-jG+Ckv);mB5tfPUe~8Bt3j zEM!qS4?2jvvh}RA5l{a>0uSB6)Mfu>d?oU&#{t8E{G#PNI0n;q)dOlSW=z)jxI=^X9mHOwf#1dYHg55bvKl3yeuZgZEFs;C}Ewl*dXoQ<`G=y~DEk8-5>g+j2HvWZpkpTC6*Of$^5k;VXav z(N@iK0*LWiqp!3BiQBAMn$JsS$F0xxW5o$8ty?at+)!lw^bI#K)Mh<4VGUp=Suads z;(^z#ZO!a?e1`SXwooQqB{+X(s|Fqt+%;oaQHM}5h53?A;X{LjV-E@qho0vC4}>EP zj8AY1{=u)(Z>NNF!FSoZg+iCFVkd=-6*D_O0fI-1FYMY+LN~;c3H)rfi;LUG0E2dk zON&TQUL>v*Zv#n7#f=k=(tI%iH2x95;Kl$t+r_&2F1GT5xc%}R61IyUovQ_0%ftgO z)l=b8@vzQTIci1U>8q_=XcbTY^b32PEw+z604TF0Z3J5|`l{rpSwKnOlQN8G^6Zsn zyucPE^^-i>F`DUXsWgfOBcnF*3u;QVN(6;RX}LCwD064V8}7)i=HS-S0x>f_?jl$Dz&ze zP=qS|SlP_pR|haHRO;>_!T2MxH6ov8J1-kI5~yIFoZ6X11zY6t4W9uiGvxvcTjKV8 zF7N2-1s(~Jk0xvaY&mjw-ZwN!o8pe8WHC^7hE=k{dCI=>A4y=Ma%1XtO1M_J(=vdH zy{6p#i3$lHDfdQq0AY7+8L@s&$r@XZK;mYJt@!#q5>B?gS+SYxRkrs&WWHdF?ckM2 z&VN{rsyLpf%Ll8Gbv9tw19jXj4>uI5({e9U%5ZghB_$lwq82)M?2XIQzcRd+f8X9O{g`%AT&4wLUy+J@c( zod3vLZR61$WVB4HYnjHL)oNSMu=m2R+TK+gc(9-y87gtUXKG(~xKXlder*uldsy@L zPvsbH)~?N_>jz!6TMoTS$rsuq8&A+9r|q-ac~3;7*cV(7spJ#(3gIBt_3(ZGesCVfcSVw&YEJu8E~e&T_ilQIh!*{$cMQ-PEX`t({R zbWYaiP3|M~NBy1dXSv^_H@w9$41Zp4-bTfS+|<8nCC0y|w>FWO__{;h8O8G^ITD@U zlE^5>s2*Q6=lHl|ZxRC@Ip_Fv5piU;!|(opUT`}6>BOj8j#H`hf;QX;-My2{cN<|V zS#i*E!`+oZWeyuDmv}J^S!?9JLB)a^jRonMjPEk4-{t(r>^8P^Jjs^cH}=#s|Kqof z&wir^!WxaU1y7!*%d)d}tULuEzQRX`A9 z4qnGNRltxDyyp+Zhw$uFB7Zh#EB~zK1`{Q7!FdnFwV41a?5JO5N6&3`40{W4XDy(U zA(nLKJqhBiUx;xK%SE7VC8YJ9fPV_4yhDI|35HXTh>b9Mj$-_IFb3QQ95i&%?!yMz z83W6f0G*;Ru;C;S5{g0QiGa2OgL|fv2n$GwVg=_gbmlfH;fG<5Nx zu5f)m5+*KZ;y{c%lmnQaVpPm_CXB`CpOymQi5PdOjQf`{YZ8lgD#ya+S2oJE9Q&@{ z1|s^PAbC9C=ZX^Np{yhub?X;!|BlWzG!XEL)wSN^19;!i_1MG~1=Z@}ODU(U70^0Bkdv+gzKaFlx@sW!pfEsACb2SMY>UaPIB27= z`@WeMrV6JwkXdI{xDc}mP&0&k@eJ(tQm8CruLEL)s_d2wxJmEvOyYWx-kR2r6+PE4 zh-bj=E%irK67G0TUvP^4(G>mJ0-g`@-nL9=XLH;qPB>J^ysyP+F;rC>BrdA%3wY#- zYsHs9w-w^fm?B!r&yH$uJGwWBSvgH?(4XS|+DWA0C>||O2imU`Pt3@nZga#l3LBt& z5N|xG;QC|n#?!wT|Cm_a?*w4@D9Js?v(tT^NtU#^6e?GWR(;7^ltxXU@ZDUcB>4g@ z(My`{lS_e|r0JinV|FIK1&mvzMN<~?e7v-zyGn1Ll+u1A5p$#+-F0^K2(e@MaVcvv zJ1*~#a@MQ{T&z<5wJLTxutd7tOhJX!(iN|}6j+ohDoMmslWJC$v6Gwa7~WQT-%Mfw z#RkDEf!6umpuPyEQi+D}#sRD-#W1koJkV=`VT_IfdtEaeX!-=Sb2AhL?;_zw!~3BR z*zp>p)t^fF8jQJaww0`GzA=Ax4G9b}z8Jor(xn?;KWsy(8jNqBQW^bGZn1JjPHpr6+&d5>0P7q%tzP4In!NoJdu+{=cNQHWp&B{sVIo_V zDet*8o(26Q=dIh$yk^;Uwu?k&6XeTDyeJ8BiQJCQ$QilBHJpU9<%VyQndq5=?$i&I ze5r$X@l|@`uEV%$PQ7Pehq?DeO4;9G`S&io_u8TK8C&Gj-r?6Tsg#qS;!@1So%SkT z1zfk@RDvQF(IYdI0nu!AAIYW+?mdn@gAyA>1$t#DBhwksJwcfj_nFYw%8vJZOgqg| z3bt~n+D=x=vZ+|$8|7vNF<_liQA%Rs8jB&xzXe~0cKqM82YyJrm1Tp~HX zU2kcwPd@P#S*#7JWt`wJZFW)}zpWA4mWQj^>nYl<$+Jmhmv(W^M ConfirmationDialog - - + + Ok 好的 - + Cancel 取消 @@ -108,149 +108,152 @@ DevicePanel - + Dongle ID 加密狗 ID - + N/A 不适用 - + Serial 串行 - + Driver Camera 司机摄像头 - + PREVIEW 预习 - + Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off) 预览面向驾驶员的摄像头,以帮助优化设备安装位置以获得最佳驾驶员监控体验。 (车辆必须关闭) - + Reset Calibration 重置校准 - + RESET 重置 - + Are you sure you want to reset calibration? 您确定要重置校准吗? - + Review Training Guide 查看培训指南 - + REVIEW 重新查看 - + Review the rules, features, and limitations of openpilot 查看 openpilot 的规则、功能和限制 - + Are you sure you want to review the training guide? 您确定要查看培训指南吗? - + Regulatory 监管 - + VIEW 查看 + Change Language - 切换语言 + 切换语言 + CHANGE - 切换 + 切换 + Select a language - 选择语言 + 选择语言 - + Reboot 重启 - + Power Off 关机 - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot 要求设备安装在左或右 4° 以内,上 5° 或下 8° 以内。 openpilot 会持续校准,很少需要重置。 - + Your device is pointed %1° %2 and %3° %4. 您的设备指向 %1° %2 和 %3° %4。 - + down - + up 向上 - + left 向左 - + right 向右 - + Are you sure you want to reboot? 您确定要重新启动吗? - + Disengage to Reboot 脱离以重新启动 - + Are you sure you want to power off? 您确定要关闭电源吗? - + Disengage to Power Off 脱离以关闭电源 @@ -299,17 +302,17 @@ InputDialog - + Cancel 取消 - + Need at least 需要至少 - + characters! 字符! @@ -389,12 +392,14 @@ location set MultiOptionDialog + Select - 选择 + 选择 + Cancel - 取消 + 取消 @@ -564,27 +569,27 @@ location set 退出 - + dashcam 行车记录器 - + openpilot openpilot - + %1 minute%2 ago %1 分钟%2 前 - + %1 hour%2 ago %1 小时%2 前 - + %1 day%2 ago %1 天%2 前 @@ -640,7 +645,7 @@ location set RichTextDialog - + Ok 好的 @@ -648,33 +653,33 @@ location set SettingsWindow - + × × - + Device 设备 - - + + Network 网络 - + Toggles 切换 - + Software 软件 - + Navigation 导航 @@ -913,68 +918,68 @@ location set SoftwarePanel - + Git Branch Git 分支 - + Git Commit Git 提交 - + OS Version 操作系统版本 - + Version 版本 - + Last Update Check 最后更新检查 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. 上次 openpilot 成功检查更新的时间。 更新程序仅在汽车关闭时运行。 - + Check for Update 检查更新 - + CHECKING 正在检查 - + Uninstall 卸载 - + UNINSTALL 卸载 - + Are you sure you want to uninstall? 您确定要卸载吗? - + failed to fetch update 未能获取更新 - - + + CHECK 查看 @@ -1062,82 +1067,82 @@ location set TogglesPanel - + Enable openpilot 启用 openpilot - + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. 使用 openpilot 系统进行自适应巡航控制和车道保持驾驶员辅助。 任何时候都需要您注意使用此功能。 更改此设置在汽车断电时生效。 - + Enable Lane Departure Warnings 启用车道偏离警告 - + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). 当您的车辆在以超过 31 英里/小时(50 公里/小时)的速度行驶时在检测到的车道线上漂移而没有激活转向信号时,接收提醒以返回车道。 - + Enable Right-Hand Drive 启用右舵模式 - + Allow openpilot to obey left-hand traffic conventions and perform driver monitoring on right driver seat. 允许 openpilot 遵守左侧交通惯例并在右侧驾驶座上执行驾驶员监控。 - + Use Metric System 使用公制 - + Display speed in km/h instead of mph. 以公里/小时而不是英里/小时显示速度。 - + Record and Upload Driver Camera 记录和上传司机摄像头 - + Upload data from the driver facing camera and help improve the driver monitoring algorithm. 从面向驾驶员的摄像头上传数据,帮助改进驾驶员监控算法。 - + Disengage On Accelerator Pedal 踩油门解除 - + When enabled, pressing the accelerator pedal will disengage openpilot. 启用后,踩下油门踏板将解除 openpilot。 - + Show ETA in 24h format 以 24 小时格式显示 ETA - + Use 24h format instead of am/pm 使用 24 小时制代替上午/下午 - + openpilot Longitudinal Control openpilot 纵向控制 - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot 将禁用汽车的雷达并接管油门和刹车的控制。 警告:这会禁用 AEB! diff --git a/selfdrive/ui/translations/main_zh-CHT.qm b/selfdrive/ui/translations/main_zh-CHT.qm index 8b055d665e4582f8d1461595d0d88a7eeacfbb49..e64aabecd68c5df555b350ade44bd61fb2ea5cd9 100644 GIT binary patch delta 1961 zcmZWpdr(w$6#jPaz5BR(_bzXhKzS^_fQ1qjAEzkBcRob&t6Io~;rMVfmh zn)P0e(}1=M=${1$cH&xMK5-B6Jz@hO@?0GVND;t*Ys3-2z)0dO+PvVxfKotz3@{e~ z$|)dlA24neVA~2zTtmNT;OVKvbyec6SN`P)Z#MK`F zXmO!X;=;g7E{u5r;^ymsMuq5%qW`lH8$TzOK|Ch{{{E1P0!XwG(%zkb>22t0ejt7U zeZWlKvj+Omi*Uen1(BAEfc!BM>&Y&3BNE#W0#Ch$@y5A;+Z;?BvWY~PNPZkI@I+G9 z23ACi@Auk} z8&~P~y*5F1#cNyY+4Hb1 z+SW2}2CNnQ@3K{X5Q2(FGou(GFNN_2=Lox15+0}*Dr=JI-!2@gq`mDq!P)P1>g~L6 z&f^cZZkf>G$lJlfhKl2E9RNIX#20r~0p60BIf0+utm4wEqk!JOi?7ZlL0y5kTKo-& z`a#@0;V{K#bD_n@g&q%G*gH%tt>_@p0pj-S>BKZ~&$&%Nz)7+Cd1tXIsb8!wZcok^D{zC?Y{0G6!peEkmJmCSILet-5g5=hqHo3fpOAL)N@>cxuH>i@XS3JEp( zMSB4LFGoHs#!@(QDoPXapje0Ye zh@Zn4Tx#GL#T#RPwbP;8IDOJ}wj$CvV9(=HcM_DV@$8(81@}*T#FtQ$%n>^ z&66p*L&g^OMO;Q-%CVtbR61Wd{d^-cPnHXB`Ewt2FiSL+oJFL8Kg*n3iI}(X859@Li zvL}LhZxjszdYC`UCk`z$JA*!^7GllLIATbgxnU%=AZMuFyLK=Wlj^&g8M_};gF51Y zL1s0&m5V9-j5?`=6?1>6=ERMoh;3@&2b}+Yp6b?{W2l8O>ZcWqKPXW>@{k&M0_xdW zW6o3Mvn_^SxH9!M7Oz;&byP2lPupWIplZwb>kJr?W68GPVDDB~);ATf=L;-bGO|f1 z%yM+`U%>DVOH2DUCh)7JHDMp$Q!^=;x2g{53U%J%{0AAsC@e~%`xiexc5>pl4Q`5e zkfHmeXj>8fJ+;IyNXxco1U$|Eyfk|T&3vlHniEBoRwrsuK5g`VIGkd&apxlb4m7nY1`Jb5Zu#%(SdUc8x#+Vt1f_FVwk$=y~ve`zr5V H(P4iBk~aPp delta 1718 zcmX9;X;4#F7(ID;?j9}Z(DM;-5D*+qOy`*?F7(?A7%BntbN(&? z{wILptAMb5K++oC8w`wopSThj-tG0} z<9ayySnJ?`IvgXamjb=EVZ_6eK;Jx!RHgw|Cz7H!kq8sWCCQ#$Fm}!cDlr4&ej@=7 zA52*Og6C_IB3$79Nu*3;cEKx~9A@X#_KrV5!qR`VSj=4ROd_dl?> z{e^>aRpaZ+*MQhVD9xD+^jHC>$5_DU30evlF|eo3YhWl4uu0c>R}c{7qwBYh7KPh% z<1YpSw*Ie=-woBZ)xJaCLux1A+cYD zj1Jk%IILROS*P$qsc^cO%z7sY=MvWe+FhY`JOleA3JultI%K!dxThlnI`zI!B<{<4 zThS0^6t7=2o&lqB^+z=l4z}n^PmQC3WAx>vJRde?!*ZdU!|k>>^=Nqs zi};=StpP*CEBEVJdcoqA$4?pmvDh@^1Yq!%)ac1{dQhrlDOv#ZYn9@)?&O&!rA?*q zk+USbdX6PATbdQLp8}1MX1y&PWeBmA0ZvLwK3dH4hoz-a8Xx#iD*B2Lp% zOI;Z2E$#T6j;l3N$?AM2JU}{rsgX{HK|0?~L4_jeLcmQ5oFLUVkcj^z>0Vwn9sb#c zF-6j=b`lG9mxX{7X84}0JqxE&`{bBM34ok0k0?D0^gl1B>nO0zP2Sh`2Iw|Tt_a@> z7%lRvvA0-B$p%|6mFhmnu;1H}$IOl!j?cSC0^kKdNbOAa98CoAx8T~24 z>p>4#39-ibU?;o(sWD04NGaWn*}uQ0#0|#J7HtE%Tr%!H%6M)&jVD_Ixh_@=7ES`6 zd?j#)kv);94Exj01QliCsAdwruB1BhDBa-EN_qyR4opz8F2<4BP-PuDu^4tMb@gLd zLX}E`+kB3c@6}-;95=GJnsuXwnWw62ANjJo7Z78aak*Obz{>S4b>ka)Y->@sRP1Bz zcT#uUnMkWz)m=4{nb2$X*qV)0FjsYy_mRl#hA(F(mX{eKUFNxC-V(B# zH@}+109EGFFW6K*r_I%Ss90Ep`D#5efYS%*0LeE?~xPKANp99*FSJ z1~hWagx=If6;m>|3~lXpc5#m`+Rg_<>E!|KNC^W+Bx`5?ruW{mc5UblR`)ck@j2(7 zVWQP@7~40}&+2vm4W~%Cb!0Q+gy&l4*;}}_6 ConfirmationDialog - - + + Ok 確定 - + Cancel 取消 @@ -108,149 +108,152 @@ DevicePanel - + Dongle ID Dongle ID - + N/A 無法使用 - + Serial 序號 - + Driver Camera 駕駛監控 - + PREVIEW 預覽 - + Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off) 預覽駕駛監控鏡頭畫面,方便調整設備安裝的位置,以提供更準確的駕駛監控。(車子必須保持在熄火的狀態) - + Reset Calibration 重置校準 - + RESET 重置 - + Are you sure you want to reset calibration? 您確定要重置校準嗎? - + Review Training Guide 觀看使用教學 - + REVIEW 觀看 - + Review the rules, features, and limitations of openpilot 觀看 openpilot 的使用規則、功能和限制 - + Are you sure you want to review the training guide? 您確定要觀看使用教學嗎? - + Regulatory 法規/監管 - + VIEW 觀看 + Change Language - 更改語言 + 更改語言 + CHANGE - 更改 + 更改 + Select a language - 選擇語言 + 選擇語言 - + Reboot 重新啟動 - + Power Off 關機 - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot 需要將裝置固定在左右偏差 4° 以內,朝上偏差 5° 以内或朝下偏差 8° 以内。鏡頭在後台會持續自動校準,很少有需要重置的情况。 - + Your device is pointed %1° %2 and %3° %4. 你的設備目前朝%2 %1° 以及朝%4 %3° 。 - + down - + up - + left - + right - + Are you sure you want to reboot? 您確定要重新啟動嗎? - + Disengage to Reboot 請先取消控車才能重新啟動 - + Are you sure you want to power off? 您確定您要關機嗎? - + Disengage to Power Off 請先取消控車才能關機 @@ -299,17 +302,17 @@ InputDialog - + Cancel 取消 - + Need at least 需要至少 - + characters! 個字元! @@ -394,12 +397,14 @@ location set MultiOptionDialog + Select - 選擇 + 選擇 + Cancel - 取消 + 取消 @@ -569,29 +574,29 @@ location set 離開 - + dashcam 行車記錄器 - + openpilot openpilot - + %1 minute%2 ago we don't need %2 %1 分鐘前 - + %1 hour%2 ago we don't need %2 %1 小時前 - + %1 day%2 ago we don't need %2 %1 天前 @@ -648,7 +653,7 @@ location set RichTextDialog - + Ok 確定 @@ -656,33 +661,33 @@ location set SettingsWindow - + × × - + Device 設備 - - + + Network 網路 - + Toggles 設定 - + Software 軟體 - + Navigation 導航 @@ -921,68 +926,68 @@ location set SoftwarePanel - + Git Branch Git 分支 - + Git Commit Git 提交 - + OS Version 系統版本 - + Version 版本 - + Last Update Check 上次檢查時間 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. 上次成功檢查更新的時間。更新系統只會在車子熄火時執行。 - + Check for Update 檢查更新 - + CHECKING 檢查中 - + Uninstall 卸載 - + UNINSTALL 卸載 - + Are you sure you want to uninstall? 您確定您要卸載嗎? - + failed to fetch update 下載更新失敗 - - + + CHECK 檢查 @@ -1070,82 +1075,82 @@ location set TogglesPanel - + Enable openpilot 啟用 openpilot - + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. 使用 openpilot 的主動式巡航和車道保持功能,開啟後您需要持續集中注意力,設定變更在重新啟動車輛後生效。 - + Enable Lane Departure Warnings 啟用車道偏離警告 - + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). 車速在時速 50 公里 (31 英里) 以上且未打方向燈的情況下,如果偵測到車輛駛出目前車道線時,發出車道偏離警告。 - + Enable Right-Hand Drive 啟用右駕模式 - + Allow openpilot to obey left-hand traffic conventions and perform driver monitoring on right driver seat. openpilot 將對右側駕駛進行監控 (但仍遵守靠左駕的交通慣例)。 - + Use Metric System 使用公制單位 - + Display speed in km/h instead of mph. 啟用後,速度單位顯示將從 mp/h 改為 km/h。 - + Record and Upload Driver Camera 記錄並上傳駕駛監控影像 - + Upload data from the driver facing camera and help improve the driver monitoring algorithm. 上傳駕駛監控的錄像來協助我們提升駕駛監控的準確率。 - + Disengage On Accelerator Pedal 油門取消控車 - + When enabled, pressing the accelerator pedal will disengage openpilot. 啟用後,踩踏油門將會取消 openpilot 控制。 - + Show ETA in 24h format 預計到達時間單位改用 24 小時制 - + Use 24h format instead of am/pm 使用 24 小時制。(預設值為 12 小時制) - + openpilot Longitudinal Control openpilot 縱向控制 - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot 將會關閉雷達訊號並接管油門和剎車的控制。注意:這也會關閉自動緊急煞車 (AEB) 系統! diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 6fe1d838ed..7922714c17 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -246,7 +246,7 @@ void UIState::update() { updateStatus(); if (sm->frame % UI_FREQ == 0) { - watchdog_kick(); + watchdog_kick(nanos_since_boot()); } emit uiUpdate(*this); } diff --git a/selfdrive/ui/update_translations.py b/selfdrive/ui/update_translations.py index 263eb5e670..d872be0d86 100755 --- a/selfdrive/ui/update_translations.py +++ b/selfdrive/ui/update_translations.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 import argparse -import os import json +import os from common.basedir import BASEDIR From cbff8fcbd02b262860b3540a3dba7108237d2b46 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 8 Jul 2022 21:17:00 -0700 Subject: [PATCH 263/302] Nav: wrap strings (#25089) * Wrap nav strings and translate * Update QM * Update QM --- selfdrive/ui/qt/maps/map.cc | 22 ++++---- selfdrive/ui/translations/main_ko.qm | Bin 19449 -> 19997 bytes selfdrive/ui/translations/main_ko.ts | 64 +++++++++++++++++++++++ selfdrive/ui/translations/main_zh-CHS.qm | Bin 17919 -> 18457 bytes selfdrive/ui/translations/main_zh-CHS.ts | 64 +++++++++++++++++++++++ selfdrive/ui/translations/main_zh-CHT.qm | Bin 18031 -> 18569 bytes selfdrive/ui/translations/main_zh-CHT.ts | 64 +++++++++++++++++++++++ 7 files changed, 203 insertions(+), 11 deletions(-) diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc index fd47f4188f..a486110a73 100644 --- a/selfdrive/ui/qt/maps/map.cc +++ b/selfdrive/ui/qt/maps/map.cc @@ -175,7 +175,7 @@ void MapWindow::updateState(const UIState &s) { loaded_once = loaded_once || m_map->isFullyLoaded(); if (!loaded_once) { - map_instructions->showError("Map Loading"); + map_instructions->showError(tr("Map Loading")); return; } @@ -192,7 +192,7 @@ void MapWindow::updateState(const UIState &s) { carPosSource["data"] = QVariant::fromValue(feature1); m_map->updateSource("carPosSource", carPosSource); } else { - map_instructions->showError("Waiting for GPS"); + map_instructions->showError(tr("Waiting for GPS")); } if (pan_counter == 0) { @@ -418,10 +418,10 @@ void MapInstructions::updateDistance(float d) { if (uiState()->scene.is_metric) { if (d > 500) { distance_str.setNum(d / 1000, 'f', 1); - distance_str += " km"; + distance_str += tr(" km"); } else { distance_str.setNum(50 * int(d / 50)); - distance_str += " m"; + distance_str += tr(" m"); } } else { float miles = d * METER_TO_MILE; @@ -429,10 +429,10 @@ void MapInstructions::updateDistance(float d) { if (feet > 500) { distance_str.setNum(miles, 'f', 1); - distance_str += " mi"; + distance_str += tr(" mi"); } else { distance_str.setNum(50 * int(feet / 50)); - distance_str += " ft"; + distance_str += tr(" ft"); } } @@ -615,7 +615,7 @@ void MapETA::updateETA(float s, float s_typical, float d) { auto eta_time = QDateTime::currentDateTime().addSecs(s).time(); if (params.getBool("NavSettingTime24h")) { eta->setText(eta_time.toString("HH:mm")); - eta_unit->setText("eta"); + eta_unit->setText(tr("eta")); } else { auto t = eta_time.toString("h:mm a").split(' '); eta->setText(t[0]); @@ -625,11 +625,11 @@ void MapETA::updateETA(float s, float s_typical, float d) { // Remaining time if (s < 3600) { time->setText(QString::number(int(s / 60))); - time_unit->setText("min"); + time_unit->setText(tr("min")); } else { int hours = int(s) / 3600; time->setText(QString::number(hours) + ":" + QString::number(int((s - hours * 3600) / 60)).rightJustified(2, '0')); - time_unit->setText("hr"); + time_unit->setText(tr("hr")); } QString color; @@ -649,10 +649,10 @@ void MapETA::updateETA(float s, float s_typical, float d) { float num = 0; if (uiState()->scene.is_metric) { num = d / 1000.0; - distance_unit->setText("km"); + distance_unit->setText(tr("km")); } else { num = d * METER_TO_MILE; - distance_unit->setText("mi"); + distance_unit->setText(tr("mi")); } distance_str.setNum(num, 'f', num < 100 ? 1 : 0); diff --git a/selfdrive/ui/translations/main_ko.qm b/selfdrive/ui/translations/main_ko.qm index f6e95b5038f984183d9d4273c581bb6ef6e4b91d..60966cdde587ebf4a43deb8ad255f374d32ca7c8 100644 GIT binary patch delta 2328 zcmZuxeNa@_9X73 zlxjOlH3{0N5N$=%0YN30pg}C87!z^g43b#Ds2LNJ*fds)?ZKT9C-IM+v+v$>?>+bY z&i(yok7{3q%02Z|j$hl|it_fr;U6wKaHcCB&?;uLn0qQ*BGGY;N8*vY@ z8W1^e$p)nHK=`M`DZuyu;(T&SJQ#c*(EI>+w{UNN;!R>S_tyb#Z4+Q_0E`!akwf|G z;6w^Aio`*05c`SkK;jm_ZUAO(TF zDB$9}pB?H_iHDDeSn@W2@8N#@M}5LGFfz`A)AvE#+Y6`^h|P9x7z?re6mcuWPeefZ z9?~|2H+>({vBMO<8JhYph(~E&77vo44dX?Oml0th8p@E|x*mwwisV~$z@&7{(9^X+ z58RkJv7AbHu_9VO?nlgdeHSgAjJf}$fFY$w+xRaoID`!0BaW9KBYP7MUWUxWyq%ng ztd!m4b>WpG8-VE#vG8mw57M9@$HwuOv9^!v%{y_R?IK;ggBsVXz}Or#51zw|xa)Ca z+ZqzSP+6nL(r#as-~M1Av{N-<2WxHLqDpO{eWNa@-nzo^nDwfQ86r2fs;&ym$B2=t z+fiG9;ok^y-gzLbS_rw(4NRCJB*`v1F<)5V#T(lrg?$}*@}0uTG76i}D14Bz14#2~ z6fUQ7V?`@;wK6o3<-+xMd;$MVwHQ7G@cm5fe}^?2aZYX99?P3Ws@J4)<0-GHkD4hw z{GPg|elBYru5PH|x~P-8HVOf5-)M2s;aZ+wB05s&u6Mq;uKRhw_NBNXn|id8SR&p7 zCO3cxdC)q;gEpO5QOW#928joIbBGJY>QBmnkU;Uo@=72{5l>1s?SG;WdA|n(eLZMP^*= z-vsnJ&4W2tn6)UaEtHmp4cAr;-OSPt(Z1*Gp@4kt-L!+WFh%?0)#rf0+1j7JrbFs$ z+J{rvA_8vf5<;8#CNAn`swv#-o^I(k4{3Fs?)Pin;(USb&qukRPoJ*tMi9Rv^jgzv zOj3eA$X&tSGHHZ9?uR@s=+VD4tCxx!^qHG!VbWgx`~|dp^mqE4mUv*yxB4Am)KIJM z=$y@H9np7r7qVyh%W+}sYnn1S=Mr0xZLC~+n{6pDh8V;3Y4Y})7JgUByC1RCqc_QW z8xJwEJ7ssp)t6YaFXjF1ti2d0AKSW{7S_oP5fX*{T0WP@g;KuUEC;a7d@46vr}EKN z%eR)eXrW?I)&GWkn<1#_JOw>xSlG?35OT+`^0G)LvkjZx@S%eyL(3hOXv_q|-(RFt z)+0urCY~G7<2DA?aANc+qY%zoz5xB1$`{%78Ia~d=8Tk~Hl zc}}#q`OLqWg@C`AFHXAz%=7EE=)Pm4)WutT;`qKNt1Q;99sv{WmKnX=(Eho_nRkN@ z87zOeTFlz7vb?#}NvG~xK3wr%Ag;~Qb!$H@pKZCGbe!MA91KoRZMWu#w_7}a=~5E| z#%S=TUg}z`?f?Jc;uVP*aVjgex&8YTNZhvYSNAFp=|CB554Z2uudn0rP+zL@d5*)(~-SMAJB+4{#}P z71m^qp}h-{{3?-HO(ZlDIV>g$+(k6Qk0@j}kqgF?K3#?%C>lPUNUKizfX)DMXG?K( z8p$p^1(uQACJNQ&lHBwfCaO2YT25=(Cv z1Ce8}WL%*G(G-nj<~|rQ?^7GRk{^ocFQ z$K4=u>R=qZJBd6}nIJw9#P&0*O>pBGYng(FN~|wpF6Mxk$7`l8cps5T4f7xzb*+7v z_9kCA>(<0{9JfHhEUES-T-Uyn+GWE{*R|55a1``DC@mAgc-mxX#f2r1&{bMpf%Vg0 z9Bg5%4Q9{Sn9@p|`zyO47_yqivnic(iEPc-)HUEC=h#g44UyL%n;%?*AVrR$Nz@pc zr;eeGjx`n!g3b!Is4EtDfIV|Jm&krOd;ZH}2pPd%7Df%xu(zJKVg53EtN$-JXnK$B z^gEBB$vJ)&l=jc()Y%CTE{qEh9l<-1i;960URhimUx$bcaq$i%5U7)jAB_^f8TcOi zPjM;hwqSiDx6M;Tvh%p?!yv*Jj^V`MF|qhZ4P9 zd1D6z%HggJLusajyKZ|Q$~$mv?I2|Tf_s+M1cwX8Q2&uWoa)hRj3Pt|;wEnt zYhMjP>MF(Fq@zR=PAGmXLp`%nMOC*w#<5Dd`g24mS!r)DD$p#;l>UFmVZ$@!^3X0Y zu2x2-LBjdBm8(`m^2rX$*akg_*(vvt6+%*}eAu=a(R!k6H~kuqla}{)#-k(4;bZT$ z;N~&>o<1$QJ^|>92PK2g?$KcU2Y+Y;R!^$p^J`8*d2ileY+a75n(>7#@Se5h&+a}1 z3H$hJcMinP@z>(8k&EZ+d22i`_xXBD9SC*sy# zIM}EX9E`n0#PXzO;IM>a}AlO#m!=#tOG~X12rCA6H zfY>4!q^lqs7o1C}tKbCg=kZ;&I}h zW9ag!9%4byJY->~_;WGp&khu8-ys7Ny2Ly4?h#p8Y80>WE`}-e8gqa2wbx9IkL WBvzGk6d diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 91685383f7..ad35a37fa1 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -340,6 +340,57 @@ 파일갱신: + + MapETA + + + eta + 에타 + + + + min + + + + + hr + 시간 + + + + km + km + + + + mi + mi + + + + MapInstructions + + + km + km + + + + m + m + + + + mi + mi + + + + ft + ft + + MapPanel @@ -389,6 +440,19 @@ location set 최근 경로 없음 + + MapWindow + + + Map Loading + 지도 로딩 + + + + Waiting for GPS + GPS를 기다리는 중 + + MultiOptionDialog diff --git a/selfdrive/ui/translations/main_zh-CHS.qm b/selfdrive/ui/translations/main_zh-CHS.qm index 19eccddbc0e919fdadb32a5621f8f7474aded85a..b96acb89d99ed8207dd34740c51714706e771040 100644 GIT binary patch delta 2290 zcmZuxeNh6su&m3bEY$c`E+nrLX6ZtQX>7bVeC*}7}GBrp~nGj0r4ua6d0ip-zG)? zBJa&TfD{RYO(%{c)(~@OF3F5j-fJTPc63vGWL2Ubof%*Tm2n4K$ z^a@o99}Q{8Ho%kv-5x$}Dx-MWd?*6?FeYMZK$J?9T}WzOO8b5!_3Q>l-@qfr*-Xsk zMoLT-nJ}?ZN^-1&8&;H_R0ii)}URK&cHEewC`I;JgijP zxF-!z-_?HHNWaLh*DMzT+&*i>S=*ZU{+~r>GSyYP#3fzvfXyi`n@v8tQgNmDPlkyX z*Cp>~uMYE|<*WyNU-ID4da=6x7BI3(+EQWB@#NL-;f8mu*p;x0y*X2oW2pG}?UK22J_XE`CRswryIIPf#fpqMD;3BG*(ztG zxxrg0)G2B1KuZ~2#GCZLE-lGl%)HIg(r623WWH4SClWDk_F%vP4-Wm#g9-Db>acn@ zg=>_mUuR30MoINAms5$aq@AB$pg=E3hx;hFP%a$_Jj0f%kvcj_$bM3~Sk}r)r+P5{ zOR2Yy1S6K|guqO;&RaUmwFoNct&6)dg$lOok{S;H5BckIG!#C#Ot~RPS_-&G98dpnx$?5g^CWp~KT93rkk{?s zLPF;A%h(HCN0I54)K{sT&tS{^#L4u#WvO_F(>}b=vhnf+miD&gy?VYA zz1wo&NA`mMOO{g;J_j848C1g$T$K8^RNsl5?=cms-#7ih?_<V^{SsdcbiJ(tDQYHlzg6gVakWVxYJHH&eu&{I-8eObR5afWP`Ca z_|wjDA@-ziBMe z_#XPUJM@3kl3_z|Zz@`wCzoGZH}&~72y+aMsI2~s+Sixg&CEoywy7n#dCua30rE!v wcQ}jlN=on0R+c6|T~0PhNW=8IPO2l<>7s)zzhr?eDQ)`yJ2utb|5W&Y0j3r(R{#J2 delta 1749 zcmX9;XHZmE7(M&;y)AFwzC{INVUeXNg4jS&!2%H}Dq_$OODsW&L`|5%HflDCh>A5r z1jLRKTbu#GGN`DCqGE|Uk`Nq%1$8u7Vsua-hhhJmz3<-pedjyh`EK@RO-s7Q9&|Fk z)76ID%u1W{x#@e()Pw-KD}c}h^w0s?1Y!^3B4Q+Q8*wfma^L(Eka`2&TZlu5e-S71 z%$IHG8Vl%4dG2#SxeVB510z=felvi`HH`Bo;5GUSUUUay`tooE@ms*rnV8D&OqATZ z&f4N~#^crH;BS0fVEc0iW7KoK6c{&{8O%ZUu4{4n%&@&0r(R{!(8M@*J z#1!aV;}~r&^gegFK8QXRqMVFT6-xo1AdGri1oZ2VaN|tC!5NVQGST{rToeL3dK4jg z?pD@QigACFK!Q2e-tEt4Rm)vS%+vAl7q+V7H~gN({Yfm9dH||>9o@W z@VKN2*vN+XJa`1E7%;%1J*<+kcagTBcpL*9(4H>fc|YscO2Nh6euy|d zzmRzw#5oa^)lw%esT&Hoxp^Ph zu{+}4NAaX(5|7->1YDPk$G^*?kcr|cg$*%hir1c0^Lw>;?fF0KphLJ=H|#i#HdT@b zQ0XC0By)Nah1(^Cs-EQCEX7S{C;T0x1oQ5e827fJ^T#%H@oB^0LsG6!9y{3nm6W@QRxtII@>Zt;PR`P?%e6qS zv(kkoDlMc+7j3s`rJYiB4GGzd(!-Prc6evU1Rh;TA@bo=1s}Gpx@smg%!@z zADjP>1V-x{#_y$soAmFhI&%nC>fb-7LfRwxk3;H#F7FMY-enxRjfO}qiCg9vX1)AK z!U2X23v#%hYS?v{@!D$)MUUONjx_4c)9B^yMt6Iz0qEOe9PuWB7iJhIL_MOE&c=x; zlyGR3aq<*O?*7RbUmgN@Rv95fPx2b)$bbmYBvrt%kTk!NSql`&MRgRA0L%Dg_=cEwh}4fk@TSMU;=<+>6U%3cp{ zQ6dAU0s|YBs1Pa;n4wI}WI*d!W!~6ULSHG{8u_I9Bq#-2IBd?-l#1O{tk)~$dNt8^ zrBYo^V&ZDEZodZ;jxqPP-Y1bk=0QzsIjk4WNBz0q&3@B-ViErg3^$j#9iSJi=CTl? z#~bt2AbLUWuR0yvPv!^JE@`Z|-3rz1LnxIwr3TjeGT|mQYCRQeSE?q3jO6(b>e}s` za<7Bxj{4zj=_mD29^?0WtDgCf9_Ui4-WYz1CJ(b1Uh!Rw*8gmA9KpHnf7#OUNi*M> zWJ~xX2J9VRnV;~O$_%t@u1aOkXIrvo&8I?*mUBORqC$C=nx{KC$A>JnVZU*0o&yZC Y77o_CIusUk$`iK6%bg4V=sMi@e-;zY9{>OV diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 1bcb30142c..c3e1954f1e 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -340,6 +340,57 @@ 更新文件: + + MapETA + + + eta + 埃塔 + + + + min + 分钟 + + + + hr + 小时 + + + + km + km + + + + mi + mi + + + + MapInstructions + + + km + km + + + + m + m + + + + mi + mi + + + + ft + ft + + MapPanel @@ -389,6 +440,19 @@ location set 没有最近的目的地 + + MapWindow + + + Map Loading + 地图加载 + + + + Waiting for GPS + 等待 GPS + + MultiOptionDialog diff --git a/selfdrive/ui/translations/main_zh-CHT.qm b/selfdrive/ui/translations/main_zh-CHT.qm index e64aabecd68c5df555b350ade44bd61fb2ea5cd9..208f29c0ec9dd45424301c70cdaf64c2e9a901bc 100644 GIT binary patch delta 2307 zcmZuxdsLKl8h+-x%*^-A?8i3by};+e-a zz{z`GC&XgL)*peic@KbgxE}lwOWg;-JKY!^2x-@KKxc*2Jdpv1LTWuu%!G770{lOR zyoD-_ErWdc0ASh%ef?G9`xGyOi4tK5V>(G95#VH+;%CT(S}Bd+RF&Wz^yx4PYzcpjSQYZl-PhiueOy^p)4;tfhUnyndpUZ{!2H-p%_>#y1Wzo>!Uiy{=$>&r}Q+ZV3Mv zCD>JAd<}au7>?o zUQt~YSDseR|s_FlZF9)5KPE1jU8h>%GvM{UZbqdZ7$R{gnV8r5dsC=z-{?Ox(! zqOVQ5`WN|{51N8cp5~17m=<($D+I@yR(vW^$t=^xHQx05(RAi3wrFIS=`T-HDW4%` z?~}|s?oTdrU@b2~|85>PbsdN0j(J8Ldp*_1oH%6xd*)%D6-xykZ!pg-XTX4G&H1zY z2<4i0-c4tKjpo{Id~E)!%q>+^Ec~|luWdy8Zgbli5|e&!(bt49VVou0?=p!@wM6z7 z^Uhs4Mp0`?u zZD!?O7HiO*I4X3(I;Df_DEu|+tWqlHHQTx(b~=aIZY|!!*FNf!b??n-oQY}Hx2u_F zl45QA4`*R`llAXv=XN@-VIs=ZMpgD58s8F2t zyDLTP{Zj4qYzK*r)jnGO6A*PmYwxb)dp@dl%y^gI0eKvpq`FT15)W7Usf;wv7bk;1 zG26M=(D(o8#mlFs#pp!-m*#6ZvHcdp(v`n3z%t}NG+37ZOM`smJv7MA8(`pa=SbD> z7}9Sc=I1#Em^`r1!-gC;^>tm-!&$Vs%hN&Sj(8Vh9T z0sL(b`2UJ&pG34AP>N`C*Yf|yb0al5Aa*L^?qw`2bY71Am0 delta 1749 zcmX9;c~p&Q9DeS1zwa*J{qA?8g{Y?6f^=OWghDln%&6=$vd6X0bPkhk=1zxfS;k;& zAqrz`N60cNOQKAegOQVHEXg(vGe{<9o=*3l=f2 zY!mus0{XLnc?Fp_k{s%J{!V63xLEP9k1#k-|rt^CdFuQS_ zyY{7z(|QZy(yc(mScsb*0U8xzQ7Bi9fLL~tm<92g2zYx#TH#ANWsnZ;1x#z9%ezNB z1-}R+y?G9PsGmBt3dBv$eld~XgeQ8uJM3ZH6E{+!}&uRj~+HB;I~H8a(e&} z=&tFynuc`r(j*oK0sfsdTW;}t_gKxxJa?@3W1Lw zaNk`aMxIS#cZ4Jtc5J^OY`baX`UAp=l_VDOsZcP0rd#F;HxgObD_W>5iJ-H#%|ca{ zI|~+QyjL(F%?E7cVYp1*kI*B%MlhmJVO40y@-7 z=NqWBkRe^L{>~^>NfnhOWKEPFE-In(H<~aaU8-*&!48T}unuLXy>)7>oeFN#g+Gm< zg4Md%+M!uy+a*>xX*Pm*+J?9R<(K1)|0e~TH5)%yievNn_TyIU<{hx_!0 zXFVi=1byw`T`c@T|EAoN78U5C4M$@xF%D^Zp5LT}Y-@t<2o0OS@8VNa+jrAi~pis$O%gg3y9brkOi>-zJd=bB~7Qv_NY<7|MBHXAAR*RQ~CnWiImD!z@Iai=v2u zQRdQcWViy-4%77;Oc^0=w-s@0Li%0cGzB9)x z{U5Pl#}vyf$76bxX8EB!ot{szY@RfWglv|=um1yj)>$fRwzGrRma3RT9FLyLz^ppj XQ$NvV-R)TOQNeSCaP)2Kb+-QjngYwa diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 2aff3334d9..f6e36081fa 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -340,6 +340,57 @@ 更新檔案: + + MapETA + + + eta + 埃塔 + + + + min + 分鐘 + + + + hr + 小時 + + + + km + km + + + + mi + mi + + + + MapInstructions + + + km + km + + + + m + m + + + + mi + mi + + + + ft + ft + + MapPanel @@ -394,6 +445,19 @@ location set 沒有最近的導航記錄 + + MapWindow + + + Map Loading + 地圖加載 + + + + Waiting for GPS + 等待 GPS + + MultiOptionDialog From f261b8a8c29fb2c9c5fee3b382e12e7887d50269 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 8 Jul 2022 22:09:37 -0700 Subject: [PATCH 264/302] EV6: supress LFA (#25094) * EV6: supress LFA * bump panda --- opendbc | 2 +- panda | 2 +- selfdrive/car/hyundai/carcontroller.py | 3 +++ selfdrive/car/hyundai/carstate.py | 5 ++++- selfdrive/car/hyundai/hda2can.py | 5 +++++ 5 files changed, 14 insertions(+), 3 deletions(-) diff --git a/opendbc b/opendbc index 1e9693ce09..9fc90a9f58 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 1e9693ce0916b896568dcd5558a670e67843c299 +Subproject commit 9fc90a9f5816ed82e0f25f2eaf7ad4af3d45733e diff --git a/panda b/panda index 53466f0934..ca927fe931 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 53466f09344c8ff6cdce3b19df76b5bca79e1327 +Subproject commit ca927fe9312651a16f13aaddca8b46af5315ede6 diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 73635375ad..a878ad3274 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -75,6 +75,9 @@ class CarController: # steering control can_sends.append(hda2can.create_lkas(self.packer, CC.enabled, self.frame, CC.latActive, apply_steer)) + if self.frame % 5 == 0: + can_sends.append(hda2can.create_cam_0x2a4(self.packer, self.frame, CS.cam_0x2a4)) + # cruise cancel if (self.frame - self.last_button_frame) * DT_CTRL > 0.25: if CC.cruiseControl.cancel: diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 6c82c33856..a10cdadbca 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -172,6 +172,7 @@ class CarState(CarStateBase): ret.cruiseState.speed = cp.vl["CRUISE_INFO"]["SET_SPEED"] * speed_factor self.buttons_counter = cp.vl["CRUISE_BUTTONS"]["_COUNTER"] + self.cam_0x2a4 = copy.copy(cp_cam.vl["CAM_0x2a4"]) return ret @@ -313,7 +314,9 @@ class CarState(CarStateBase): @staticmethod def get_cam_can_parser(CP): if CP.carFingerprint in HDA2_CAR: - return None + signals = [(f"BYTE{i}", "CAM_0x2a4") for i in range(3, 24)] + checks = [("CAM_0x2a4", 20)] + return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 6) signals = [ # signal_name, signal_address diff --git a/selfdrive/car/hyundai/hda2can.py b/selfdrive/car/hyundai/hda2can.py index e4c658c1a9..437f5cf538 100644 --- a/selfdrive/car/hyundai/hda2can.py +++ b/selfdrive/car/hyundai/hda2can.py @@ -12,6 +12,11 @@ def create_lkas(packer, enabled, frame, lat_active, apply_steer): } return packer.make_can_msg("LKAS", 4, values, frame % 255) +def create_cam_0x2a4(packer, frame, camera_values): + camera_values.update({ + "BYTE7": 0, + }) + return packer.make_can_msg("CAM_0x2a4", 4, camera_values, frame % 255) def create_buttons(packer, cnt, cancel, resume): values = { From 825acfae98543c915c18d3b19a9c5d2503e431a6 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 8 Jul 2022 22:09:58 -0700 Subject: [PATCH 265/302] Improve EV6 tune (#25085) --- selfdrive/car/torque_data/override.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index be81af2606..476313df2b 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -20,7 +20,7 @@ FORD FOCUS 4TH GEN: [.nan, 1.5, .nan] COMMA BODY: [.nan, 1000, .nan] # Totally new cars -KIA EV6 2022: [3.0, 2.5, 0.0] +KIA EV6 2022: [3.5, 2.5, 0.0] RAM 1500 5TH GEN: [2.0, 2.0, 0.05] # Dashcam or fallback configured as ideal car From d08a23177495c778fe628dc97728f5bbfee8b0f1 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 8 Jul 2022 22:46:20 -0700 Subject: [PATCH 266/302] Ship EV6 (#25095) * Ship EV6 * bump opendbc --- RELEASES.md | 1 + docs/CARS.md | 3 ++- opendbc | 2 +- selfdrive/car/hyundai/interface.py | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/test/process_replay/test_processes.py | 1 + 6 files changed, 7 insertions(+), 4 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index 588b88827a..b87bd2ee7d 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -29,6 +29,7 @@ Version 0.8.15 (2022-07-20) * Chrysler ECU firmware fingerprinting thanks to realfast! * Honda Civic 2022 support * Hyundai Tucson 2021 support thanks to bluesforte! +* Kia EV6 2022 support * Lexus NX Hybrid 2020 support thanks to AlexandreSato! * Ram 1500 2019-21 support thanks to realfast! diff --git a/docs/CARS.md b/docs/CARS.md index a1e89efe12..eb570faa7e 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -71,7 +71,7 @@ How We Rate The Cars |Toyota|RAV4 2019-21|All|||||| |Toyota|RAV4 Hybrid 2019-21|All|||||| -# Silver - 68 cars +# Silver - 69 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -95,6 +95,7 @@ How We Rate The Cars |Hyundai|Santa Fe Plug-in Hybrid 2022|All|||||| |Hyundai|Tucson Diesel 2019|SCC + LKAS|||||| |Kia|Ceed 2019|SCC + LKAS|||||| +|Kia|EV6 2022|All|||||| |Kia|Forte 2018|SCC + LKAS|||||| |Kia|Forte 2019-21|SCC + LKAS|||||| |Kia|K5 2021-22|SCC|||||| diff --git a/opendbc b/opendbc index 9fc90a9f58..81148db67f 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 9fc90a9f5816ed82e0f25f2eaf7ad4af3d45733e +Subproject commit 81148db67fd00d4e2a107b5b8269c532436edf2b diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 97119c77b7..069b0e74e5 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -36,7 +36,7 @@ class CarInterface(CarInterfaceBase): # These cars have been put into dashcam only due to both a lack of users and test coverage. # These cars likely still work fine. Once a user confirms each car works and a test route is # added to selfdrive/car/tests/routes.py, we can remove it from this list. - ret.dashcamOnly = candidate in {CAR.KIA_OPTIMA_H, CAR.ELANTRA_GT_I30} or candidate in HDA2_CAR + ret.dashcamOnly = candidate in {CAR.KIA_OPTIMA_H, CAR.ELANTRA_GT_I30} ret.steerActuatorDelay = 0.1 # Default delay ret.steerLimitTimer = 0.4 diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 0d61dbd735..65ecbb4be3 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -dab90772097a0dd4706677ba4fe5e84b10232099 \ No newline at end of file +825acfae98543c915c18d3b19a9c5d2503e431a6 \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 96d1014004..652c49db3d 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -18,6 +18,7 @@ from tools.lib.logreader import LogReader original_segments = [ ("BODY", "937ccb7243511b65|2022-05-24--16-03-09--1"), # COMMA.BODY ("HYUNDAI", "02c45f73a2e5c6e9|2021-01-01--19-08-22--1"), # HYUNDAI.SONATA + ("HYUNDAI", "d824e27e8c60172c|2022-07-08--21-21-15--1"), # HYUNDAI.KIA_EV6 ("TOYOTA", "0982d79ebb0de295|2021-01-04--17-13-21--13"), # TOYOTA.PRIUS (INDI) ("TOYOTA2", "0982d79ebb0de295|2021-01-03--20-03-36--6"), # TOYOTA.RAV4 (LQR) ("TOYOTA3", "f7d7e3538cda1a2a|2021-08-16--08-55-34--6"), # TOYOTA.COROLLA_TSS2 From 89d1d9f6df6e1fbe65609fa8f93702479620a50e Mon Sep 17 00:00:00 2001 From: Greg Hogan Date: Sat, 9 Jul 2022 00:55:40 -0700 Subject: [PATCH 267/302] firmware fingerprinting: order brand requests (#23311) Co-authored-by: Shane Smiskol --- selfdrive/car/car_helpers.py | 4 +- selfdrive/car/fw_versions.py | 75 ++++++++++++++++++++++++++++-------- 2 files changed, 62 insertions(+), 17 deletions(-) diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 690072cc4d..b6bdece676 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -8,7 +8,7 @@ from system.version import is_comma_remote, is_tested_branch from selfdrive.car.interfaces import get_interface_attr from selfdrive.car.fingerprints import eliminate_incompatible_cars, all_legacy_fingerprint_cars from selfdrive.car.vin import get_vin, VIN_UNKNOWN -from selfdrive.car.fw_versions import get_fw_versions, match_fw_to_car, get_present_ecus +from selfdrive.car.fw_versions import get_fw_versions_ordered, match_fw_to_car, get_present_ecus from system.swaglog import cloudlog import cereal.messaging as messaging from selfdrive.car import gen_empty_fingerprint @@ -99,7 +99,7 @@ def fingerprint(logcan, sendcan): cloudlog.warning("Getting VIN & FW versions") _, vin = get_vin(logcan, sendcan, bus) ecu_rx_addrs = get_present_ecus(logcan, sendcan) - car_fw = get_fw_versions(logcan, sendcan) + car_fw = get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs) exact_fw_match, fw_candidates = match_fw_to_car(car_fw) else: diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 04610b96d9..c4b158aebb 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -225,6 +225,15 @@ def build_fw_dict(fw_versions, filter_brand=None): return fw_versions_dict +def get_brand_addrs(): + versions = get_interface_attr('FW_VERSIONS', ignore_none=True) + brand_addrs = defaultdict(set) + for brand, cars in versions.items(): + for fw in cars.values(): + brand_addrs[brand] |= {(addr, sub_addr) for _, addr, sub_addr in fw.keys()} + return brand_addrs + + def match_fw_to_car_fuzzy(fw_versions_dict, log=True, exclude=None): """Do a fuzzy FW match. This function will return a match, and the number of firmware version that were matched uniquely to that specific car. If multiple ECUs uniquely match to different cars @@ -236,7 +245,7 @@ def match_fw_to_car_fuzzy(fw_versions_dict, log=True, exclude=None): # time and only one is in our database. exclude_types = [Ecu.fwdCamera, Ecu.fwdRadar, Ecu.eps, Ecu.debug] - # Build lookup table from (addr, subaddr, fw) to list of candidate cars + # Build lookup table from (addr, sub_addr, fw) to list of candidate cars all_fw_versions = defaultdict(list) for candidate, fw_by_addr in FW_VERSIONS.items(): if candidate == exclude: @@ -361,24 +370,59 @@ def get_present_ecus(logcan, sendcan): return ecu_responses -def get_fw_versions(logcan, sendcan, extra=None, timeout=0.1, debug=False, progress=False): - ecu_types = {} +def get_brand_ecu_matches(ecu_rx_addrs): + """Returns dictionary of brands and matches with ECUs in their FW versions""" - # Extract ECU addresses to query from fingerprints - # ECUs using a subaddress need be queried one by one, the rest can be done in parallel - addrs = [] - parallel_addrs = [] + brand_addrs = get_brand_addrs() + brand_matches = {r.brand: set() for r in REQUESTS} + + brand_rx_offsets = set((r.brand, r.rx_offset) for r in REQUESTS) + for addr, sub_addr, _ in ecu_rx_addrs: + # Since we can't know what request an ecu responded to, add matches for all possible rx offsets + for brand, rx_offset in brand_rx_offsets: + a = (uds.get_rx_addr_for_tx_addr(addr, -rx_offset), sub_addr) + if a in brand_addrs[brand]: + brand_matches[brand].add(a) + + return brand_matches + + +def get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs, timeout=0.1, debug=False, progress=False): + """Queries for FW versions ordering brands by likelihood, breaks when exact match is found""" + all_car_fw = [] + brand_matches = get_brand_ecu_matches(ecu_rx_addrs) + + for brand in sorted(brand_matches, key=lambda b: len(brand_matches[b]), reverse=True): + car_fw = get_fw_versions(logcan, sendcan, brand=brand, timeout=timeout, debug=debug, progress=progress) + all_car_fw.extend(car_fw) + matches = match_fw_to_car_exact(build_fw_dict(car_fw)) + if len(matches) == 1: + break + + return all_car_fw + + +def get_fw_versions(logcan, sendcan, brand=None, extra=None, timeout=0.1, debug=False, progress=False): versions = get_interface_attr('FW_VERSIONS', ignore_none=True) + if brand is not None: + versions = {brand: versions[brand]} + if extra is not None: versions.update(extra) + # Extract ECU addresses to query from fingerprints + # ECUs using a subaddress need be queried one by one, the rest can be done in parallel + addrs = [] + parallel_addrs = [] + ecu_types = {} + for brand, brand_versions in versions.items(): for c in brand_versions.values(): for ecu_type, addr, sub_addr in c.keys(): a = (brand, addr, sub_addr) if a not in ecu_types: - ecu_types[(addr, sub_addr)] = ecu_type + ecu_types[a] = ecu_type if sub_addr is None: if a not in parallel_addrs: @@ -390,17 +434,17 @@ def get_fw_versions(logcan, sendcan, extra=None, timeout=0.1, debug=False, progr addrs.insert(0, parallel_addrs) fw_versions = {} - for i, addr in enumerate(tqdm(addrs, disable=not progress)): + requests = [r for r in REQUESTS if brand is None or r.brand == brand] + for addr in tqdm(addrs, disable=not progress): for addr_chunk in chunks(addr): - for r in REQUESTS: + for r in requests: try: addrs = [(a, s) for (b, a, s) in addr_chunk if b in (r.brand, 'any') and - (len(r.whitelist_ecus) == 0 or ecu_types[(a, s)] in r.whitelist_ecus)] + (len(r.whitelist_ecus) == 0 or ecu_types[(b, a, s)] in r.whitelist_ecus)] if addrs: query = IsoTpParallelQuery(sendcan, logcan, r.bus, addrs, r.request, r.response, r.rx_offset, debug=debug) - t = 2 * timeout if i == 0 else timeout - fw_versions.update({(r.brand, addr): (version, r) for addr, version in query.get_data(t).items()}) + fw_versions.update({(r.brand, addr): (version, r) for addr, version in query.get_data(timeout).items()}) except Exception: cloudlog.warning(f"FW query exception: {traceback.format_exc()}") @@ -409,7 +453,7 @@ def get_fw_versions(logcan, sendcan, extra=None, timeout=0.1, debug=False, progr for (brand, addr), (version, request) in fw_versions.items(): f = car.CarParams.CarFw.new_message() - f.ecu = ecu_types[addr] + f.ecu = ecu_types[(brand, addr[0], addr[1])] f.fwVersion = version f.address = addr[0] f.responseAddress = uds.get_rx_addr_for_tx_addr(addr[0], request.rx_offset) @@ -433,6 +477,7 @@ if __name__ == "__main__": parser = argparse.ArgumentParser(description='Get firmware version of ECUs') parser.add_argument('--scan', action='store_true') parser.add_argument('--debug', action='store_true') + parser.add_argument('--brand', help='Only query addresses/with requests for this brand') args = parser.parse_args() logcan = messaging.sub_sock('can') @@ -458,7 +503,7 @@ if __name__ == "__main__": print() t = time.time() - fw_vers = get_fw_versions(logcan, sendcan, extra=extra, debug=args.debug, progress=True) + fw_vers = get_fw_versions(logcan, sendcan, brand=args.brand, extra=extra, debug=args.debug, progress=True) _, candidates = match_fw_to_car(fw_vers) print() From eb17291ca13035b40d653da107653d4420517aaa Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 9 Jul 2022 16:47:10 +0800 Subject: [PATCH 268/302] Display the current language in MultiOptionDialog (#25098) * check the selected language in lange select dialog * disable if user selects current option * update line numbers Co-authored-by: Shane Smiskol --- selfdrive/ui/qt/offroad/settings.cc | 3 +- selfdrive/ui/qt/widgets/input.cc | 15 +++-- selfdrive/ui/qt/widgets/input.h | 4 +- selfdrive/ui/translations/main_ko.ts | 70 ++++++++++++------------ selfdrive/ui/translations/main_zh-CHS.ts | 70 ++++++++++++------------ selfdrive/ui/translations/main_zh-CHT.ts | 70 ++++++++++++------------ 6 files changed, 119 insertions(+), 113 deletions(-) diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 6bcdd55b0a..d5b8d4bbd1 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -137,7 +137,8 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { auto translateBtn = new ButtonControl(tr("Change Language"), tr("CHANGE"), ""); connect(translateBtn, &ButtonControl::clicked, [=]() { QMap langs = getSupportedLanguages(); - QString selection = MultiOptionDialog::getSelection(tr("Select a language"), langs.keys(), this); + QString currentLang = QString::fromStdString(Params().get("LanguageSetting")); + QString selection = MultiOptionDialog::getSelection(tr("Select a language"), langs.keys(), langs.key(currentLang), this); if (!selection.isEmpty()) { // put language setting, exit Qt UI, and trigger fast restart Params().put("LanguageSetting", langs[selection].toStdString()); diff --git a/selfdrive/ui/qt/widgets/input.cc b/selfdrive/ui/qt/widgets/input.cc index a130a8e935..b0facfce83 100644 --- a/selfdrive/ui/qt/widgets/input.cc +++ b/selfdrive/ui/qt/widgets/input.cc @@ -261,7 +261,7 @@ bool RichTextDialog::alert(const QString &prompt_text, QWidget *parent) { // MultiOptionDialog -MultiOptionDialog::MultiOptionDialog(const QString &prompt_text, QStringList l, QWidget *parent) : QDialogBase(parent) { +MultiOptionDialog::MultiOptionDialog(const QString &prompt_text, const QStringList &l, const QString ¤t, QWidget *parent) : QDialogBase(parent) { QFrame *container = new QFrame(this); container->setStyleSheet(R"( QFrame { background-color: #1B1B1B; } @@ -301,12 +301,17 @@ MultiOptionDialog::MultiOptionDialog(const QString &prompt_text, QStringList l, confirm_btn->setObjectName("confirm_btn"); confirm_btn->setEnabled(false); - for (QString &s : l) { + for (const QString &s : l) { QPushButton *selectionLabel = new QPushButton(s); selectionLabel->setCheckable(true); + selectionLabel->setChecked(s == current); QObject::connect(selectionLabel, &QPushButton::toggled, [=](bool checked) { if (checked) selection = s; - confirm_btn->setEnabled(true); + if (selection != current) { + confirm_btn->setEnabled(true); + } else { + confirm_btn->setEnabled(false); + } }); group->addButton(selectionLabel); @@ -336,8 +341,8 @@ MultiOptionDialog::MultiOptionDialog(const QString &prompt_text, QStringList l, outer_layout->addWidget(container); } -QString MultiOptionDialog::getSelection(const QString &prompt_text, const QStringList l, QWidget *parent) { - MultiOptionDialog d = MultiOptionDialog(prompt_text, l, parent); +QString MultiOptionDialog::getSelection(const QString &prompt_text, const QStringList &l, const QString ¤t, QWidget *parent) { + MultiOptionDialog d = MultiOptionDialog(prompt_text, l, current, parent); if (d.exec()) { return d.selection; } diff --git a/selfdrive/ui/qt/widgets/input.h b/selfdrive/ui/qt/widgets/input.h index 47d8b74efd..6c47a31d87 100644 --- a/selfdrive/ui/qt/widgets/input.h +++ b/selfdrive/ui/qt/widgets/input.h @@ -73,7 +73,7 @@ class MultiOptionDialog : public QDialogBase { Q_OBJECT public: - explicit MultiOptionDialog(const QString &prompt_text, const QStringList l, QWidget *parent); - static QString getSelection(const QString &prompt_text, const QStringList l, QWidget *parent); + explicit MultiOptionDialog(const QString &prompt_text, const QStringList &l, const QString ¤t, QWidget *parent); + static QString getSelection(const QString &prompt_text, const QStringList &l, const QString ¤t, QWidget *parent); QString selection; }; diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index ad35a37fa1..5a8f21d7a7 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -193,67 +193,67 @@ 변경 - + Select a language 언어선택 - + Reboot 재부팅 - + Power Off 전원 종료 - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot은 장치를 왼쪽 또는 오른쪽 4° 이내, 위쪽 5° 또는 아래쪽 8° 이내로 설치해야 합니다. openpilot은 지속적으로 보정되므로 리셋이 거의 필요하지 않습니다. - + Your device is pointed %1° %2 and %3° %4. 사용자의 기기가 %1° %2 및 %3° %4를 가리키고 있습니다. - + down 아래 - + up - + left 왼쪽 - + right 오른쪽 - + Are you sure you want to reboot? 재부팅 하시겠습니까? - + Disengage to Reboot 재부팅 하려면 해제하세요 - + Are you sure you want to power off? 전원을 종료하시겠습니까? - + Disengage to Power Off 전원을 종료하려면 해제하세요 @@ -461,7 +461,7 @@ location set 선택 - + Cancel 취소 @@ -717,33 +717,33 @@ location set SettingsWindow - + × × - + Device 장치 - - + + Network 네트워크 - + Toggles 토글 - + Software 소프트웨어 - + Navigation 네비게이션 @@ -982,68 +982,68 @@ location set SoftwarePanel - + Git Branch Git 브렌치 - + Git Commit Git 커밋 - + OS Version OS 버전 - + Version 버전 - + Last Update Check 최신 업데이트 검사 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. 이전에 openpilot에서 업데이트를 성공적으로 확인한 시간입니다. 업데이트 프로그램은 차량 연결이 해제되었을때만 작동합니다. - + Check for Update 업데이트 확인 - + CHECKING 검사중 - + Uninstall 삭제 - + UNINSTALL 삭제 - + Are you sure you want to uninstall? 삭제하시겠습니까? - + failed to fetch update 업데이트를 가져올수없습니다 - - + + CHECK 확인 diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index c3e1954f1e..dbbde36394 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -193,67 +193,67 @@ 切换 - + Select a language 选择语言 - + Reboot 重启 - + Power Off 关机 - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot 要求设备安装在左或右 4° 以内,上 5° 或下 8° 以内。 openpilot 会持续校准,很少需要重置。 - + Your device is pointed %1° %2 and %3° %4. 您的设备指向 %1° %2 和 %3° %4。 - + down - + up 向上 - + left 向左 - + right 向右 - + Are you sure you want to reboot? 您确定要重新启动吗? - + Disengage to Reboot 脱离以重新启动 - + Are you sure you want to power off? 您确定要关闭电源吗? - + Disengage to Power Off 脱离以关闭电源 @@ -461,7 +461,7 @@ location set 选择 - + Cancel 取消 @@ -717,33 +717,33 @@ location set SettingsWindow - + × × - + Device 设备 - - + + Network 网络 - + Toggles 切换 - + Software 软件 - + Navigation 导航 @@ -982,68 +982,68 @@ location set SoftwarePanel - + Git Branch Git 分支 - + Git Commit Git 提交 - + OS Version 操作系统版本 - + Version 版本 - + Last Update Check 最后更新检查 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. 上次 openpilot 成功检查更新的时间。 更新程序仅在汽车关闭时运行。 - + Check for Update 检查更新 - + CHECKING 正在检查 - + Uninstall 卸载 - + UNINSTALL 卸载 - + Are you sure you want to uninstall? 您确定要卸载吗? - + failed to fetch update 未能获取更新 - - + + CHECK 查看 diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index f6e36081fa..2920916ece 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -193,67 +193,67 @@ 更改 - + Select a language 選擇語言 - + Reboot 重新啟動 - + Power Off 關機 - + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. openpilot 需要將裝置固定在左右偏差 4° 以內,朝上偏差 5° 以内或朝下偏差 8° 以内。鏡頭在後台會持續自動校準,很少有需要重置的情况。 - + Your device is pointed %1° %2 and %3° %4. 你的設備目前朝%2 %1° 以及朝%4 %3° 。 - + down - + up - + left - + right - + Are you sure you want to reboot? 您確定要重新啟動嗎? - + Disengage to Reboot 請先取消控車才能重新啟動 - + Are you sure you want to power off? 您確定您要關機嗎? - + Disengage to Power Off 請先取消控車才能關機 @@ -466,7 +466,7 @@ location set 選擇 - + Cancel 取消 @@ -725,33 +725,33 @@ location set SettingsWindow - + × × - + Device 設備 - - + + Network 網路 - + Toggles 設定 - + Software 軟體 - + Navigation 導航 @@ -990,68 +990,68 @@ location set SoftwarePanel - + Git Branch Git 分支 - + Git Commit Git 提交 - + OS Version 系統版本 - + Version 版本 - + Last Update Check 上次檢查時間 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. 上次成功檢查更新的時間。更新系統只會在車子熄火時執行。 - + Check for Update 檢查更新 - + CHECKING 檢查中 - + Uninstall 卸載 - + UNINSTALL 卸載 - + Are you sure you want to uninstall? 您確定您要卸載嗎? - + failed to fetch update 下載更新失敗 - - + + CHECK 檢查 From be7f7041681ab088f03c075a8a836e538378a7a8 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 11 Jul 2022 12:52:03 -0700 Subject: [PATCH 269/302] Fix new steer saturated warning with joystick mode (#25113) Fix steer sat warning with joystick mode --- selfdrive/controls/controlsd.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 6f0c9c2ae6..117509f1e6 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -602,14 +602,14 @@ class Controls: lac_log.saturated = abs(actuators.steer) >= 0.9 # Send a "steering required alert" if saturation count has reached the limit - if lac_log.active and not CS.steeringPressed and self.CP.lateralTuning.which() == 'torque': + if lac_log.active and not CS.steeringPressed and self.CP.lateralTuning.which() == 'torque' and not self.joystick_mode: undershooting = abs(lac_log.desiredLateralAccel) / abs(1e-3 + lac_log.actualLateralAccel) > 1.2 turning = abs(lac_log.desiredLateralAccel) > 1.0 good_speed = CS.vEgo > 5 max_torque = abs(self.last_actuators.steer) > 0.99 if undershooting and turning and good_speed and max_torque: self.events.add(EventName.steerSaturated) - elif lac_log.active and lac_log.saturated and not CS.steeringPressed: + elif lac_log.active and not CS.steeringPressed and lac_log.saturated: dpath_points = lat_plan.dPathPoints if len(dpath_points): # Check if we deviated from the path From 5e896ce2f134b9f17d466bf1aec694142bcb5ed3 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Mon, 11 Jul 2022 13:22:13 -0700 Subject: [PATCH 270/302] Improve Simplified Chinese translations (#25091) * 1 * shane told me to do this * 1.5 * 2 * 3 * 4 * Update main_zh-CHS.ts * release * some minor improvements * build * remove state Co-authored-by: Shane Smiskol --- selfdrive/ui/translations/main_zh-CHS.qm | Bin 18457 -> 18507 bytes selfdrive/ui/translations/main_zh-CHS.ts | 272 +++++++++++------------ 2 files changed, 135 insertions(+), 137 deletions(-) diff --git a/selfdrive/ui/translations/main_zh-CHS.qm b/selfdrive/ui/translations/main_zh-CHS.qm index b96acb89d99ed8207dd34740c51714706e771040..59487d263a7a7524f15a239bb7ace144137f31b0 100644 GIT binary patch delta 4896 zcmZuz30PBC_CHD9%f5gtDzbzR+dJw5{3}wOY}-)N!h|+8V30j@CNpXqEqYi8%FhK0ZA!_nvdl_B+3OH?8J; zwVJcq+cFn``vf4|0KhY$G^3n{awEzOC=UQoxGz@&(9r-9w^5D;h>S;Bh&o264Cn&j z-ve-22O#i4`60?tC@-Kq3?S$PfKb%4xMt%AD!RT2Fs>CqeFR`q z8#+n^n5;)>0nop`}ii9AS%PePQawZP7DO|nwNp+ z%Ro~@u%bf9yLKJ3^RR=i={_3tf`R)5ZcG6~SqnN|3{!XQ01(ZCX%p9>!_n}k?!^FO zG*JB6adZ>_wG{zq{~^qOg7&g<*m~j=z}Q&W(@+8sRs}t78UWwRV1K<4_xEr-M@0ez zwR48O6@*pia1vHou-7qZ9PQCCfZzyD*EhH^Dv)!^fEDmq!nw%Z4&XC^b1SYDV8jTn z*o5s-^>BmjKcL-HZnn4q1KZCnV*9QBnfvB>5$dnwe$;`1#a3_+PFw|`Xyu;M;<>&f zxmS)OW}-gjUftq>=Plt;mZ+fs?gpOEFW57mo4f$)7|bk}*QmvVUn$_dE62zqWxPH6 z^6;RCyaRjCP~F1o32jE;UgVt~f_>*KNkMIqm*Ui#7_{#@svX<0-VzQuv037sLeYbV#KM`w(Aur zo2d6rcLD@_LH(_I2bQ{$+AqbH$*xde-MED4_NTt;`xo~7F7?BhzX1p=v^Wu4k$RVw zS!V+z_0pO0U`%K#J#9L+DzU^uo5TlkG(_~PL6|{I4gD$$HqjQ8n3+&TFQ}Z42D|7* z@p5$VZ`!&Z0}-8YO21U6RMtA>m~MJA0vO!y(wl9F6^W7F@!E2Lp+o2oj$Osd`O=?1 z3Bta1B4@ z7LF|cTmJYxp8_N=;TLkSCBZa*`@^RI{?quML~X*rm+&8HzCjQs2m->eVyZmBPOoK{ zV6WhVx*susse(JYZ8-m9t%84FL^2o>E_l#~CE^_rJRbcMV!=(A8PNKK)=<}T851%U%KH@K8|0nbk7OASmODLm$mtH!Gfl;eu{GCDQFh>^c^A8MUlx)q6K09L^qB&CD{s!_u7)So*Ph$}iljVQefsPW!$Up5zEO=j* zpBno$qCG_+yo(GfII3_@$MH^7C_HaGMM65Mm~b7>i|JIoIYlL|%5b`AUgd zKi}3w9*C1TQA90q=QDPVrBOu~iPo3%{!7Qi;Bh=yl zGoc25H86I^0m1Twq00ZQK}zK*e!lF1FcGo_gph@Hbznk!BZkDTiAc9xC6IPCcbN^- z$T#vhJ}?js=|rvw=C*%H5)^uEUYWiWO3WKu+rM<`Rb=IzE{GqHHmaCa9Xw-0VSC$= z_Om7LF!p61m2NPBW|&jYe5QPtM&H$;<}ycSx7Jr1`}KDkRcbEzQE{52#LG#KOSVX8 zKC@`6=GydGMBy4Hl0Gj%s%tzgbkty>Yf?hI$v#i=at+L_Y~kB`bi)Uvj9q_1Yu3HJ z4xebkcJ_-Jj&!lJ|7aoMbS4T*s}KJ1KV3_GT4H#DVbaI zG)u$V&*rO&Z$LckHgxEJV(E-Z~S8Lg=GvImV< zIj8w{<$dFB((HDb4W-CEloiX}HGJcdg%V>u`PMy`($=gwNg_NZ2!ys{`i~hPW{)tL zw7NWBWr)^wn;#-}{^Ai!i$TeRlkYu>ge|`nxo&{=7Lw^1?NnrwP=+W&NRwxkkhLtJ z8u;Y4XB_Rq{@Uw5bPb25>ga_F$*02#=?d$%^)#8S_H<~Ns^i;tM3O|Dub%o;x5d`P zj3lKaKBK9wi_N=8sCS4+$j)Tp(fJ%=@QxG-*{{yw);r`)??{Q%qHVrxkS(}7;6=Xn z4wi^vGU7EC{~5?5?_hq{#lo)Dek9mOiCcPPhjI9qMJD+Kh=foLwTR&=GSA0fz{l@; zsM@>TXDKzpw}?MDo{SvIu{pK)H)CZ8;v+3!l1K_MB@GTvSs9Q>XR){^scI$8cg;<0 z2U{A_A7JBnvtQJl1*S~0D)22IZ^#4<#+HjTrNmG)7$pM+(AV$BUd9D2<9Iqu4+TXD z#G!7WEWWq*UQiN;%k=Gy3|Yi+b#!A8_>P7h2*naiFDsB~AL*A`50cxVp{Z%b_u6mh z&n$l2{5`8X;5EO_x`VOnlp3hPN0vgtS1d5ef$$5$LAE3t zBQ&n=jLi03`Od*Lq-!cNp5M|}*u_jFX_1jwnk<+BbD;{0Jp*b7gl&^;mDb&*QD*5t_ho5;{mmG!~=I?WYk?Gl4U%O1aURzVZv&VmK$dkW}avPoo|K%z&k z7YW(e*qq6Uk(!vX)(0#dIDE~)R#c(SIY@X$j9_l_AyX-nJlKBC8;uDA(!I%1$s8HN zoekhw*bAaJ$Qu5L6XK`#;tmK|Ah-;O*5nrc2f6Sy{RQ?Ywy%5J)ig&TcYuJw#*f1< z10gYpL^gWuqt4;vKuj>#q9xa2{3tdXLdA}wY{%+vlib)W9@lu4Y{UhYHORGCADYTn zH6J2$oIhea4?)FX71K#XoKnEA@NNpgLCTBsr-hEb&WQ^|Kb5xESYM3F` zgJbIB%RSs-JYE_NSdk2@#|*4UIZnsb_=rF3WIh`P)FZc?q!`Az6_S z7oEt68L0LzbJ4v$xNB}T_IKV_b6Ix_B_%fINWQA3$yUiSJ{d^(l@{7&G5zG%#F0{# zRamuxn3cgK{FP!4FSe^}A)iG!0UDuPsNOP-WoNCtXRC9F#-GDR1mcHU&8GC`}i=jIGBS}8z62r7&drgwY>@%bnD+=zAlJ7WxuP-s<4{4`zok7L-ZUX2NK9Jjj8|Fx zmCJ3%APyfU4r;`AK?0};tp`NxX-n-@hih|mY8F^4U$-4YD}D1J#@!TNrnl7?TRCEPmsnzE#2V$Zm&ISlOdJsl@kI(_e^pAU zf{lD*t92`SILM-h3>ll~rv9(K^M!%)HDl~1A8*G{KeN^)I`Ts@L5i=3S~4Pij7-XE zXlrzd`YD=RQl1`Tsdw1C^k%YMYMb2Bx0+kBuK3#0a6<>1m*z@2$F^MeXEm3#sjgsO z5XS!L-K9r1E;9D(Mzi}hH)kkxZ>YIeJBtx>D}s1bzRLNgY4kHrP;;MC=-DZAjY<-h zaUI`=@=Q;PZ5h4{eaQICVmGh<(ct}=**tkqpK`MiIa5 zU3QZgves&*R`hC$*j})AKRa9)<%9q77fTB|^&mq#FZRm&r9V4z*!}EvhU`}mTBK-x zhe;-5#_e@Jcl*bM{E_W_Nk(?OlU&%_+(FmNvp;aIuwEQ1nd2wRhLm2k?jH0=wvA78 TUT|gA<)_(O-J$pM_^AH}{k-)m delta 4941 zcmZu!2Ut{B_CGVcH|0$ODJp^vAWi9I1VmJ@V0+^fMM9Nf7?on9*kC}xKtKn)Vj*fY zHr(i6S7Kau6HC?_MKm$$#+Vot+dqk$rbdJ8xr}AMtlxZc?z{KgbIbyDoo+YLbU zGk{|PfEaB$W}%ElS&8x}?jHppKLy|u0N{5C=l==dk9tpJv#wpX(0Lt z50@R5bgsD(+#W42FV$^>QWA7aRi2Mzbr8yW_F^tzVqazqsSt6cO z2HFCGh#ZB<-`%!iL$3!Iu|WU> z#ezPY24WiC7DTVKVy?qB3v?#~abcIBfjVaK9_$ zEGN*gM(Epl6CgZCI0mBzw;Ex(BSsuHPPp-s6u@(!@L&Tv7XF#=@VJ!#swm+XI<)J# zS9tvlawdco-q`F4&~Lm0V-4vI;L^vz^Lxyh=K=@s`r#PaE{75w8rEEN_&|xC4=!`q z|IuVLw8P==`*CCFw+_esE0DOKIdt@T3?L|Vcv7+*0S;tF-~TIsGhwoKwxMHxWoC}U zY1K_;;mrg9^-N|-4mv6-W8P+dLHh}eb=|m+k;Q&Yk5qncmo7`~a=INcL z$$r{35Rt24|LJuRxn|wOUb~JSd7ou(Ejxo8m|&L)SJJ$=oUIKQT$NM}%dM2j>n9TE3EEX_Tci1qK^B3%hcLf9z1bd3iX;x4`JG#k6x9&Y4d z?06zMmwTZdV8Cgv?ml*`{7YAEW`d@@-v$eve5nVbJtLYjFMkFiHHQ=LAzG}Axq+Q3RHvNKfY3SjQO->qjT@gR>)ypa5Rk9jcy|Qm_7CM>w&6ih2b7;Y zLN0hLRh}Pl0id@;CHXgYQ1L32%SbHm=sK0#o#y}%8ddUbv={bRRb=Tz(*CZBY`j{7 zxzAIrHy0sPPgO_e{DDyAsjlDKgpe1gZjAXqfT0~TkvZQwpr%kapCpL~3ylqAj<`@N zhmkNDcuBy?9_*yrY|A3s4XvA_G(V1}rBaL=) zp=0yD(&|?lywoa{zxw)0I!wvORXxzRHche?m833OM0~m3_H(}Ed=!p3pI2P(mKzq> z%F&{OEM`DNc5Bv&b&E~g4OcAF^An5>mg)SXoJo~kT5CxF>MTm~B=cpdK4GBFZY`~@ zKb$HyiH%O6244t=eLXS))W!zXy)R33a>;I8P?XkESEZZZ{6k4}Q6tgHTNJNmo7$~K z9h|DtK9*3i-rCIof2#Fl4UPNAWmbxVoLv4fQ~ zwVU^mZygORQ+jdn7BbW+kj`O9g-%gYxuvsA))Utbr=iMpzS z#FwF@1Z3RFaWnjahegqhAec26GKb&M^gG9mr;fzDT%+N=$)?ubB&hgdhL`SSw>+yh z-Dxeo?oV$;N)i#3Eg??HaC_Jp5jbS9t_^dO!-yLtKl% zg80sX=`bIEWjHera>*%=AhCpxg2+u4g zr@S>{O^zcUhi7(#spXV;RE=Up5`1jZ9<=5yoO6iW^VuX8(KWq@Y#q2vDxu?YwRsL1 z<{QFF{GCDFHqSRkAe=g*ZMWZIfpf2XQ%V4(K4syHRK^5gj7y$Xe2c7^9pFDSzV43U zqW#-iL=$3?E-0$srdO}Y%^6{l>T1#s85`;kzg#n1F09SYNmWqxkS_w7MRxVJqCl;H z(Thzvn%j94G#Jo?G#d#1FnKG2f^- zLK`G;57K(7Qvzu2F+nLf%*(KM+Nqls>>nAmph$b2cIDD)G&%+JNLsZ;YEJH!XO{9V6rIv)epRK> zsDpe$Omjx7=`<+D1ln zhq+-&+FZj~0n1R|NMM9F%QW|`e@KiGzQXeTWO2j*Cbb;V*c36EX}OAnyAh+rBFms2 z^^nNX_SLdTPq8Q^pyCKBtdI0!nYr)GA52a}BB66V%Du_=kzN9Z^osJqbFitBgs66@ zgkm}4sHKzii8d+ZFcuSm4(mncP|_GZ`1OqG0>6!1hz^olz^Kgo)x57~lSC82%5&Sb z>13!Ta`Z%=%lE=)-_UDw9QE(f9du`DwfRx=uat=NYmqF|#-Ff5PJ2ArsQC%qBtwGb zmO+(WJ#7Zn$hjdIef!f4YqNWDZ1*%7N+1VOOo%BI7S@tIF`0O`8}OHmlf7aGsRq6X z>80Yh*i^4UB>_1@j0&{}y*$;PDR{yDN$W`L1nchlJmdIociX?xMW$N5HtqL6YtfS7 zgL_J-VD~f28?GOVXOjG)BEx-%Z`lZmoKd@e|*f>h{0x+x?;1wBC)=GCB)l zNL5^K)t~*^8h1zB^EAQeRt_y^B}EspNPETS_ZzPpS^u{;V^3DcAChq^0}Bo{->bW| zCYNLmOYrr>>*-Z*tCaJKywKOZjrR4P9{9c(Hb3f?o3@)ZrVCB0_)goUso#*K;ipwDv>g~5cuuSCd53t6 z7}rk?5qR;cX|J9UpQWNPpkMgEa~Me~M`-$L`1Ak!CZQI{nGx%~)b@wgYa4nEe=Dz> z=M2dZ%F7JN#5!`gR6@0M1=s=3jtsXhf3fEce5dW!cCB_|)q_T1=IV^^mJTxQ)N70l zG+OO-lfeGcvDN5z(X8{&v{THFCiiXZqW5!lYr(zgDr!4Fm%dG2R7z}qE@hm(Qp|fw zqKP^2sUVDGC%K7eS}{e7k`}poys7+%c+{8yQ{S|bE?QVs($nwAtWo{@fchotweEBQ z5gdsaCXx-KR;6ZB?`XBt=xFUy&t7*y+Ku#>^VdC{zWD5KyR82&t)@F(zUyfFPW4Y$ zRqW`w7RyJs* Close - + 关闭 @@ -16,7 +16,7 @@ Reboot and Update - 重启和更新 + 重启并更新 @@ -24,17 +24,17 @@ Back - 后退 + 返回 Enable Tethering - 启用网络共享 + 启用WiFi热点 Tethering Password - 网络共享密码 + WiFi热点密码 @@ -45,7 +45,7 @@ Enter new tethering password - 输入新的网络共享密码 + 输入新的WiFi热点密码 @@ -55,22 +55,22 @@ Enable Roaming - 启用漫游 + 启用数据漫游 APN Setting - APN 设置 + APN设置 Enter APN - 输入 APN + 输入APN leave blank for automatic configuration - 为自动配置留空 + 留空以自动配置 @@ -92,17 +92,17 @@ You must accept the Terms and Conditions in order to use openpilot. - 您必须接受条款和条件才能使用 openpilot。 + 您必须接受条款和条件以使用openpilot。 Back - 后退 + 返回 Decline, uninstall %1 - 拒绝,卸载 %1 + 拒绝并卸载%1 @@ -110,37 +110,37 @@ Dongle ID - 加密狗 ID + 设备ID(Dongle ID) N/A - 不适用 + N/A Serial - 串行 + 序列号 Driver Camera - 司机摄像头 + 驾驶员摄像头 PREVIEW - 预习 + 预览 Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off) - 预览面向驾驶员的摄像头,以帮助优化设备安装位置以获得最佳驾驶员监控体验。 (车辆必须关闭) + 打开并预览驾驶员摄像头,用于调整安装角度以获得最优驾驶员监控体验。仅熄火时可用。 Reset Calibration - 重置校准 + 重置设备校准 @@ -150,32 +150,32 @@ Are you sure you want to reset calibration? - 您确定要重置校准吗? + 您确定要重置设备校准吗? Review Training Guide - 查看培训指南 + 新手指南 REVIEW - 重新查看 + 查看 Review the rules, features, and limitations of openpilot - 查看 openpilot 的规则、功能和限制 + 查看openpilot的使用规则,以及其功能和限制。 Are you sure you want to review the training guide? - 您确定要查看培训指南吗? + 您确定要查看新手指南吗? Regulatory - 监管 + 监管信息 @@ -210,32 +210,32 @@ openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. - openpilot 要求设备安装在左或右 4° 以内,上 5° 或下 8° 以内。 openpilot 会持续校准,很少需要重置。 + openpilot要求设备安装的偏航角在左4°和右4°之间,俯仰角在上5°和下8°之间。一般来说,openpilot会持续更新校准,很少需要重置。 Your device is pointed %1° %2 and %3° %4. - 您的设备指向 %1° %2 和 %3° %4。 + 您的设备校准为%1° %2、%3° %4。 down - + 朝下 up - 向上 + 朝上 left - 向左 + 朝左 right - 向右 + 朝右 @@ -245,17 +245,17 @@ Disengage to Reboot - 脱离以重新启动 + 取消openpilot以重新启动 Are you sure you want to power off? - 您确定要关闭电源吗? + 您确定要关机吗? Disengage to Power Off - 脱离以关闭电源 + 取消openpilot以关机 @@ -263,7 +263,7 @@ Drives - 驱动器 + 旅程数 @@ -278,12 +278,12 @@ PAST WEEK - 上周 + 过去一周 KM - 千米 + 公里 @@ -296,7 +296,7 @@ camera starting - 相机启动中 + 正在启动相机 @@ -309,12 +309,12 @@ Need at least - 需要至少 + 至少需要 characters! - 字符! + 个字符! @@ -322,7 +322,7 @@ Installing... - 安装... + 正在安装…… @@ -332,12 +332,12 @@ Resolving deltas: - 解决增量: + 正在处理: Updating files: - 更新文件: + 正在更新文件: @@ -401,12 +401,12 @@ CLEAR - CLEAR + 清空 Recent Destinations - 近期目的地 + 最近目的地 @@ -417,27 +417,25 @@ Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai - 使用逗号获取显示的详细路线和更多信息 -主要订阅。 立即注册:https://connect.comma.ai + 订阅comma prime以获取导航。 +立即注册:https://connect.comma.ai No home location set - 没有家 -位置集 + 家:未设定 No work location set - 没有工作 -位置集 + 工作:未设定 no recent destinations - 没有最近的目的地 + 无最近目的地 @@ -445,7 +443,7 @@ location set Map Loading - 地图加载 + 地图加载中 @@ -471,23 +469,23 @@ location set Advanced - 先进的 + 高级 Enter password - 先进的 + 输入密码 for " - 为了 " + 网络名称:" Wrong password - Wrong password + 密码错误 @@ -495,30 +493,30 @@ location set km/h - 公里/小时 + km/h mph - 英里/小时 + mph MAX - 最大限度 + 最高定速 SPEED - 速度 + SPEED LIMIT - 限制 + LIMIT @@ -544,7 +542,7 @@ location set Pair your device to your comma account - 将您的设备与您的逗号账户配对 + 将您的设备与comma账号配对 @@ -574,12 +572,12 @@ location set Become a comma prime member at connect.comma.ai - 成为 connect.comma.ai 的逗号主要会员 + 打开connect.comma.ai以注册comma prime会员 PRIME FEATURES: - 主要特点: + comma prime特权: @@ -589,7 +587,7 @@ location set 1 year of storage - 1年存储 + 1年数据存储 @@ -602,12 +600,12 @@ location set ✓ SUBSCRIBED - ✓ 订阅 + ✓ 已订阅 comma prime - 逗号素数 + comma prime @@ -617,7 +615,7 @@ location set COMMA POINTS - 逗号分 + COMMA POINTS点数 @@ -635,7 +633,7 @@ location set dashcam - 行车记录器 + 行车记录仪 @@ -673,17 +671,17 @@ location set Resetting device... - 正在重置设备... + 正在重置设备…… System Reset - 系统重置 + 恢复出厂设置 System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. - 触发系统重置。 按确认删除所有内容和设置。 按取消恢复启动。 + 已触发系统重置:确认以删除所有内容和设置。取消以正常启动设备。 @@ -703,7 +701,7 @@ location set Unable to mount data partition. Press confirm to reset your device. - 无法挂载数据分区。 按确认重置您的设备。 + 无法挂载数据分区。 确认以重置您的设备。 @@ -735,7 +733,7 @@ location set Toggles - 切换 + 设定 @@ -758,7 +756,7 @@ location set Power your device in a car with a harness or proceed at your own risk. - 使用安全带在汽车中为您的设备供电或自行承担风险。 + 请使用car harness线束为您的设备供电,或自行承担风险。 @@ -775,28 +773,28 @@ location set Getting Started - 入门 + 开始设置 Before we get on the road, let’s finish installation and cover some details. - 在我们上路之前,让我们完成安装并介绍一些细节。 + 开始旅程之前,让我们完成安装并介绍一些细节。 Connect to Wi-Fi - 连接到无线网络 + 连接到WiFi Back - 后退 + 返回 Continue without Wi-Fi - 在没有 Wi-Fi 的情况下继续 + 不连接WiFi并继续 @@ -811,12 +809,12 @@ location set Dashcam - 行车记录器 + Dashcam(行车记录仪) Custom Software - 定制的软件 + 自定义软件 @@ -826,12 +824,12 @@ location set for Custom Software - 定制软件 + 以下载自定义软件 Downloading... - 正在下载... + 正在下载…… @@ -841,7 +839,7 @@ location set Ensure the entered URL is valid, and the device’s internet connection is good. - 确保输入的 URL 有效,并且设备的互联网连接良好。 + 请确保互联网连接良好且输入的URL有效。 @@ -864,7 +862,7 @@ location set Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. - 将您的设备与 comma connect (connect.comma.ai) 配对并领取您的 comma prime 优惠。 + 将您的设备与comma connect(connect.comma.ai)配对并领取您的comma prime优惠。 @@ -878,7 +876,7 @@ location set CONNECT - 连接 + CONNECT @@ -889,49 +887,49 @@ location set ONLINE - 在线的 + 在线 ERROR - 错误 + 连接出错 TEMP - 温度 + 设备温度 HIGH - 高的 + 过热 GOOD - 好的 + 良好 OK - 好的 + 一般 VEHICLE - 车辆 + 车辆连接 NO - 未连接 + PANDA - 熊猫 + PANDA @@ -941,7 +939,7 @@ location set SEARCH - 搜索 + 搜索中 @@ -956,7 +954,7 @@ location set ETH - 以太網 + 以太网 @@ -984,32 +982,32 @@ location set Git Branch - Git 分支 + Git Branch Git Commit - Git 提交 + Git Commit OS Version - 操作系统版本 + 系统版本 Version - 版本 + 软件版本 Last Update Check - 最后更新检查 + 上次检查更新 The last time openpilot successfully checked for an update. The updater only runs while the car is off. - 上次 openpilot 成功检查更新的时间。 更新程序仅在汽车关闭时运行。 + 上一次成功检查更新的时间。更新程序仅在汽车熄火时运行。 @@ -1019,7 +1017,7 @@ location set CHECKING - 正在检查 + 正在检查更新 @@ -1039,7 +1037,7 @@ location set failed to fetch update - 未能获取更新 + 获取更新失败 @@ -1053,12 +1051,12 @@ location set SSH Keys - SSH 密钥 + SSH密钥 Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. - 警告:这将授予对 GitHub 设置中所有公钥的 SSH 访问权限。 切勿输入您自己以外的 GitHub 用户名。 逗号员工永远不会要求您添加他们的 GitHub 用户名。 + 警告:这将授予SSH访问权限给您GitHub设置中的所有公钥。切勿输入您自己以外的GitHub用户名。comma员工永远不会要求您添加他们的GitHub用户名。 @@ -1069,7 +1067,7 @@ location set Enter your GitHub username - 输入你的 GitHub 用户名 + 输入您的GitHub用户名 @@ -1079,12 +1077,12 @@ location set REMOVE - 消除 + 删除 Username '%1' has no keys on GitHub - 用户名“%1”在 GitHub 上没有密钥 + 用户名“%1”在GitHub上没有密钥 @@ -1094,7 +1092,7 @@ location set Username '%1' doesn't exist on GitHub - GitHub 上不存在用户名“%1” + GitHub上不存在用户名“%1” @@ -1102,7 +1100,7 @@ location set Enable SSH - 启用 SSH + 启用SSH @@ -1120,7 +1118,7 @@ location set Scroll to accept - 滑动接受 + 滑动以接受 @@ -1133,12 +1131,12 @@ location set Enable openpilot - 启用 openpilot + 启用openpilot Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. - 使用 openpilot 系统进行自适应巡航控制和车道保持驾驶员辅助。 任何时候都需要您注意使用此功能。 更改此设置在汽车断电时生效。 + 使用openpilot进行自适应巡航和车道保持辅助。使用此功能时您必须时刻保持注意力。该设置的更改在熄火时生效。 @@ -1148,7 +1146,7 @@ location set Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). - 当您的车辆在以超过 31 英里/小时(50 公里/小时)的速度行驶时在检测到的车道线上漂移而没有激活转向信号时,接收提醒以返回车道。 + 车速超过31mph(50km/h)时,若检测到车辆越过车道线且未打转向灯,系统将发出警告以提醒您返回车道。 @@ -1158,57 +1156,57 @@ location set Allow openpilot to obey left-hand traffic conventions and perform driver monitoring on right driver seat. - 允许 openpilot 遵守左侧交通惯例并在右侧驾驶座上执行驾驶员监控。 + 允许openpilot遵守左侧交通惯例并在右侧驾驶座上执行驾驶员监控。 Use Metric System - 使用公制 + 使用公制单位 Display speed in km/h instead of mph. - 以公里/小时而不是英里/小时显示速度。 + 显示车速时,以km/h代替mph。 Record and Upload Driver Camera - 记录和上传司机摄像头 + 录制并上传驾驶员摄像头 Upload data from the driver facing camera and help improve the driver monitoring algorithm. - 从面向驾驶员的摄像头上传数据,帮助改进驾驶员监控算法。 + 上传驾驶员摄像头的数据,帮助改进驾驶员监控算法。 Disengage On Accelerator Pedal - 踩油门解除 + 踩油门时取消控制 When enabled, pressing the accelerator pedal will disengage openpilot. - 启用后,踩下油门踏板将解除 openpilot。 + 启用后,踩下油门踏板将取消openpilot。 Show ETA in 24h format - 以 24 小时格式显示 ETA + 以24小时格式显示预计到达时间 Use 24h format instead of am/pm - 使用 24 小时制代替上午/下午 + 使用24小时制代替am/pm openpilot Longitudinal Control - openpilot 纵向控制 + openpilot纵向控制 openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! - openpilot 将禁用汽车的雷达并接管油门和刹车的控制。 警告:这会禁用 AEB! + openpilot将禁用车辆的雷达并接管油门和刹车的控制。警告:AEB将被禁用! @@ -1221,12 +1219,12 @@ location set An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. - 需要操作系统更新。 将您的设备连接到 Wi-Fi,以获得最快的更新体验。 下载大小约为 1GB。 + 操作系统需要更新。请将您的设备连接到WiFi以获取更快的更新体验。下载大小约为1GB。 Connect to Wi-Fi - 连接到无线网络 + 连接到WiFi @@ -1236,12 +1234,12 @@ location set Back - 后退 + 返回 Loading... - 正在加载... + 正在加载…… @@ -1260,12 +1258,12 @@ location set Scanning for networks... - 正在扫描网络... + 正在扫描网络…… CONNECTING... - 正在连接... + 正在连接…… @@ -1275,7 +1273,7 @@ location set Forget Wi-Fi Network " - 忘记 Wi-Fi 网络" + 忘记WiFi网络" From c181d475c52798462c5b2a2cf2237eebde0fa26d Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Mon, 11 Jul 2022 13:41:55 -0700 Subject: [PATCH 271/302] fix a translation line break --- selfdrive/ui/translations/main_zh-CHS.ts | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 9dade34701..9ac35994e6 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -862,7 +862,7 @@ location set Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. - 将您的设备与comma connect(connect.comma.ai)配对并领取您的comma prime优惠。 + 将您的设备与comma connect (connect.comma.ai)配对并领取您的comma prime优惠。 From 30d88d6892f11bf2472d97d79e9f68bef9e01b3c Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Mon, 11 Jul 2022 13:45:45 -0700 Subject: [PATCH 272/302] update main_zh-CHS.qm --- selfdrive/ui/translations/main_zh-CHS.qm | Bin 18507 -> 18509 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/selfdrive/ui/translations/main_zh-CHS.qm b/selfdrive/ui/translations/main_zh-CHS.qm index 59487d263a7a7524f15a239bb7ace144137f31b0..63c17d76b7f0f99e5180d400a8143d17cbbdde55 100644 GIT binary patch delta 774 zcmWksX-HI27(MsBcW0XEIpYvI_@l;sGM5=e)U?43T&AKlHOUMy(XteROpQ=%0jUh- zDu$4#n6_DCIDeEEx89xuK{Nx{fqKS%hOQVeO~V<}hX0?lI)zw9 z(ZtM|ZsbUlWF;3l#SO%*LtcL`psPlHW-H*GfJ3*=0f|{Cd_Dz)2cn|HAMhGR&H5VP zaTMLtGeAyn{wkt;wOZM#_Z!(2U`-U)oyjF%Rqf)tM5J%Mr;U&#>UQy z3Qep|YlvG6qa5GGfX2#_#k|I1G8w(UZqRmSj2TPhD6(B}t;Ku9xUk$w&3-d3rrig2 b1sn&Gw+zK=Plm8FqTe1Y!FR}IuQUGxC?Cv+ delta 771 zcmWlXZAep59LAq>?>)1vyUl%=!wpD3Huh zj*s>j1(c*!|^D;7EvwlERZ>_M}W*J(<0d&ihj&*H7ueXDx7` zS9)=W%wj90>72WO@uu{tfMh{Y(#l*Z5IrTjB&+R&+)zO3gtPKvLjy(B%VQJyH2qti z95a(!yYNX_Y*v_Md!SnxTB{^woAP9dmJOa!o?oVQQmaIfY){+b`p&CBqK{`7!pNzZ zmt3Im@#VZ)Hw~y-UK9EVh^gf@qaG?@fVczfJH%V6nrYr6rer%C5#MDi3ldzho6P*r zE;%?|8p&2jH7yFaVqrH#k>WJ@{GMI;21vzzo2P~-L#OCdtn91sDhVu4Y|z}I;M~dv zL>SKs+|fPsmDBy$)s1%a(lpaex;P!*u(-wT+Q$7MujyhWn1z=+9kOa0qrZmxt5NP2 z%DJs(W_$$PMm0CF3`h!9^U`Ubq-mkoSOR_OSWgPII;hSK7^ts&b>Ry!`mbY zX%e*DkhmI2du)nPjh&^4WsTKjGzR?GqtjV1X0K7Am_EV%tN|0omGy_z?3Qsg^C@uD Yb_qx`jVJllI#|8%xWdPmT-PlB0NsGh%m4rY From bdfaa1d1eee77d1f9fb5b9b2632c9988caba02e3 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Mon, 11 Jul 2022 15:19:55 -0700 Subject: [PATCH 273/302] Ram 1500 torque tune (#25117) * torque control again * 3mss per s * no bad sensors * tweaks * Need more checks before we can do this * update refs * only ram for now Co-authored-by: Adeeb Shihadeh --- panda | 2 +- selfdrive/car/chrysler/carcontroller.py | 7 ++++--- selfdrive/car/chrysler/interface.py | 6 +++--- selfdrive/car/chrysler/values.py | 14 ++++++++++---- selfdrive/car/interfaces.py | 4 ++-- selfdrive/car/torque_data/override.yaml | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 7 files changed, 22 insertions(+), 15 deletions(-) diff --git a/panda b/panda index ca927fe931..baecd2ecc6 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit ca927fe9312651a16f13aaddca8b46af5315ede6 +Subproject commit baecd2ecc6a2a608e1305601f6f697feca69fe88 diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py index e0eb979e6a..a7f2d007f1 100644 --- a/selfdrive/car/chrysler/carcontroller.py +++ b/selfdrive/car/chrysler/carcontroller.py @@ -16,6 +16,7 @@ class CarController: self.lkas_active_prev = False self.packer = CANPacker(dbc_name) + self.params = CarControllerParams(CP) def update(self, CC, CS, low_speed_alert): can_sends = [] @@ -40,8 +41,8 @@ class CarController: # steering if self.frame % 2 == 0: # steer torque - new_steer = int(round(CC.actuators.steer * CarControllerParams.STEER_MAX)) - apply_steer = apply_toyota_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, CarControllerParams) + new_steer = int(round(CC.actuators.steer * self.params.STEER_MAX)) + apply_steer = apply_toyota_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, self.params) if not lkas_active: apply_steer = 0 self.steer_rate_limited = new_steer != apply_steer @@ -56,6 +57,6 @@ class CarController: self.lkas_active_prev = lkas_active new_actuators = CC.actuators.copy() - new_actuators.steer = self.apply_steer_last / CarControllerParams.STEER_MAX + new_actuators.steer = self.apply_steer_last / self.params.STEER_MAX return new_actuators, can_sends diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 697fb9b83a..8826a92523 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -46,15 +46,15 @@ class CarInterface(CarInterfaceBase): # Ram elif candidate == CAR.RAM_1500: + ret.steerActuatorDelay = 0.2 + ret.wheelbase = 3.88 ret.steerRatio = 16.3 ret.mass = 2493. + STD_CARGO_KG ret.maxLateralAccel = 2.4 ret.minSteerSpeed = 14.5 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.1], [0.02]] - ret.lateralTuning.pid.kf = 0.00003 else: raise ValueError(f"Unsupported car: {candidate}") diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index ada4f486fc..f7531792fb 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -26,10 +26,16 @@ class CAR: class CarControllerParams: - STEER_MAX = 261 # higher than this faults the EPS on Chrysler/Jeep. Ram DT allows more - STEER_DELTA_UP = 3 - STEER_DELTA_DOWN = 3 - STEER_ERROR_MAX = 80 + def __init__(self, CP): + self.STEER_MAX = 261 # higher than this faults the EPS on Chrysler/Jeep. Ram DT allows more + self.STEER_ERROR_MAX = 80 + + if CP.carFingerprint in RAM_CARS: + self.STEER_DELTA_UP = 5 + self.STEER_DELTA_DOWN = 5 + else: + self.STEER_DELTA_UP = 3 + self.STEER_DELTA_DOWN = 3 STEER_THRESHOLD = 120 diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 136337c5a4..4c7ea97dff 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -135,11 +135,11 @@ class CarInterfaceBase(ABC): return ret @staticmethod - def configure_torque_tune(candidate, tune, steering_angle_deadzone_deg=0.0): + def configure_torque_tune(candidate, tune, steering_angle_deadzone_deg=0.0, use_steering_angle=True): params = get_torque_params(candidate) tune.init('torque') - tune.torque.useSteeringAngle = True + tune.torque.useSteeringAngle = use_steering_angle tune.torque.kp = 1.0 / params['LAT_ACCEL_FACTOR'] tune.torque.kf = 1.0 / params['LAT_ACCEL_FACTOR'] tune.torque.ki = 0.1 / params['LAT_ACCEL_FACTOR'] diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index 476313df2b..8e6f62c4e7 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -21,7 +21,7 @@ COMMA BODY: [.nan, 1000, .nan] # Totally new cars KIA EV6 2022: [3.5, 2.5, 0.0] -RAM 1500 5TH GEN: [2.0, 2.0, 0.05] +RAM 1500 5TH GEN: [2.0, 2.0, 0.0] # Dashcam or fallback configured as ideal car mock: [10.0, 10, 0.0] diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 65ecbb4be3..fc5f83c32a 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -825acfae98543c915c18d3b19a9c5d2503e431a6 \ No newline at end of file +d583bbd9643000e7f817171c583d31ae3141a652 \ No newline at end of file From 903bb405286295b48d5192cb2a7b2c01029193e3 Mon Sep 17 00:00:00 2001 From: Lee Jong Mun <43285072+crwusiz@users.noreply.github.com> Date: Tue, 12 Jul 2022 08:51:03 +0900 Subject: [PATCH 274/302] Improve Korean translations (#25105) * kor translations fix update_translations --release qm * space * qm * map setting tr space remove * ts update fix ko_update ch_update * qm release * Update QM * Fix this translation Co-authored-by: Shane Smiskol --- selfdrive/ui/qt/maps/map_settings.cc | 2 +- selfdrive/ui/translations/main_ko.qm | Bin 19997 -> 20040 bytes selfdrive/ui/translations/main_ko.ts | 96 +++++++++++------------ selfdrive/ui/translations/main_zh-CHS.qm | Bin 18509 -> 18508 bytes selfdrive/ui/translations/main_zh-CHS.ts | 2 +- selfdrive/ui/translations/main_zh-CHT.qm | Bin 18569 -> 18568 bytes selfdrive/ui/translations/main_zh-CHT.ts | 7 +- 7 files changed, 51 insertions(+), 56 deletions(-) diff --git a/selfdrive/ui/qt/maps/map_settings.cc b/selfdrive/ui/qt/maps/map_settings.cc index eaa8b1f703..d143b44e70 100644 --- a/selfdrive/ui/qt/maps/map_settings.cc +++ b/selfdrive/ui/qt/maps/map_settings.cc @@ -104,7 +104,7 @@ MapPanel::MapPanel(QWidget* parent) : QWidget(parent) { screenshot->setPixmap(pm.scaledToWidth(1080, Qt::SmoothTransformation)); no_prime_layout->addWidget(screenshot, 0, Qt::AlignHCenter); - QLabel *signup = new QLabel(tr("Get turn-by-turn directions displayed and more with a comma \nprime subscription. Sign up now: https://connect.comma.ai")); + QLabel *signup = new QLabel(tr("Get turn-by-turn directions displayed and more with a comma\nprime subscription. Sign up now: https://connect.comma.ai")); signup->setStyleSheet(R"(font-size: 45px; color: white; font-weight:300;)"); signup->setAlignment(Qt::AlignCenter); diff --git a/selfdrive/ui/translations/main_ko.qm b/selfdrive/ui/translations/main_ko.qm index 60966cdde587ebf4a43deb8ad255f374d32ca7c8..c5c66d1e73491c2ff09d91b6fdd5200002b2a6da 100644 GIT binary patch delta 2731 zcmYLJX;c(v7Jb!S)l2opt_J}NnpG4;!61vQf`Y~+XgCT<#?c^(xCEn~s3hYCijGT zc6t;x5h(_UMlB^$<^XpAR{CuOAd1YQN!oct&K{IDZZC)+uT_bN??uz{L@1g`)BoOE zh>Xf;=DL64Km}zeu4AE`GUk1Ti+9oN6J9*q12i856Oi z5Va03XJ%M}u+YOC=)^+oVdiEA6c`f5+*KSW8lJ#B9=nmqQ={N>;FsW5h2O&-qKI5Y z3SR&vK2~HoAmi|vibEZ!`|x7Lr4kT}XjfdDyo1Q$f#UWI#1(uLUCr=J*fmA>5m&@p zu4D^Ch7h^-DLsEg&4za=eYV9RvpLF@GY~lX56aUtWny%3Ds)iI^SA7c0vla4A~VeyZq0|QaiEs_B;1Inv!2`bIf(ETcJv-?N1r@9 zPF%;827{Q}cCPe~@QQvhSGIW*l(@y6wRS_fHC)4hFO;j~u6yGpITR*x_qxEy?;GyB z4bAYtMmr`y;a(1a;h1QZ!aD<|D_0r&Lm=U9Rm|fQNSLomt-4AS7p9uapd#YD3Tyv<|A5(>h_o*=nC4C>9*6E_dGmPeiKE=6?qQE7binkKz5NtWZCH0%?>_ z)vu!a-~m>X6x4{u^IVgr1Y<{6&4Pctg2cBq+gBbS@+#8&=`;elI%qCDG-I5uRU6)i zx!%*7OEq{!f!c&$a*!FLot54Tq7B;F8=zdub?w|NC>^BJ&bK6jkV(6PhT#2^r0ux( zHq6$d?Q%pHRGImNV01dwZhn4SD>6>yiyxy?d1nG+i2|4K+xkox*YSJapvHlv{QlbG zAasl`y*mr$)$oT~QFAteuPoXF$a}%G?R=wK4DJuI@{fLB z0O_K2%*FLMkghY=HGxo!F6BWn%(PyY-GheVuhuQU&4T#`-De-WKthAg@*_$#Vz$mU z6^glC)w|SzK$u?dU4{9;+xk(lYv7f;`jjNpIx%0L7MV>np+%pb2qof{>SymQL_qIi z{gSt3X07^tFW*H5_w`k~@C=2|_02~h-PqIm8~1=?IQ=~f2(o`OsLFkD;ZsAX=Uxh$RlwL+hDM(+Vd5@BVbY!k=^K2W7CZ3C6Lgi)wn!yBHSEkEIx=nFj6oc>WfE>PZ>{@ z;iB;&#;ecZ39lC8&GG@ z<8nO-*OF_gw&+ge<+UVOH`VxcX4Xeq_J|*9Eq=b%ozl1UzBX5DG6|iTHNIC0NT~Q% zZJ0HtCX0mX>4Q5{`P3W^i2>)(~Z!!U1m zP_TH?kRp$MHmp_iO*Ku`IK0Bx!7!y_s>39ee9oFFiVh(zO+Qtfv&JK0fz6|OXj8Sd zsHs|NclbBMj1ya&%u1owB=$SyI6KKvWEtv(wyyum@V@g_wW=xk(*Bw(@u{;}tFe{b z^p?{X-CWGfO)<*F%SoOh;i5y;9uh3)upBQgatTyeDotF(EDN$%OqTJfm6i^|g0nb~k({K|c#*zX?4tQ13sMN5l^4QCXW z*NP<`2?nRutjgCUTsdiDn(L&y9!5sTS9G7zB4t!r`oXi=#LCr{YDWD|spjQLsOlbO zR{S;)6UT7vsnJt zRQAp+>uTxQTXPugW|@gxaB+IPo49&_PUYKP}Y`LGv8iO>1o`T%%~7r0!J=H z4%E;M*Dl65loraauHP;-$|mT@YPfGNf%KPzvkLb7nmZX{esa3EKaHVqq{otQ$F-r$ d{ubn-STr_Qd0y&BmNbkY7ESfUf7#SE{{dW0I-~#q delta 2737 zcmZuzX;c(v7Jb!S)l2n;$R=yCi3qZUhGCH?JMLo8Aqt~|7}Thv8BmNU$*2Rk=ad=~ z(YS!i*r=gE!Jq>jpuxCcfT#yh#wBW^CdSEVRAg?;oH_Gje$=^D-}1iu?z`{nZY^W> zlrh^}iw+XW`iVv*6UlRd^MNaX8-SkzO++l_4cSCoFj3GIU<^^PJ8%}(6c3`$b0Wnr zL_=DLly1O#z$hYH6|jLwe}+hFAsX(CrxWAji2Sgw$aXnitP3v^C9NYeYKX>{;2UD6byG z;czK3_$meHaKJUUr>?-C`IuvkpV6MsF50Bx@gRpf(u8(AVZZlDUN#=X^7EySr zESb-P60>BPHpti*D%;bk#`-0))0;pnyk2&0+!i96dRa#r;tEPxZyP)lxmd1=Dr^ipEpPH$ z1LHoHU$%Wl#B7m2&#!>M0c_HPFA*<_opV?Mv0`??I1CS2$gaHgHj&p&wlEt+l^k2l zJ|&87VvBZ-tA~qcuy4>NV-Ouu2hmH#mX*WVq2BC)J2}8C)^vFXk*_CP{eC%7vcT49 zttB(C-+bSV@%8LCKRhNHI-I>VrW&SIa(o0zk&wgbHZFs*E?k1%7o{D`Wz0dTqGuFw zx%@ep=q0z%2N@WTa|^9zU(+aRz|`O~xm=>Oz#%3rSygJjvt zXFot9d5`jC3@#7%2dV`BCbY{X)p$9W+dNgxd-M`g*Qhq}mdxvllA!uW_~jJ7Y%? z0(vgdE}m>5;`az3X{$a#8w#tmZTlcu*aq!|ZeVDSwz~zy*iN0I!UqR-=z`s@ zB7rHosQyy)^A2655%WGNy3;FwvES;Nybi&{UAm@t;7FD3{AhSV6RYdYKzllHdi$cI z6_{w$I~OB!yOnyc=LwLgS0CAjn<~s-KVcK3vpb_-7M}z+JLyYz;~oeY(C@i77M}Qv z{%_?tC~AoQ?7!dz_mlcdW82~OTL#t7xItC%2D>=4cQj*g`2ICfgwc?C2l0$o4NG$G zLLrSIaND)@sQm|q&*m+GRL>26U;2tD?!2M*{$5Bv+0d7K9N#Vr;GEl1v~q~d#krxC zgew!J^twh8&L!4UeaUx`Bv{th`ie``EiTTMZPIlTDi<||S`snNcI8>uwOpv4BfiUb z46!jSZB-3u8!B5}Ng!Ve6~}0d-czf7Gxu4>l2Gqd-DB<{p?P&BHMf%>UAJU(d)9^$dzd5aIVM(uzH8UYT* zBZ!RNMNHAfTIb#T{lycyWb5lQT_LAxu5GTCKGb(I%uaENP3mB*JvKo$|I4T9$L2)o zrp<2*V-&C3dNYCIfNie&&E7_#y;od0bOXmWC!XFV@^;=F+fsP`tQcYE&0G*?+PT|W zKk-XsQ?;Fh7N5ETOm46nAywPOFiORL2AV#O4P;Yvm8 ztFBVBlk|auo>8kv_$tz}ZGaI)$LSjF#mvS{By=UVY?mH6Ix%c>dwYYV9+t*vcuJs& zltghfO`PqV<+0APtueAIlLXV*+RWzElht*FBz!mBQqYxQ?y2<=uQ~_vZKdX(>L;~X z1J2@OA%y?0g3HAOml#Hn*0^{uGE1WPg=?I~=3-{$tHEf}BUe4cv8KM`YDwYVW?(O6 z)D=n{qy8voSScpdTgIsxeJ*8)^TL7|g|s_ND`QP(O?~3A@NV&NxK0uy6pXFa6ILpw zedd~~*5ec3)N(0n`l!Jqc|^`+xGk2vR#sdS<$xp`UB#VI9%^J`Rmrkmtc|+DS|f;? zqXXW&NcGV_GL9iuzgV`xD|vP6;5a|4=g3bKV!g$#(b1zK{{K8yrqBY)qg2YLY^xL7 z%S|MO#GaAqwC3{mMYTB)y|v}2q#1jN@f$&lX(`RezcQgYvFZYLzmJh%nqLcojhm$= z5;`-@J<^T16EYaAHcR{@ae|9LZ;{bTA7!vN_gY3 Enter new tethering password - 새 테더링 비밀번호 입력 + 새 테더링 비밀번호를 입력하세요 @@ -70,7 +70,7 @@ leave blank for automatic configuration - 자동 구성을 위해 비워둠 + 자동설정을 하려면 공백으로 두세요 @@ -92,7 +92,7 @@ You must accept the Terms and Conditions in order to use openpilot. - 당신은 반드시 약관에 동의해야만 openpilot을 사용할 수 있습니다. + openpilot을 사용하려면 이용 약관에 동의해야 합니다. @@ -102,7 +102,7 @@ Decline, uninstall %1 - 거절,삭제 %1 + 거절, %1 제거 @@ -135,7 +135,7 @@ Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off) - 운전자 카메라를 미리 보면서 최적의 운전자 모니터링 경험을 위해 기기 장착 위치를 최적화할수 있습니다. (차량은 반드시 닫아야 합니다) + 운전자 카메라를 미리 보면서 최적의 운전자 모니터링 경험을 위해 장치의 장착 위치를 최적화할수 있습니다. (차량연결은 해제되어있어야 합니다) @@ -150,7 +150,7 @@ Are you sure you want to reset calibration? - 캘리브레이션을 재설정하시겠습니까? + 캘리브레이션을 재설정하시겠습니까? @@ -165,12 +165,12 @@ Review the rules, features, and limitations of openpilot - openpilot의 규칙, 기능, 제한 다시보기 + openpilot의 규칙, 기능 및 제한 다시보기 Are you sure you want to review the training guide? - 트레이닝 가이드를 다시보시겠습니까? + 트레이닝 가이드를 다시보시겠습니까? @@ -185,7 +185,7 @@ Change Language - 언어변경 + 언어 변경 @@ -195,7 +195,7 @@ Select a language - 언어선택 + 언어를 선택하세요 @@ -210,37 +210,37 @@ openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. - openpilot은 장치를 왼쪽 또는 오른쪽 4° 이내, 위쪽 5° 또는 아래쪽 8° 이내로 설치해야 합니다. openpilot은 지속적으로 보정되므로 리셋이 거의 필요하지 않습니다. + openpilot은 장치를 좌측 또는 우측은 4° 이내, 위쪽 5° 또는 아래쪽은 8° 이내로 설치해야 합니다. openpilot은 지속적으로 보정되므로 리셋이 거의 필요하지 않습니다. Your device is pointed %1° %2 and %3° %4. - 사용자의 기기가 %1° %2 및 %3° %4를 가리키고 있습니다. + 사용자의 장치가 %1° %2 및 %3° %4를 가리키고 있습니다. down - 아래 + 아래로 up - + 위로 left - 왼쪽 + 좌측으로 right - 오른쪽 + 우측으로 Are you sure you want to reboot? - 재부팅 하시겠습니까? + 재부팅 하시겠습니까? @@ -250,7 +250,7 @@ Are you sure you want to power off? - 전원을 종료하시겠습니까? + 전원을 종료하시겠습니까? @@ -263,7 +263,7 @@ Drives - 주행수 + 주행 @@ -273,7 +273,7 @@ ALL TIME - 전체 시간 + 전체 @@ -309,12 +309,12 @@ Need at least - 최소 필요 + 최소 characters! - 문자! + 자가 필요합니다! @@ -345,7 +345,7 @@ eta - 에타 + 도착 @@ -401,7 +401,7 @@ CLEAR - CLEAR + 삭제 @@ -411,14 +411,14 @@ Try the Navigation Beta - 네비게이션(베타)을 사용해보세요 + 네비게이션(베타)를 사용해보세요 - Get turn-by-turn directions displayed and more with a comma + Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai - 자세한 경로안내를 확인하시려면 comma prime을 구독하세요. -즉시등록:https://connect.comma.ai + 자세한 경로안내를 원하시면 comma prime을 구독하세요. +등록:https://connect.comma.ai @@ -437,7 +437,7 @@ location set no recent destinations - 최근 경로 없음 + 최근 목적지 없음 @@ -471,7 +471,7 @@ location set Advanced - 고급 + 고급 설정 @@ -775,12 +775,12 @@ location set Getting Started - 시작 + 설정 시작 Before we get on the road, let’s finish installation and cover some details. - 출발하기 전에 설치를 완료하고 몇 가지 세부 사항을 살펴보겠습니다. + 출발하기 전에 설정을 완료하고 몇 가지 세부 사항을 살펴보겠습니다. @@ -859,7 +859,7 @@ location set Finish Setup - 설치완료 + 설정 완료 @@ -869,7 +869,7 @@ location set Pair device - 페어링 + 장치 페어링 @@ -911,12 +911,12 @@ location set GOOD - 경고 + 좋음 OK - 좋음 + 경고 @@ -1009,7 +1009,7 @@ location set The last time openpilot successfully checked for an update. The updater only runs while the car is off. - 이전에 openpilot에서 업데이트를 성공적으로 확인한 시간입니다. 업데이트 프로그램은 차량 연결이 해제되었을때만 작동합니다. + 최근에 openpilot이 업데이트를 성공적으로 확인했습니다. 업데이트 프로그램은 차량 연결이 해제되었을때만 작동합니다. @@ -1019,22 +1019,22 @@ location set CHECKING - 검사중 + 확인중 Uninstall - 삭제 + 제거 UNINSTALL - 삭제 + 제거 Are you sure you want to uninstall? - 삭제하시겠습니까? + 제거하시겠습니까? @@ -1084,7 +1084,7 @@ location set Username '%1' has no keys on GitHub - 사용자 이름 '%1' GitHub에 키가 없습니다 + '%1'의 키가 GitHub에 없습니다 @@ -1094,7 +1094,7 @@ location set Username '%1' doesn't exist on GitHub - 사용자 이름 '%1' GitHub에 없습니다 + '%1'은 GitHub에 없습니다 @@ -1120,7 +1120,7 @@ location set Scroll to accept - 스크롤 허용 + 허용하려면 아래로 스크롤하세요 @@ -1168,12 +1168,12 @@ location set Display speed in km/h instead of mph. - mph가 아닌 km/h로 속도 표시. + mph 대신 km/h로 속도를 표시합니다. Record and Upload Driver Camera - 운전자 카메라 기록 및 업로드 + 운전자 카메라 녹화 및 업로드 @@ -1193,7 +1193,7 @@ location set Show ETA in 24h format - 24시간 형식으로 ETA 표시 + 24시간 형식으로 도착예정시간 표시 @@ -1275,7 +1275,7 @@ location set Forget Wi-Fi Network " - wifi 네트워크 저장안함" + wifi 네트워크 저장안함 " diff --git a/selfdrive/ui/translations/main_zh-CHS.qm b/selfdrive/ui/translations/main_zh-CHS.qm index 63c17d76b7f0f99e5180d400a8143d17cbbdde55..45fae52b4286bb3e57938bf6c7c4ad53d3bd3ba1 100644 GIT binary patch delta 1686 zcmX9;2~1R16g@NZ|15uI{(uZ%Q3M8%MP#XfvdNZ$pal^W<5G=6QL8q#S|l!`ts9~U z!Ch1ka4EGWxYm6^EGW2PG$j~R5H(t;HI-<<9>XM)lmGsI_nmvrxv#NEajQsC2XL?@uH||?FuxqI`2qN`kN6%~{P}%x@f(+*dl1&|0Y<-tu(KUd zNDyj+xoH}N#xuk!2)6~mWgx_juB3CPBue3E&4FfEGoXKhKoe0aLt_0hV0Z-*Uz`Mj zS7MBA7GT?eKD6^Gn#I7UQ4rH2Zc;Sn-bEHz7lLjq4MUF>5tXS%FE1 zDgj+CCMRtr)o@HXyc~!gkLg#~j&-;@7Gzmi-~^WTvVd_m${U)1m=UO1{0-ofgIc>( zU`Pu(HZI}&8ihlcAKs#;-~~lUA=M9xR;1PW0G_^z-4D1P=AmfH5Lnl$c%-ZV zoD&rwxz)rDw-eSP}F|nIJ7Dvop$RHtaa?wQ_H>jvGppr#F$M1FpH;P9D@*Pw2U+h4GY=gngLYwV5(Tyi7V@5s23%hV%V&|1 zI!{ zOFctys~@8s#1FkB7!agZx@9n3x7Bi&KNT!eN4`v;f`6$KYc2rctJPB#)ZSB2SM>A& zZkg)y{=2MXzDoTe^#Ristg-k|GVfGPmD4Zmut{@l;WHALr0JS)fD&%fynjVyRA)6G zBRXmJ0ByWaEoZ(}o2(*X(>ZPSn~x;ALc4j%ZeVbsc7HYN*zMGw>~QCEx=v%9!4S>S zxtD4=F5`5uZ%eubv-P%a>NH9_G+vig$NBR1(iMWK!hT(IOA1p|u4}dZo)<^86gw<{ z9m!JGokn(;DCNI&=2XujMzOPUsi4!u=Q?R?A1(EKEbTmB!E~CX(nk|%O^>v%kru0Z zrK20RvLU5(Hc(^+f~%yfIov1;Qmr(E*T)s9)*+IF9!M`{FQ!zUdc~=glr~rIe)&2H zIp`A}=K}+L_0ym7B5+@!Uvys}@qGR2pUm98Wc$BvpEN0{B zTw++BvDR{s)~6e5;|?+dUO~o&NO~{LHa1V@IGWeV_D8C?-XlA$rvi4avZW^;2vN(U z+IRy6bjxEmQ9`?^@}jt}7+ya)e-8)T2lC#|7-nId{A(o-3W<>~{KpIoZjqZ}?l9aD zCT%ybMopc`9LsSIwJ|w7x9{Uk(`Xvg&VoVPO$&26=-t8+qsGzUw5j#QKJxA|wI%!x bL|Wzou>+2WYf1+wmXtjFBI3B6Q@H>CHZ-~4 delta 1659 zcmX9;dsK{R9Dcr;@0)3E-_UK=CDnAN`=(W-(rzRqk}T~yNU_*sH`2Nc8yj+|ovd3( zigjt7le^>6u0)|YSe=bsBIK}ImlaO!KF-WP&zblA-rxKDp6B_!mkWg}g+ifcY$~A4 z1o|!@<`B0KHxf?)VkaO615yys?>TWG;2%z$$Zs-iXx>tk;UgR-E5_oj|v5fN#5qZ-DF%`#%;va}Bu;F@GyC_$9c?jC}TL~SXC)-41A$}#lu5g^Qh zVVWsG_j(Ku-+⋘WIj-X^$kEw7^t%hQvarE6yaW z1B}ZR*OOVePk`c19c>IetGHY0#DYteVxS3dOi{W#m3Z#4(p(Tt1(THXl3DkYiOT&l ziTfLsRYym&PKWYj70(6dDQkR|Sg$F1S+0wd_Z%XFR&hoG1@0Cm=C%w5+}gxNQ^-h_ zE9Q$Yf$)psrUZsd8D>MH*@lkQHgxk8OUgUQELtpkFpX#t4>WE7%;&_zUzJnREb)Y% z-WcwPmmW3)9`53$Cx6p}?(Jer^kL@BB5A{^dDIKZP%sx5&?v>pUZkETrA?+M;gh9I z?HNF?k!E^UQ1dy`%*s79x0J{%+WAVk(>V?Pd!>b8GB0>775qdZntB_$M%mD9whg2A zNhSTt>49UrRI;9_&}B&FKdb;u_R_%%cd3z^^jjx2SFD%LxnERr-Jrmer)>_^FbN2@D(=CQ*@^}#v!Ng!4Id`uZ7T&sTF)B~{ZtA6u@ z3Mo&j-w%95(;e*M{AxJ+e_AU=(}eYQJNEOm!)Ci9tsX${6ph;OC8IM#<56PAAsMNO zeZiMQuGEZ6d_dj(HK}>jE9R>AG%B(JuDPfp) zRhtV3c`7lA&6H^i9vS)ng0{GeE_(f?-E?Xf1L>qKX&Og2-fFjBp{vSHZRN^h-lEi= z43@}Zw{@{(viz=nJT;qAca_RXieS91(i|Vc)J|Laad+QU2u(!x+ zed-3*b1l@*9!1s`X}o^pyYZZtMtxNg=cdn2eO)QV2p*%q+)NDY(l^(Vn7GcMs_^86 ziH0DTTO<-;i0E9!`8#W<4CB7p$#5)(81bE<#=M)Bjy2Q_A^LIczM?Nq~!G)|dg zzU;KOg6nVPp844fpM$$>?uY~WtK|WA`LYE4BPXt*P7aggxkElzt1p?>yel7TS$><9`7LdCUM}9S%jROYDXD)>}OW M3T}t&dqxKS50wtHa{vGU diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 9ac35994e6..04bd2415f0 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -415,7 +415,7 @@ - Get turn-by-turn directions displayed and more with a comma + Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai 订阅comma prime以获取导航。 立即注册:https://connect.comma.ai diff --git a/selfdrive/ui/translations/main_zh-CHT.qm b/selfdrive/ui/translations/main_zh-CHT.qm index 208f29c0ec9dd45424301c70cdaf64c2e9a901bc..130bcfc92670cff84c6c6fcf359be599e4941e3e 100644 GIT binary patch delta 1686 zcmX9;3sg;M7~SXGbME8Zd(V|_H=@_Atco_OWJPd^Q z#Q?*2z@;3C5v%e3mzWhts%h`G6I72WX?6zKi&@PKV4i?&7ixf*2`HP%JiA1~=}LvY zN^x&lCinLXwq8Mif3nbSvp>-3hR~yc>W9<|DV1Hg{zBMro$I~yLd{T#akGS*;ts$w zSa|foBA|m!R5H#1oi~XA_iiHxp_{~bWhR+z5J$IR#vzNuO|=GIm?9ooPGVuQcru{? zu*?##r7*CUB-U54jE<3F!&Wy2%+W{=cfdMG@FO4ldNCuVC!~_c5#$TF!yD#8VF3lNFM%u;F zQt2fSu|-;!P(cGZTG3)_MeC7P^lp@jOPW}_$I|w@X=G@Z_Fi5M*q2C$zAB-lYo((m z*2essbn$*2*Y8RfA3tRcT>g-5M<1f!vSlTLn)h{)&H2-To@H`BHGrwO$|J_ICJ_O0 zhH?@x$?_!soj|BTp0ux&#obDL1?X+^>@Q~Ve43mct^$6?wA^1YLM&dNyx9Qd}m=5 zi@mB9qvPc_%_Qik){4GE>8^KL^_hbTj?wmc6i)^3Yx|d-0D8~WjuNQ7|0V5?rWU~0 zQ(NI!pF`$TwQrKH(`|a4y$dDl9H`srv5*-~(jAz3hXj&!&xUNLgcZ71kEx8NT=zEe z0no8Y->-|4?XX*)s3Bp?9({V_TN2IEugKiM{crVK_AriXf&TD4KYsT&=*;YYuNZ@0 zv7YTB8Dd`)J(sLGI>V^Zl(v&#NULOj1->;DfUd$8Lv7t)x+vRF?=p>pne88oqDDC<}j9~Oxaw`5^LTn z`*K$?p)loGh)fTJrz>YNcu{VvI2A9Bj}wa1#yQk!kMeNBOg{9?D3s5mw53MBQ|IV~ zr^fhOc|cp6G4(bFfnTg~`ZbBlO)xI_#>)Gzjg?PWlEALU^Mk06o4d(+iUfjxGWnKq zJ>aS-IBGV%(PWD6ca(IG@OxqzrnPTAWq|pn zvO@Nk*Vm@1ttvgzXu4EKbgVbkRg$3ey;-}{pAW{FyLmYS{+($I8L(SXB2Jc*}Zh8KT9KN3CeV+I2c|V>v`V#ssMS80tqV#oEib;lW32A9U z5*3CxD`FPM2#b{&hSSg}@-ZB2zE<0{)AP@Dp5J}nzx(=K*Y9`d77BTV!Y0oM3!q5_ z28<(S64QuVi0c8V6Ho^LvOnNkMI1qVNlfIP8QthUy)eaF_@Z!wO9UfvxjgwE81pH2 zh5`wJfbI!#4q(?s%w~KouwWNpJsnugnDu=io$L1Lg@3vPZh@4u9SC!SRMG|rDx`+N zJmd(e={PY7(q##7z6*JsD=@I2C{%FBii6Jg8eq7K05eg)2QiJy0l!Iz={O1u4#OxV z3FuLWxS(SE|HWlSlInHDFDPP>BF6o}+w5*&{L0tdUw{eXS;pfrA!#*l3Bjbjm4K3o z$+4SB)dN%Ztsu+QnD%2MkTviQ7ACthK{b|kGJ$Cpc3o@+!jn;x&N};tpur}dwD+NX z-4d=J66}Kq0-gy%uQE@d-wk2NMyelhM@Tr|pYd11w(E=sD?;-GiFua_H^mCT$s#-& z^cB#@LDZ+71ANLvul9S$LSUH~txqSj?c!8xRveHm?zpD#K$>`LJ&Ap!6;H)(1k6jt zs|if(EQ_}rX`>}kY%RBA!Y?(F#R0G#t8scN^V}JYdwv)z|5vjlfq91x(i~7p+_zCv zQ^!^@cW6%3@LWJ2O@sHUqAOybtVU_(-dZxaAkB@Xz}BA9vU?)|*JIL(Br?)wOF7aj zAgEj_iLGY?S-R0|-;K7%yV2#DR9g9#-aV0awfjr7KJ zOS<%+h4FUj(&K0JpvUjhy|5$fx8<@vh?a0mEwLDAkLl*vgY<(vzTma;p9m zV3g%~o>f4gUY=LIm*$oe-vCzj^0L`Wxj#i-K3D}jevtFOAra+bH@axL(RFAyhW#d& z`c~2d+YY(3fL&ool`Gd~Q;FB|;R~&Rf4zLBlbVb9@>#bl?5b9|r>y+0-M@zGWFUc(CK>kg;gCxLOg=i_%X@k!lZHyweV_PRHZsgR~l z_hH0Cpzk}YsQwKci~U8_lEdd~tacvYX`2G8qwOAC9i`|@oN?y}#iP`ULn12?FZpt) z70SfXZPYzLnY4y_MOZ0`Q>kx1QAs`@33&gbYy?{iJC$oKW7$e8ikxJJ*q-{lM^1o? zACWJGSB5_Sp_%`M`psQ*(QB8!q`ra;spv~@PNW;P`m!dvs`;R=&fUx!2I)@($Ye3Q zXr=6sbx_|iE1gokFbH+4IGFnk9;eUI>*t1P_c-7lk%mQAB`T6^Se;?ZXXTyY{8LKp z?Q8hy6IN{3%V>L=xA=W$bgN<9>sO;+=rVf#))*Z{%R=ppal@ujdTZn8NY*yI-Z-h4 z`CO(L7mg+CEIHM<<^5+&u-aHt$hmP|Y-}v282-^Y6|Ym4s!uUpo6IS*%~I{Y ztzx`M?VXd(=Cd)W?r)>0$7OX`D_<7>4eIFi)X8S7x+wBvHl;<)+s?uDxvuVb7|sC> zSNB))q9KZU@^8A__l(*c{tMvXY_@vACr?*rwvFJJ4rwvlKj`8El3^az#(aT;%xS6Z zR4B^4>1H-vonzjbl2+uXGuWRn-|i^mKpru-Mjrw~T;{SF;%kTNa(fCHMQ0sH2(GnV Ij_WM{0lCk!tN;K2 diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 2920916ece..806dd54ad3 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -415,16 +415,11 @@ - Get turn-by-turn directions displayed and more with a comma + Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai 成為 comma 高級會員來使用導航功能 立即註冊:https://connect.comma.ai - - Get turn-by-turn directions displayed and more with a comma -prime subscription. Sign up now: https://connect.comma.ai - 成為 comma 高級會員來使用導航功能,立即註冊:https://connect.comma.ai - No home From 2ae52e9b2218c23d4c80b36fb0b50387b6ecdd8f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 11 Jul 2022 17:20:56 -0700 Subject: [PATCH 275/302] process replay: ensure enabled for significant amount of time (#25121) * process replay: ensure enabled for significant amount of time * update refs * 10s is reasonable --- selfdrive/controls/controlsd.py | 3 ++- selfdrive/test/process_replay/process_replay.py | 11 +++++++++-- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/test/process_replay/test_processes.py | 16 ++++++++-------- 4 files changed, 20 insertions(+), 12 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 117509f1e6..b344705f9d 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -406,7 +406,8 @@ class Controls: if not self.initialized: all_valid = CS.canValid and self.sm.all_checks() - if all_valid or self.sm.frame * DT_CTRL > 3.5 or SIMULATION: + timed_out = self.sm.frame * DT_CTRL > (6. if REPLAY else 3.5) + if all_valid or timed_out or SIMULATION: if not self.read_only: self.CI.init(self.CP, self.can_sock, self.pm.sock['sendcan']) self.initialized = True diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index c667aa3887..bea7dc46ee 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -14,6 +14,7 @@ from cereal import car, log from cereal.services import service_list from common.params import Params from common.timeout import Timeout +from common.realtime import DT_CTRL from panda.python import ALTERNATIVE_EXPERIENCE from selfdrive.car.car_helpers import get_car, interfaces from selfdrive.test.process_replay.helpers import OpenpilotPrefix @@ -548,11 +549,17 @@ def cpp_replay_process(cfg, lr, fingerprint=None): def check_enabled(msgs): + cur_enabled_count = 0 + max_enabled_count = 0 for msg in msgs: if msg.which() == "carParams": if msg.carParams.notCar: return True elif msg.which() == "controlsState": if msg.controlsState.active: - return True - return False + cur_enabled_count += 1 + else: + cur_enabled_count = 0 + max_enabled_count = max(max_enabled_count, cur_enabled_count) + + return max_enabled_count > int(10. / DT_CTRL) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index fc5f83c32a..bef6956ec3 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -d583bbd9643000e7f817171c583d31ae3141a652 \ No newline at end of file +998b457e0d38e3639814ed81cb2d32e92d9bed8c \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 652c49db3d..91cc40f5ce 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -18,14 +18,14 @@ from tools.lib.logreader import LogReader original_segments = [ ("BODY", "937ccb7243511b65|2022-05-24--16-03-09--1"), # COMMA.BODY ("HYUNDAI", "02c45f73a2e5c6e9|2021-01-01--19-08-22--1"), # HYUNDAI.SONATA - ("HYUNDAI", "d824e27e8c60172c|2022-07-08--21-21-15--1"), # HYUNDAI.KIA_EV6 + ("HYUNDAI", "d824e27e8c60172c|2022-07-08--21-21-15--0"), # HYUNDAI.KIA_EV6 ("TOYOTA", "0982d79ebb0de295|2021-01-04--17-13-21--13"), # TOYOTA.PRIUS (INDI) ("TOYOTA2", "0982d79ebb0de295|2021-01-03--20-03-36--6"), # TOYOTA.RAV4 (LQR) ("TOYOTA3", "f7d7e3538cda1a2a|2021-08-16--08-55-34--6"), # TOYOTA.COROLLA_TSS2 ("HONDA", "eb140f119469d9ab|2021-06-12--10-46-24--27"), # HONDA.CIVIC (NIDEC) ("HONDA2", "7d2244f34d1bbcda|2021-06-25--12-25-37--26"), # HONDA.ACCORD (BOSCH) ("CHRYSLER", "4deb27de11bee626|2021-02-20--11-28-55--8"), # CHRYSLER.PACIFICA - ("RAM", "2f4452b03ccb98f0|2022-07-07--08-01-56--2"), # CHRYSLER.RAM_1500 + ("RAM", "2f4452b03ccb98f0|2022-07-07--08-01-56--3"), # CHRYSLER.RAM_1500 ("SUBARU", "4d70bc5e608678be|2021-01-15--17-02-04--5"), # SUBARU.IMPREZA ("GM", "0c58b6a25109da2b|2021-02-23--16-35-50--11"), # GM.VOLT ("NISSAN", "35336926920f3571|2021-02-12--18-38-48--46"), # NISSAN.XTRAIL @@ -39,13 +39,14 @@ original_segments = [ segments = [ ("BODY", "regen660D86654BA|2022-07-06--14-27-15--0"), ("HYUNDAI", "regen657E25856BB|2022-07-06--14-26-51--0"), + ("HYUNDAI", "d824e27e8c60172c|2022-07-08--21-21-15--0"), ("TOYOTA", "regenBA97410FBEC|2022-07-06--14-26-49--0"), ("TOYOTA2", "regenDEDB1D9C991|2022-07-06--14-54-08--0"), ("TOYOTA3", "regenDDC1FE60734|2022-07-06--14-32-06--0"), ("HONDA", "regen17B09D158B8|2022-07-06--14-31-46--0"), ("HONDA2", "regen041739C3E9A|2022-07-06--15-08-02--0"), ("CHRYSLER", "regenBB2F9C1425C|2022-07-06--14-31-41--0"), - ("RAM", "2f4452b03ccb98f0|2022-07-07--08-01-56--2"), + ("RAM", "2f4452b03ccb98f0|2022-07-07--08-01-56--3"), ("SUBARU", "regen732B69F33B1|2022-07-06--14-36-18--0"), ("GM", "regen01D09D915B5|2022-07-06--14-36-20--0"), ("NISSAN", "regenEA6FB2773F5|2022-07-06--14-58-23--0"), @@ -65,7 +66,7 @@ def run_test_process(data): res = None if not args.upload_only: lr = LogReader.from_bytes(lr_dat) - res, log_msgs = test_process(cfg, lr, ref_log_path, args.ignore_fields, args.ignore_msgs) + res, log_msgs = test_process(cfg, lr, ref_log_path, cur_log_fn, args.ignore_fields, args.ignore_msgs) # save logs so we can upload when updating refs save_log(cur_log_fn, log_msgs) @@ -83,7 +84,7 @@ def get_log_data(segment): return (segment, f.read()) -def test_process(cfg, lr, ref_log_path, ignore_fields=None, ignore_msgs=None): +def test_process(cfg, lr, ref_log_path, new_log_path, ignore_fields=None, ignore_msgs=None): if ignore_fields is None: ignore_fields = [] if ignore_msgs is None: @@ -96,7 +97,7 @@ def test_process(cfg, lr, ref_log_path, ignore_fields=None, ignore_msgs=None): # check to make sure openpilot is engaged in the route if cfg.proc_name == "controlsd": if not check_enabled(log_msgs): - raise Exception(f"Route never enabled: {ref_log_path}") + return f"Route did not enable at all or for long enough: {new_log_path}", log_msgs try: return compare_logs(ref_log_msgs, log_msgs, ignore_fields + cfg.ignore, ignore_msgs, cfg.tolerance), log_msgs @@ -216,8 +217,7 @@ if __name__ == "__main__": results: Any = defaultdict(dict) p2 = pool.map(run_test_process, pool_args) for (segment, proc, subtest_name, result) in tqdm(p2, desc="Running Tests", total=len(pool_args)): - if isinstance(result, list): - results[segment][proc + subtest_name] = result + results[segment][proc + subtest_name] = result diff1, diff2, failed = format_diff(results, ref_commit) if not upload: From 29c8e5d227eacae36dbc4357bf5328f22668d5ef Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 11 Jul 2022 17:26:59 -0700 Subject: [PATCH 276/302] Chrysler: increase Ram torque rate limit --- selfdrive/car/chrysler/values.py | 4 ++-- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index f7531792fb..69dade4b64 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -31,8 +31,8 @@ class CarControllerParams: self.STEER_ERROR_MAX = 80 if CP.carFingerprint in RAM_CARS: - self.STEER_DELTA_UP = 5 - self.STEER_DELTA_DOWN = 5 + self.STEER_DELTA_UP = 6 + self.STEER_DELTA_DOWN = 6 else: self.STEER_DELTA_UP = 3 self.STEER_DELTA_DOWN = 3 diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index bef6956ec3..d98ae96516 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -998b457e0d38e3639814ed81cb2d32e92d9bed8c \ No newline at end of file +2ae52e9b2218c23d4c80b36fb0b50387b6ecdd8f \ No newline at end of file From 045c881e1ffeb5e7bcb8e1ee78d4a42caee1be4d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 11 Jul 2022 21:11:12 -0700 Subject: [PATCH 277/302] couple more stinger MYs supported --- docs/CARS.md | 2 +- selfdrive/car/hyundai/values.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index eb570faa7e..5e185ed278 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -105,7 +105,7 @@ How We Rate The Cars |Kia|Seltos 2021|SCC + LKAS|||||| |Kia|Sorento 2018|SCC + LKAS|||||| |Kia|Sorento 2019|SCC + LKAS|||||| -|Kia|Stinger 2018|SCC + LKAS|||||| +|Kia|Stinger 2018-20|SCC + LKAS|||||| |Lexus|CT Hybrid 2017-18|LSS|[3](#footnotes)||||| |Lexus|ES Hybrid 2017-18|LSS|[3](#footnotes)||||| |Lexus|NX 2018-19|All|[3](#footnotes)||||| diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 4b3acf3f27..2e6a2017ea 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -151,7 +151,7 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { HyundaiCarInfo("Kia Sorento 2018", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_c), HyundaiCarInfo("Kia Sorento 2019", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_e), ], - CAR.KIA_STINGER: HyundaiCarInfo("Kia Stinger 2018", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", harness=Harness.hyundai_c), + CAR.KIA_STINGER: HyundaiCarInfo("Kia Stinger 2018-20", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", harness=Harness.hyundai_c), CAR.KIA_CEED: HyundaiCarInfo("Kia Ceed 2019", harness=Harness.hyundai_e), CAR.KIA_EV6: HyundaiCarInfo("Kia EV6 2022", "All", harness=Harness.hyundai_p), From 614b3a01f89eabfa9ea26ed2a367592939f78e11 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 11 Jul 2022 22:10:06 -0700 Subject: [PATCH 278/302] Chrysler: limit buttons to 20Hz (#25125) * Chrysler: limit buttons to 10Hz * cleanup * 20hz --- selfdrive/car/chrysler/carcontroller.py | 20 +++++++++++++++----- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 16 insertions(+), 6 deletions(-) diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py index a7f2d007f1..8156e7841e 100644 --- a/selfdrive/car/chrysler/carcontroller.py +++ b/selfdrive/car/chrysler/carcontroller.py @@ -1,4 +1,5 @@ from opendbc.can.packer import CANPacker +from common.realtime import DT_CTRL from selfdrive.car import apply_toyota_steer_torque_limits from selfdrive.car.chrysler.chryslercan import create_lkas_hud, create_lkas_command, create_cruise_buttons from selfdrive.car.chrysler.values import RAM_CARS, CarControllerParams @@ -14,6 +15,7 @@ class CarController: self.hud_count = 0 self.last_lkas_falling_edge = 0 self.lkas_active_prev = False + self.last_button_frame = 0 self.packer = CANPacker(dbc_name) self.params = CarControllerParams(CP) @@ -26,11 +28,19 @@ class CarController: # *** control msgs *** - das_bus = 2 if self.CP.carFingerprint in RAM_CARS else 0 - if CC.cruiseControl.cancel: - can_sends.append(create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, cancel=True)) - elif CC.enabled and CS.out.cruiseState.standstill: - can_sends.append(create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, resume=True)) + # cruise buttons + if (self.frame - self.last_button_frame)*DT_CTRL > 0.05: + das_bus = 2 if self.CP.carFingerprint in RAM_CARS else 0 + + # ACC cancellation + if CC.cruiseControl.cancel: + self.last_button_frame = self.frame + can_sends.append(create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, cancel=True)) + + # ACC resume from standstill + elif CC.cruiseControl.resume: + self.last_button_frame = self.frame + can_sends.append(create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, resume=True)) # HUD alerts if self.frame % 25 == 0: diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index d98ae96516..b165b163ba 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -2ae52e9b2218c23d4c80b36fb0b50387b6ecdd8f \ No newline at end of file +11e721366f1c177a84e6cb8b48171113ac3b54f9 \ No newline at end of file From 4d7b7483d70a61cf0fb938107df55c24f27da1b0 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Tue, 12 Jul 2022 12:36:57 +0200 Subject: [PATCH 279/302] Replay: tolerances per field (#25116) * tolerances per field in replay * refactor * Remove laikad parameters * Small comment change --- selfdrive/test/process_replay/compare_logs.py | 22 ++++++++++++++++--- .../test/process_replay/process_replay.py | 2 +- .../test/process_replay/test_processes.py | 2 +- 3 files changed, 21 insertions(+), 5 deletions(-) diff --git a/selfdrive/test/process_replay/compare_logs.py b/selfdrive/test/process_replay/compare_logs.py index 057e46cd9c..bf6daf5fed 100755 --- a/selfdrive/test/process_replay/compare_logs.py +++ b/selfdrive/test/process_replay/compare_logs.py @@ -46,11 +46,25 @@ def remove_ignored_fields(msg, ignore): return msg.as_reader() -def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None, tolerance=None): +def get_field_tolerance(diff_field, field_tolerances): + diff_field_str = diff_field[0] + for s in diff_field[1:]: + # loop until number in field + if not isinstance(s, str): + break + diff_field_str += '.'+s + if diff_field_str in field_tolerances: + return field_tolerances[diff_field_str] + + +def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None, tolerance=None, field_tolerances=None): if ignore_fields is None: ignore_fields = [] if ignore_msgs is None: ignore_msgs = [] + if field_tolerances is None: + field_tolerances = {} + default_tolerance = EPSILON if tolerance is None else tolerance log1, log2 = (list(filter(lambda m: m.which() not in ignore_msgs, log)) for log in (log1, log2)) @@ -72,7 +86,6 @@ def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None, tolerance=Non msg1_dict = msg1.to_dict(verbose=True) msg2_dict = msg2.to_dict(verbose=True) - tolerance = EPSILON if tolerance is None else tolerance dd = dictdiffer.diff(msg1_dict, msg2_dict, ignore=ignore_fields) # Dictdiffer only supports relative tolerance, we also want to check for absolute @@ -80,10 +93,13 @@ def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None, tolerance=Non def outside_tolerance(diff): try: if diff[0] == "change": + field_tolerance = default_tolerance + if (tol := get_field_tolerance(diff[1], field_tolerances)) is not None: + field_tolerance = tol a, b = diff[2] finite = math.isfinite(a) and math.isfinite(b) if finite and isinstance(a, numbers.Number) and isinstance(b, numbers.Number): - return abs(a - b) > max(tolerance, tolerance * max(abs(a), abs(b))) + return abs(a - b) > max(field_tolerance, field_tolerance * max(abs(a), abs(b))) except TypeError: pass return True diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index bea7dc46ee..0c642cde17 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -28,7 +28,7 @@ TIMEOUT = 15 PROC_REPLAY_DIR = os.path.dirname(os.path.abspath(__file__)) FAKEDATA = os.path.join(PROC_REPLAY_DIR, "fakedata/") -ProcessConfig = namedtuple('ProcessConfig', ['proc_name', 'pub_sub', 'ignore', 'init_callback', 'should_recv_callback', 'tolerance', 'fake_pubsubmaster', 'submaster_config', 'environ', 'subtest_name'], defaults=({}, {}, "")) +ProcessConfig = namedtuple('ProcessConfig', ['proc_name', 'pub_sub', 'ignore', 'init_callback', 'should_recv_callback', 'tolerance', 'fake_pubsubmaster', 'submaster_config', 'environ', 'subtest_name', "field_tolerances"], defaults=({}, {}, "", {})) def wait_for_event(evt): diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 91cc40f5ce..d8cd1fd57a 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -100,7 +100,7 @@ def test_process(cfg, lr, ref_log_path, new_log_path, ignore_fields=None, ignore return f"Route did not enable at all or for long enough: {new_log_path}", log_msgs try: - return compare_logs(ref_log_msgs, log_msgs, ignore_fields + cfg.ignore, ignore_msgs, cfg.tolerance), log_msgs + return compare_logs(ref_log_msgs, log_msgs, ignore_fields + cfg.ignore, ignore_msgs, cfg.tolerance, cfg.field_tolerances), log_msgs except Exception as e: return str(e), log_msgs From f0b5ff5c1addff7932fe86a2874a23d87b5eb5f3 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Tue, 12 Jul 2022 14:03:35 +0200 Subject: [PATCH 280/302] Replay: Fix --upload-only (#25127) Add checking for list back --- selfdrive/test/process_replay/test_processes.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index d8cd1fd57a..77d73a4ff4 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -217,7 +217,8 @@ if __name__ == "__main__": results: Any = defaultdict(dict) p2 = pool.map(run_test_process, pool_args) for (segment, proc, subtest_name, result) in tqdm(p2, desc="Running Tests", total=len(pool_args)): - results[segment][proc + subtest_name] = result + if isinstance(result, list): + results[segment][proc + subtest_name] = result diff1, diff2, failed = format_diff(results, ref_commit) if not upload: From 205f6f7414f502248082949addac25a215c73d59 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 12 Jul 2022 16:09:21 +0200 Subject: [PATCH 281/302] casync: manifest compare script (#25129) * casync compare script * typo * cleanup output --- .../tici/tests/compare_casync_manifest.py | 74 +++++++++++++++++++ 1 file changed, 74 insertions(+) create mode 100755 system/hardware/tici/tests/compare_casync_manifest.py diff --git a/system/hardware/tici/tests/compare_casync_manifest.py b/system/hardware/tici/tests/compare_casync_manifest.py new file mode 100755 index 0000000000..5e5fa24556 --- /dev/null +++ b/system/hardware/tici/tests/compare_casync_manifest.py @@ -0,0 +1,74 @@ +#!/usr/bin/env python3 +import argparse +import collections +import multiprocessing +import os +from typing import Dict, List + +import requests +from tqdm import tqdm + +import system.hardware.tici.casync as casync + + +def get_chunk_download_size(chunk): + sha = chunk.sha.hex() + path = os.path.join(remote_url, sha[:4], sha + ".cacnk") + if os.path.isfile(path): + return os.path.getsize(path) + else: + r = requests.head(path) + r.raise_for_status() + return int(r.headers['content-length']) + + +if __name__ == "__main__": + + parser = argparse.ArgumentParser(description='Compute overlap between two casync manifests') + parser.add_argument('frm') + parser.add_argument('to') + args = parser.parse_args() + + frm = casync.parse_caibx(args.frm) + to = casync.parse_caibx(args.to) + remote_url = args.to.replace('.caibx', '') + + most_common = collections.Counter(t.sha for t in to).most_common(1)[0][0] + + frm_dict = casync.build_chunk_dict(frm) + + # Get content-length for each chunk + with multiprocessing.Pool() as pool: + szs = list(tqdm(pool.imap(get_chunk_download_size, to), total=len(to))) + chunk_sizes = {t.sha: sz for (t, sz) in zip(to, szs)} + + sources: Dict[str, List[int]] = { + 'seed': [], + 'remote_uncompressed': [], + 'remote_compressed': [], + } + + for chunk in to: + # Assume most common chunk is the zero chunk + if chunk.sha == most_common: + continue + + if chunk.sha in frm_dict: + sources['seed'].append(chunk.length) + else: + sources['remote_uncompressed'].append(chunk.length) + sources['remote_compressed'].append(chunk_sizes[chunk.sha]) + + print() + print("Update statistics (excluding zeros)") + print() + print("Download only with no seed:") + print(f" Remote (uncompressed)\t\t{sum(sources['seed'] + sources['remote_uncompressed']) / 1000 / 1000:.2f} MB\tn = {len(to)}") + print(f" Remote (compressed download)\t{sum(chunk_sizes.values()) / 1000 / 1000:.2f} MB\tn = {len(to)}") + print() + print("Upgrade with seed partition:") + print(f" Seed (uncompressed)\t\t{sum(sources['seed']) / 1000 / 1000:.2f} MB\t\t\t\tn = {len(sources['seed'])}") + sz, n = sum(sources['remote_uncompressed']), len(sources['remote_uncompressed']) + print(f" Remote (uncompressed)\t\t{sz / 1000 / 1000:.2f} MB\t(avg {sz / 1000 / 1000 / n:4f} MB)\tn = {n}") + sz, n = sum(sources['remote_compressed']), len(sources['remote_compressed']) + print(f" Remote (compressed download)\t{sz / 1000 / 1000:.2f} MB\t(avg {sz / 1000 / 1000 / n:4f} MB)\tn = {n}") From 105afee4a21ad008fa741f19c5a62a6d52fdd773 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Tue, 12 Jul 2022 18:11:47 +0200 Subject: [PATCH 282/302] Laikad: set cache dir to comma_download_cache (#25131) * Cache downloads for process replay * set cache dir permanent * Create constant --- selfdrive/locationd/laikad.py | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 0954cb4c9f..4868e8ae52 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -27,6 +27,7 @@ from system.swaglog import cloudlog MAX_TIME_GAP = 10 EPHEMERIS_CACHE = 'LaikadEphemeris' +DOWNLOADS_CACHE_FOLDER = "/tmp/comma_download_cache" CACHE_VERSION = 0.1 POS_FIX_RESIDUAL_THRESHOLD = 100.0 @@ -42,7 +43,7 @@ class Laikad: valid_ephem_types: Valid ephemeris types to be used by AstroDog save_ephemeris: If true saves and loads nav and orbit ephemeris to cache. """ - self.astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types, clear_old_ephemeris=True) + self.astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types, clear_old_ephemeris=True, cache_dir=DOWNLOADS_CACHE_FOLDER) self.gnss_kf = GNSSKalman(GENERATED_DIR, cython=True) self.auto_fetch_orbits = auto_fetch_orbits @@ -183,7 +184,7 @@ class Laikad: def fetch_orbits(self, t: GPSTime, block): # Download new orbits if 1 hour of orbits data left if t + SECS_IN_HR not in self.astro_dog.orbit_fetched_times and (self.last_fetch_orbits_t is None or abs(t - self.last_fetch_orbits_t) > SECS_IN_MIN): - astro_dog_vars = self.astro_dog.valid_const, self.astro_dog.auto_update, self.astro_dog.valid_ephem_types + astro_dog_vars = self.astro_dog.valid_const, self.astro_dog.auto_update, self.astro_dog.valid_ephem_types, self.astro_dog.cache_dir ret = None if block: # Used for testing purposes @@ -203,8 +204,8 @@ class Laikad: self.cache_ephemeris(t=t) -def get_orbit_data(t: GPSTime, valid_const, auto_update, valid_ephem_types): - astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types) +def get_orbit_data(t: GPSTime, valid_const, auto_update, valid_ephem_types, cache_dir): + astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types, cache_dir=cache_dir) cloudlog.info(f"Start to download/parse orbits for time {t.as_datetime()}") start_time = time.monotonic() try: @@ -301,6 +302,7 @@ def main(sm=None, pm=None): replay = "REPLAY" in os.environ use_internet = "LAIKAD_NO_INTERNET" not in os.environ laikad = Laikad(save_ephemeris=not replay, auto_fetch_orbits=use_internet) + while True: sm.update() From 780c60324bf19762e9b72da38be0a9f09d624efd Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 12 Jul 2022 11:12:35 -0700 Subject: [PATCH 283/302] process replay: fix string failures after #25127 --- selfdrive/test/process_replay/test_processes.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 77d73a4ff4..4ebb0701dd 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -217,7 +217,7 @@ if __name__ == "__main__": results: Any = defaultdict(dict) p2 = pool.map(run_test_process, pool_args) for (segment, proc, subtest_name, result) in tqdm(p2, desc="Running Tests", total=len(pool_args)): - if isinstance(result, list): + if not args.upload_only: results[segment][proc + subtest_name] = result diff1, diff2, failed = format_diff(results, ref_commit) From 1f17f812cfa74c1db2ceba05dae4946b5e472e2a Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Tue, 12 Jul 2022 15:45:43 -0500 Subject: [PATCH 284/302] Add missing RAV4H_TSS2_2022 engine f/w (#25111) `@Rocks#8913` 2021 RAV4 Hybrid (Italy) DongleID/route 081a1d5f242294c0|2022-07-10--17-39-33 Continental camera p/n 8646C-0R090... https://discord.com/channels/469524606043160576/524327905937850394/995781101903679558 --- selfdrive/car/toyota/values.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 2a03999342..723fa85820 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1381,11 +1381,12 @@ FW_VERSIONS = { b'8965B42172\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x700, None): [ - b'\x01896634A62000\x00\x00\x00\x00', - b'\x01896634A08000\x00\x00\x00\x00', - b'\x01896634A61000\x00\x00\x00\x00', b'\x01896634A02001\x00\x00\x00\x00', b'\x01896634A03000\x00\x00\x00\x00', + b'\x01896634A08000\x00\x00\x00\x00', + b'\x01896634A61000\x00\x00\x00\x00', + b'\x01896634A62000\x00\x00\x00\x00', + b'\x01896634A63000\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F0R01100\x00\x00\x00\x00', From ecac734160f719f59364a637b7cd781460456845 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 12 Jul 2022 13:51:25 -0700 Subject: [PATCH 285/302] update compatibility docs with VIN data (#25134) * start with genesis * chrysler * honda * toyota * subaru --- docs/CARS.md | 46 ++++++++++++++++---------------- selfdrive/car/chrysler/values.py | 4 +-- selfdrive/car/honda/values.py | 20 +++++++------- selfdrive/car/hyundai/values.py | 6 ++--- selfdrive/car/subaru/values.py | 6 ++--- selfdrive/car/toyota/values.py | 10 +++---- 6 files changed, 46 insertions(+), 46 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 5e185ed278..c3efe87515 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -49,12 +49,12 @@ How We Rate The Cars |Kia|Niro Electric 2021|All|||||| |Kia|Niro Electric 2022|All|||||| |Kia|Telluride 2020|SCC + LKAS|||||| -|Lexus|ES 2019-21|All|||||| +|Lexus|ES 2019-22|All|||||| |Lexus|ES Hybrid 2019-22|All|||||| -|Lexus|NX 2020|All|||||| -|Lexus|NX Hybrid 2020|All|||||| +|Lexus|NX 2020-21|All|||||| +|Lexus|NX Hybrid 2020-21|All|||||| |Lexus|RX 2020-22|All|||||| -|Lexus|UX Hybrid 2019-21|All|||||| +|Lexus|UX Hybrid 2019-22|All|||||| |Toyota|Avalon 2022|All|||||| |Toyota|Avalon Hybrid 2022|All|||||| |Toyota|Camry 2021-22|All||[4](#footnotes)|||| @@ -80,8 +80,8 @@ How We Rate The Cars |Audi|RS3 2018|ACC + Lane Assist|||||| |Audi|S3 2015-17|ACC + Lane Assist|||||| |Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise|||||| -|Genesis|G70 2018|All|||||| -|Genesis|G80 2018|All|||||| +|Genesis|G70 2018-19|All|||||| +|Genesis|G80 2017-19|All|||||| |Hyundai|Elantra 2021-22|SCC + LKAS|||||| |Hyundai|Elantra Hybrid 2021-22|SCC + LKAS|||||| |Hyundai|Ioniq Electric 2020|SCC + LKAS|||||| @@ -117,10 +117,10 @@ How We Rate The Cars |Nissan|X-Trail 2017|ProPILOT|||||| |SEAT|Ateca 2018|Driver Assistance|||||| |SEAT|Leon 2014-20|Driver Assistance|||||| -|Subaru|Ascent 2019-20|All|||||| +|Subaru|Ascent 2019-21|All|||||| |Subaru|Crosstrek 2020-21|EyeSight|||||| -|Subaru|Forester 2019-21|All|||||| -|Subaru|Impreza 2020-21|EyeSight|||||| +|Subaru|Forester 2019-22|All|||||| +|Subaru|Impreza 2020-22|EyeSight|||||| |Subaru|XV 2020-21|EyeSight|||||| |Toyota|Alphard 2019-20|All|||||| |Toyota|Alphard Hybrid 2021|All|||||| @@ -151,7 +151,7 @@ How We Rate The Cars |---|---|---|:---:|:---:|:---:|:---:|:---:| |Acura|ILX 2016-19|AcuraWatch Plus|||||| |Acura|RDX 2016-18|AcuraWatch Plus|||||| -|Acura|RDX 2019-21|All|||||| +|Acura|RDX 2019-22|All|||||| |Audi|Q2 2018|ACC + Lane Assist|||||| |Audi|Q3 2020-21|ACC + Lane Assist|||||| |Cadillac|Escalade ESV 2016[1](#footnotes)|ACC + LKAS|||||| @@ -159,27 +159,27 @@ How We Rate The Cars |Chrysler|Pacifica 2019-20|Adaptive Cruise|||||| |Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise|||||| |Chrysler|Pacifica Hybrid 2019-22|Adaptive Cruise|||||| -|Genesis|G90 2018|All|||||| +|Genesis|G90 2017-18|All|||||| |GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise|||||| -|Honda|Accord 2018-21|All|||||| -|Honda|Accord Hybrid 2018-21|All|||||| +|Honda|Accord 2016-22|All|||||| +|Honda|Accord Hybrid 2018-22|All|||||| |Honda|Civic 2016-18|Honda Sensing|||||| -|Honda|Civic 2019-20|All|||[2](#footnotes)||| +|Honda|Civic 2019-21|All|||[2](#footnotes)||| |Honda|Civic 2022|All|||||| |Honda|Civic Hatchback 2017-21|Honda Sensing|||||| |Honda|Civic Hatchback 2022|All|||||| |Honda|CR-V 2015-16|Touring|||||| -|Honda|CR-V 2017-21|Honda Sensing|||||| +|Honda|CR-V 2017-22|Honda Sensing|||||| |Honda|CR-V Hybrid 2017-19|Honda Sensing|||||| |Honda|e 2020|All|||||| -|Honda|Fit 2018-19|Honda Sensing|||||| +|Honda|Fit 2018-20|Honda Sensing|||||| |Honda|Freed 2020|Honda Sensing|||||| -|Honda|HR-V 2019-20|Honda Sensing|||||| -|Honda|Insight 2019-21|All|||||| +|Honda|HR-V 2019-22|Honda Sensing|||||| +|Honda|Insight 2019-22|All|||||| |Honda|Inspire 2018|All|||||| -|Honda|Odyssey 2018-20|Honda Sensing|||||| +|Honda|Odyssey 2018-22|Honda Sensing|||||| |Honda|Passport 2019-21|All|||||| -|Honda|Pilot 2016-21|Honda Sensing|||||| +|Honda|Pilot 2016-22|Honda Sensing|||||| |Honda|Ridgeline 2017-22|Honda Sensing|||||| |Hyundai|Elantra 2017-19|SCC + LKAS|||||| |Hyundai|Genesis 2015-16|SCC + LKAS|||||| @@ -190,16 +190,16 @@ How We Rate The Cars |Hyundai|Tucson 2021|SCC + LKAS|||||| |Hyundai|Veloster 2019-20|SCC + LKAS|||||| |Jeep|Grand Cherokee 2016-18|Adaptive Cruise|||||| -|Jeep|Grand Cherokee 2019-20|Adaptive Cruise|||||| +|Jeep|Grand Cherokee 2019-21|Adaptive Cruise|||||| |Kia|Niro Plug-in Hybrid 2019|SCC + LKAS|||||| |Kia|Optima 2017|SCC + LKAS|||||| |Lexus|IS 2017-19|All|||||| -|Lexus|RC 2020|All|||||| +|Lexus|RC 2017-2020|All|||||| |Lexus|RX 2016-18|All|[3](#footnotes)||||| |Lexus|RX Hybrid 2016-19|All|[3](#footnotes)||||| |Mazda|CX-5 2022|All|||||| |Mazda|CX-9 2021|All|||||| -|Ram|1500 2019-21|Adaptive Cruise|||||| +|Ram|1500 2019-22|Adaptive Cruise|||||| |Subaru|Crosstrek 2018-19|EyeSight|||||| |Subaru|Impreza 2017-19|EyeSight|||||| |Subaru|XV 2018-19|EyeSight|||||| diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 69dade4b64..80baba9bd6 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -53,8 +53,8 @@ CAR_INFO: Dict[str, Optional[Union[ChryslerCarInfo, List[ChryslerCarInfo]]]] = { CAR.PACIFICA_2018: ChryslerCarInfo("Chrysler Pacifica 2017-18"), CAR.PACIFICA_2020: ChryslerCarInfo("Chrysler Pacifica 2019-20"), CAR.JEEP_CHEROKEE: ChryslerCarInfo("Jeep Grand Cherokee 2016-18", video_link="https://www.youtube.com/watch?v=eLR9o2JkuRk"), - CAR.JEEP_CHEROKEE_2019: ChryslerCarInfo("Jeep Grand Cherokee 2019-20", video_link="https://www.youtube.com/watch?v=jBe4lWnRSu4"), - CAR.RAM_1500: ChryslerCarInfo("Ram 1500 2019-21"), + CAR.JEEP_CHEROKEE_2019: ChryslerCarInfo("Jeep Grand Cherokee 2019-21", video_link="https://www.youtube.com/watch?v=jBe4lWnRSu4"), + CAR.RAM_1500: ChryslerCarInfo("Ram 1500 2019-22"), } # Unique CAN messages: diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index c6e20f2d83..bfa42bd509 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -109,13 +109,13 @@ class HondaCarInfo(CarInfo): CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = { CAR.ACCORD: [ - HondaCarInfo("Honda Accord 2018-21", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), + HondaCarInfo("Honda Accord 2016-22", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), HondaCarInfo("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), ], - CAR.ACCORDH: HondaCarInfo("Honda Accord Hybrid 2018-21", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), + CAR.ACCORDH: HondaCarInfo("Honda Accord Hybrid 2018-22", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), CAR.CIVIC: HondaCarInfo("Honda Civic 2016-18", harness=Harness.nidec), CAR.CIVIC_BOSCH: [ - HondaCarInfo("Honda Civic 2019-20", "All", video_link="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", footnotes=[Footnote.CIVIC_DIESEL], min_steer_speed=2. * CV.MPH_TO_MS, harness=Harness.bosch_a), + HondaCarInfo("Honda Civic 2019-21", "All", video_link="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", footnotes=[Footnote.CIVIC_DIESEL], min_steer_speed=2. * CV.MPH_TO_MS, harness=Harness.bosch_a), HondaCarInfo("Honda Civic Hatchback 2017-21", harness=Harness.bosch_a), ], CAR.CIVIC_BOSCH_DIESEL: None, # same platform @@ -125,20 +125,20 @@ CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = { ], CAR.ACURA_ILX: HondaCarInfo("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS, harness=Harness.nidec), CAR.CRV: HondaCarInfo("Honda CR-V 2015-16", "Touring", harness=Harness.nidec), - CAR.CRV_5G: HondaCarInfo("Honda CR-V 2017-21", harness=Harness.bosch_a), + CAR.CRV_5G: HondaCarInfo("Honda CR-V 2017-22", harness=Harness.bosch_a), CAR.CRV_EU: None, # HondaCarInfo("Honda CR-V EU", "Touring"), # Euro version of CRV Touring CAR.CRV_HYBRID: HondaCarInfo("Honda CR-V Hybrid 2017-19", harness=Harness.bosch_a), - CAR.FIT: HondaCarInfo("Honda Fit 2018-19", harness=Harness.nidec), + CAR.FIT: HondaCarInfo("Honda Fit 2018-20", harness=Harness.nidec), CAR.FREED: HondaCarInfo("Honda Freed 2020", harness=Harness.nidec), - CAR.HRV: HondaCarInfo("Honda HR-V 2019-20", harness=Harness.nidec), - CAR.ODYSSEY: HondaCarInfo("Honda Odyssey 2018-20", min_steer_speed=0., harness=Harness.nidec), + CAR.HRV: HondaCarInfo("Honda HR-V 2019-22", harness=Harness.nidec), + CAR.ODYSSEY: HondaCarInfo("Honda Odyssey 2018-22", min_steer_speed=0., harness=Harness.nidec), CAR.ODYSSEY_CHN: None, # Chinese version of Odyssey CAR.ACURA_RDX: HondaCarInfo("Acura RDX 2016-18", "AcuraWatch Plus", harness=Harness.nidec), - CAR.ACURA_RDX_3G: HondaCarInfo("Acura RDX 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), - CAR.PILOT: HondaCarInfo("Honda Pilot 2016-21", harness=Harness.nidec), + CAR.ACURA_RDX_3G: HondaCarInfo("Acura RDX 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), + CAR.PILOT: HondaCarInfo("Honda Pilot 2016-22", harness=Harness.nidec), CAR.PASSPORT: HondaCarInfo("Honda Passport 2019-21", "All", harness=Harness.nidec), CAR.RIDGELINE: HondaCarInfo("Honda Ridgeline 2017-22", harness=Harness.nidec), - CAR.INSIGHT: HondaCarInfo("Honda Insight 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), + CAR.INSIGHT: HondaCarInfo("Honda Insight 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), CAR.HONDA_E: HondaCarInfo("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), } diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 2e6a2017ea..6e184ce9ef 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -156,10 +156,10 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { CAR.KIA_EV6: HyundaiCarInfo("Kia EV6 2022", "All", harness=Harness.hyundai_p), # Genesis - CAR.GENESIS_G70: HyundaiCarInfo("Genesis G70 2018", "All", harness=Harness.hyundai_f), + CAR.GENESIS_G70: HyundaiCarInfo("Genesis G70 2018-19", "All", harness=Harness.hyundai_f), CAR.GENESIS_G70_2020: HyundaiCarInfo("Genesis G70 2020", "All", harness=Harness.hyundai_f), - CAR.GENESIS_G80: HyundaiCarInfo("Genesis G80 2018", "All", harness=Harness.hyundai_h), - CAR.GENESIS_G90: HyundaiCarInfo("Genesis G90 2018", "All", harness=Harness.hyundai_c), + CAR.GENESIS_G80: HyundaiCarInfo("Genesis G80 2017-19", "All", harness=Harness.hyundai_h), + CAR.GENESIS_G90: HyundaiCarInfo("Genesis G90 2017-18", "All", harness=Harness.hyundai_c), } class Buttons: diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index ea923b1b50..8fac934285 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -41,18 +41,18 @@ class SubaruCarInfo(CarInfo): CAR_INFO: Dict[str, Union[SubaruCarInfo, List[SubaruCarInfo]]] = { - CAR.ASCENT: SubaruCarInfo("Subaru Ascent 2019-20", "All"), + CAR.ASCENT: SubaruCarInfo("Subaru Ascent 2019-21", "All"), CAR.IMPREZA: [ SubaruCarInfo("Subaru Impreza 2017-19"), SubaruCarInfo("Subaru Crosstrek 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), SubaruCarInfo("Subaru XV 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), ], CAR.IMPREZA_2020: [ - SubaruCarInfo("Subaru Impreza 2020-21"), + SubaruCarInfo("Subaru Impreza 2020-22"), SubaruCarInfo("Subaru Crosstrek 2020-21"), SubaruCarInfo("Subaru XV 2020-21"), ], - CAR.FORESTER: SubaruCarInfo("Subaru Forester 2019-21", "All"), + CAR.FORESTER: SubaruCarInfo("Subaru Forester 2019-22", "All"), CAR.FORESTER_PREGLOBAL: SubaruCarInfo("Subaru Forester 2017-18"), CAR.LEGACY_PREGLOBAL: SubaruCarInfo("Subaru Legacy 2015-18"), CAR.OUTBACK_PREGLOBAL: SubaruCarInfo("Subaru Outback 2015-17"), diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 723fa85820..f47ab87040 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -124,7 +124,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { ], CAR.COROLLAH_TSS2: [ ToyotaCarInfo("Toyota Corolla Hybrid 2020-22"), - ToyotaCarInfo("Lexus UX Hybrid 2019-21"), + ToyotaCarInfo("Lexus UX Hybrid 2019-22"), ], CAR.HIGHLANDER: ToyotaCarInfo("Toyota Highlander 2017-19", video_link="https://www.youtube.com/watch?v=0wS0wXSLzoo", footnotes=[Footnote.DSU]), CAR.HIGHLANDER_TSS2: ToyotaCarInfo("Toyota Highlander 2020-22"), @@ -151,14 +151,14 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { # Lexus CAR.LEXUS_CTH: ToyotaCarInfo("Lexus CT Hybrid 2017-18", "LSS", footnotes=[Footnote.DSU]), CAR.LEXUS_ESH: ToyotaCarInfo("Lexus ES Hybrid 2017-18", "LSS", footnotes=[Footnote.DSU]), - CAR.LEXUS_ES_TSS2: ToyotaCarInfo("Lexus ES 2019-21"), + CAR.LEXUS_ES_TSS2: ToyotaCarInfo("Lexus ES 2019-22"), CAR.LEXUS_ESH_TSS2: ToyotaCarInfo("Lexus ES Hybrid 2019-22", video_link="https://youtu.be/BZ29osRVJeg?t=12"), CAR.LEXUS_IS: ToyotaCarInfo("Lexus IS 2017-19"), CAR.LEXUS_NX: ToyotaCarInfo("Lexus NX 2018-19", footnotes=[Footnote.DSU]), CAR.LEXUS_NXH: ToyotaCarInfo("Lexus NX Hybrid 2018-19", footnotes=[Footnote.DSU]), - CAR.LEXUS_NX_TSS2: ToyotaCarInfo("Lexus NX 2020"), - CAR.LEXUS_NXH_TSS2: ToyotaCarInfo("Lexus NX Hybrid 2020"), - CAR.LEXUS_RC: ToyotaCarInfo("Lexus RC 2020"), + CAR.LEXUS_NX_TSS2: ToyotaCarInfo("Lexus NX 2020-21"), + CAR.LEXUS_NXH_TSS2: ToyotaCarInfo("Lexus NX Hybrid 2020-21"), + CAR.LEXUS_RC: ToyotaCarInfo("Lexus RC 2017-2020"), CAR.LEXUS_RX: ToyotaCarInfo("Lexus RX 2016-18", footnotes=[Footnote.DSU]), CAR.LEXUS_RXH: ToyotaCarInfo("Lexus RX Hybrid 2016-19", footnotes=[Footnote.DSU]), CAR.LEXUS_RX_TSS2: ToyotaCarInfo("Lexus RX 2020-22"), From ea449f1fe0bbff0eff5b12d64f0b5e75b7983998 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 12 Jul 2022 14:08:17 -0700 Subject: [PATCH 286/302] Use upstream wait-on-check-action action (#25126) Use upstream lewagon action --- .github/workflows/prebuilt.yaml | 2 +- .github/workflows/release.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/prebuilt.yaml b/.github/workflows/prebuilt.yaml index 7acc8a2254..99d9694f24 100644 --- a/.github/workflows/prebuilt.yaml +++ b/.github/workflows/prebuilt.yaml @@ -25,7 +25,7 @@ jobs: IMAGE_NAME: openpilot-prebuilt steps: - name: Wait for green check mark - uses: commaai/wait-on-check-action@f16fc3bb6cd4886520b4e9328db1d42104d5cadc + uses: lewagon/wait-on-check-action@e2558238c09778af25867eb5de5a3ce4bbae3dcd with: ref: master wait-interval: 30 diff --git a/.github/workflows/release.yaml b/.github/workflows/release.yaml index fb5a37eeef..8df89dcc38 100644 --- a/.github/workflows/release.yaml +++ b/.github/workflows/release.yaml @@ -12,7 +12,7 @@ jobs: if: github.repository == 'commaai/openpilot' steps: - name: Wait for green check mark - uses: commaai/wait-on-check-action@f16fc3bb6cd4886520b4e9328db1d42104d5cadc + uses: lewagon/wait-on-check-action@e2558238c09778af25867eb5de5a3ce4bbae3dcd with: ref: master wait-interval: 30 From b632d56244c5fd6821477a642d6f151ea4b13b20 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Tue, 12 Jul 2022 16:39:13 -0700 Subject: [PATCH 287/302] UI: change wording for dcam preview description (#25142) --- selfdrive/ui/qt/offroad/settings.cc | 2 +- selfdrive/ui/translations/main_ja.ts | 4 ++-- selfdrive/ui/translations/main_ko.qm | Bin 20040 -> 19981 bytes selfdrive/ui/translations/main_ko.ts | 4 ++-- selfdrive/ui/translations/main_zh-CHS.qm | Bin 18508 -> 18469 bytes selfdrive/ui/translations/main_zh-CHS.ts | 4 ++-- selfdrive/ui/translations/main_zh-CHT.qm | Bin 18568 -> 18509 bytes selfdrive/ui/translations/main_zh-CHT.ts | 6 +++--- 8 files changed, 10 insertions(+), 10 deletions(-) diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index d5b8d4bbd1..9aeb966ccf 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -102,7 +102,7 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { // offroad-only buttons auto dcamBtn = new ButtonControl(tr("Driver Camera"), tr("PREVIEW"), - tr("Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off)")); + tr("Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off)")); connect(dcamBtn, &ButtonControl::clicked, [=]() { emit showDriverView(); }); addItem(dcamBtn); diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 5c0f54a314..f3b8733128 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -134,8 +134,8 @@ - Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off) - ドライバーカメラのプレビューにより、デバイスの取り付け位置を最適化し、最高のドライバーモニタリング体験を提供します。(車両の電源を切る必要があります) + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) + ドライバー向けカメラをプレビューする、ドライバーモニタリングの視認性を確保します。(車両の電源を切る必要があります) diff --git a/selfdrive/ui/translations/main_ko.qm b/selfdrive/ui/translations/main_ko.qm index c5c66d1e73491c2ff09d91b6fdd5200002b2a6da..40b0bb65a38d65ee901ac7a85257e88868b4513c 100644 GIT binary patch delta 1903 zcmX9;Yfx2H7+v?=bMEupb1%xnv5>m`N23+hBMX66Gk z3REhz6o^d786aOtzL1B83 z7}gP&0zTV_{I|2PWxJT56j%%-hyzN)w4{`mcz^qb;mDd1`3bBpIE`T7QFmrF$=$mg~vO&eh5!!L78*TA!^bT;N{|&LK<{_){5O-h8BF+`-f7nVpYQ*N(Yk&kr zJS0;W<(_!v*Iv$Ni)U`#p^!uM;??QRw4YTnO(5ZMsgk8MpZsa1I3<_@*`@i5DafQ~ z$zl4APU(|!f@;ZAg_QHeQKmTJKivPdwEDGGj9(+Y8KtlX;-u1TEX0)WM)kfM10viQ zA1hUb)=)_ARH^C%IzkSYYTjE%CMu+T?S15Dnsj0?h|Sv|o%BCP0rXPuB^DICUFu)k zNud+nIBTEuXpjYtgHG^IqjPd}%3V7dd`UOuW&#<^)y-~f0j53BWoXFz$Thm^hmV24 zak@vzJtef*Q~H1qQWYxbYlpAp%?9=Ra{HOMKz}!NH>sPb|K}DN(caPjJNY^=qSFu; z(#n_Ph#^VKLTwif*|-0t}eJv?V*kH_9K#E8GXv}Jh1x9xpw}8$D>mE(1$ipLak)DlzWk!t$UVXC_DA_eI(?d+nk;&@ZTh6?gi zZ8{t-u~X-iza{yUY&P9^)kQX7*6e?qt2T4su~W>YF(+K!2n>xgFTBb=5B}bqe_kX> zbIfasJV}nl-1a+JAN`cM<2jPy{f_K;jM>7^$^MO;A5|%bOc8_PRRkCM~3^1KrNdGhjkEMMx9w?BG`2kep?KVex&5b#&hFs zW#gyp-_QYN$MqSMJx}?nhKZv8R$3lV?h$3m*%?35zbCAQKlt()lB}LH*|9PGR_|XQ z0}}-6oNGKUs>Pb@qJNDxYp!D;f`T{_~&j z{9m2@f7hRVh_i~*uYh>1WEv2%~R&*08W0Nkh}Y*$*w{O+dc-;TOjNo z1XK!y=6EKpfYA9j;zsN;4^VTD54}v6}kL z71PY&q-_%mma!po)`%t2MZok2@r|%r>U3Rv!|Nz%Gx0I=zY;gTzJc+L;+yei-hs{H zjt@yhsvE=L*f9)QHHP!w65UZXY-B*S=zgD$kXMQ|?{1|M*Tt_}Z&RO*V$*0CFK@kg zC75@@Cspk0C!z3vigzm7+2}1}nEpT<870Bz61D2!JUXjZYkm|>1wYUx-Or$cc5SBT z0x&O5yF^9Zr#5Pj4L=1!OSO&B2V8)`M>~?+L#yTMLLwKph>aHXX_3vGAdmIg8WQ&P*IR#jLWytatJfX`g0|~FIl(&q zKKe6vL;0R#(3$>32fbzpb?bRmA`B_NxJr03mEo0~K{9PJE3cDrAsub&TeLWjxqGoRT4@vX56ael-O)sI>4bYMQ2=nLm=@A<2&p8 zsG!N%@*`U`E#KJoA{7g`Ap2b+fjC)q1$+1*;)eWe@ zl}gMjlk@knU~r{e`jVGer~J{#A9;d*%bwl5Ys!am`w=QPxQ5R?ZQZfw zFGH!j(9_$R4y9G-aq@p{SAjRKwf0)1cde_yTg#jMue_dRO%u4bz3Ggn%`=E-D2TWg zajyO9&wJ{9rs}sXbXeEftn2rb&Yzg;EK^okSCuPeG4b? - Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off) - 운전자 카메라를 미리 보면서 최적의 운전자 모니터링 경험을 위해 장치의 장착 위치를 최적화할수 있습니다. (차량연결은 해제되어있어야 합니다) + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) + 운전자 모니터링이 좋은 가시성을 갖도록 운전자를 향한 카메라를 미리 봅니다. (차량연결은 해제되어있어야 합니다) diff --git a/selfdrive/ui/translations/main_zh-CHS.qm b/selfdrive/ui/translations/main_zh-CHS.qm index 45fae52b4286bb3e57938bf6c7c4ad53d3bd3ba1..2c7963cf17a496e356fb5b0372b565ac82514661 100644 GIT binary patch delta 1858 zcmX9;c~n$o9KAF1-Yjos-a{S41!UL+6j=%v1Q9VYutb!QLNf^(#t;$)lw8Qv6e+{N zB*hgF%gl4ousB+pNTOkJva&doq6lb2+bI&ku7~;O&ij_%cfWh@@B6AmRb8SgaV>lb zP!9kT0s)PUxPZ8tm_yu6ECU42%LYIU0w#V*3-2adpVN7n%}{jv0X6XzdbWtu1VzlAje+;5J+q03i+C=+TO&jbEZXc!UC zi=0Bo_B_rPt44+epb*~6RipNMQ|lj9lXuY1kWs3HMt{IZquTQw$EOXbt|kgBoUFR8 zt_0kys_w@(17rSDOSX%EUxnJIqn-P%t79YwiS1M`apH}GFRJ%lV;0;p)u-PivBx6S zpT*K^WvTkx1lAoVs@s}Uo&W-Ot8W~12F509gg_U-5}oy9Y>C6; zg0=VKzbj=T|$hyUYlXSfc4^z5y-M@FKh^AiGAKnSL-qX+a zZ{W*Or;pQ+s8Xg+@98JOB>h`?dpK{?A2`N3BUb4@?(pJwfI(+o#^lU0cva}xB0h#$ zf7-bI4Z}0@Cf%m=0fwYalq~9~A!P|A9`9;MYm6o#7gL1Z9!{LWz`rULcPjioAe9Z$NT1VE`I$-{-y>CAe};y%Nc)>xtf0%3!u zdC|P%^m0?uF4ik_&oHf=Px|6w)9(9=S)j&LyOZrRuE5lEkfH=nFn!fZ4E)~I+DL-J z4zsq}n|QNz z|N8wX@9T`B?LP7cRXk|&X!-0vwA=NRd^L)1w2MX2|IU|B*Qi)#v12E9D32lK0cP06x#gixxvO3C#tv^hh0FFlKrJybq_4W6w{|v98R{vOBVK>{&Kz#`0XNEjv5Sns3jwr`j{^ Mj)Id#P8X*B4>phSf&c&j delta 1954 zcmX9;4Nz3)6+Qd*z5RK+`yS{@tWjAPP!PnWK@>$nXdt2m5kw|v%m6RzCbA$dAWd{* z#3+#>4jPr9!3Z&_wV6Sqi7{#vu^2&R#e*;unC(?}`hMrUQ}xCe8t(W)SnaM;k#W z_ZuDp0XqTX1mdT}c;Y{ZX8~I+V7&;090n#|0|I{sOyRyIfvJ4p#=w2R^VNW>14!S> zLNkFy*~B-2tQaQwjkpR33M6jkdMB{@01K1>Yo8K-1$@KbckK8%*#9lWE$;#I9zxvH z2k2yo?Xe764zcSqVk^WeA`m%g>wNW04pV>jRha{F^RgYjtC%Zs;==m z*W*KV-8mu?`*k;jgTRC|-M#0kfoI1FvikxMeqIRczspN=*zR1c;<`x!wQ*4Df+hKisBS>4Sao|I z;J7QkQ9wF|DshYWUm)(HxM#sB+A($nRp$uW&y1iWL~LpqB&&Ji2Yp4v4dP#~>;jzU z#AC0uP*1n`xs`LV^@?Br*h8B-#IJv%)%}4F#M_C-Xg|Ls$5HUP|B-Cl)&R4*r4%KM zw3kVFFLNMqDB((kB;hQJ-Mx+)yYF?{?|@q;Ke` z`%+IY358@xKWyp*LNAYCVvzKBhykSF_c=incGNiSA3C!MT z$k$Q#Fwt;u@F_59nc-CQUO$)eqqvnenO(_O@A(L1jg5y-apJdqxYCT z?GNF5w%KS~Ne8VmhcuaZR2G@%KlHm9aKyZHVIM~jWzOA1>5{IP^OsZV$tmWdj${&= zVy*)nhWE|adNSy!1Loeq5?)J(<@u4**`XpAUF~AWX>!dyUOB-9#JTMBfV}OF%J&X= z=TnY2?54cu)ImDcE;rp+%25r<`~6*qL}sn>IX43(QErzf@^<-3 zZVyTzq3iP9LLa3Iv*?a*pwyL?kh2#^D9Dm}vj!M7)w1F?FNKixmNnmrBwl0LSYc=U z6HCW^j%Z4r_Om1qEn5AP+W29zYMnN>ie`CaO-_H>Y-SZ6b| zhO%I~ZTf_Nl1RKQeuzY$J#9O}s|`-O-*%#s5AjvDcISumLbk0vnK&iJb}4~gkPB_s z@_0P$Z!2RyZsq!*GHweM80}D;gDJoagEH$@6wUWQSy)R2N9QYRlAouUqm-KWc-SML z?7NdhZ!A*&(!x43l9Vrhp(n=oDBVd{Y4+SXs_6mmNn?j|X9m-<2< z6UMx&dfok;omZ{Dv6&uNrS8?dBsN(+Q~Ez3;e^_IcRxEBP;aIFjqgqmFn`q1*~V&< zZgImIb!>8Zct%~VUi0PGY`swP?MokK^lv(`aa6w=~!SLKm&lR+lvoiu wto8UjC0@rXC1s8RZLQByROYGB%DBVp@s*Sf@6pzkYGoeHTc{l^2sl6U|7&9g_5c6? diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 04bd2415f0..d9377054a5 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -134,8 +134,8 @@ - Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off) - 打开并预览驾驶员摄像头,用于调整安装角度以获得最优驾驶员监控体验。仅熄火时可用。 + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) + 打开并预览驾驶员摄像头,以确保驾驶员监控具有良好视野。仅熄火时可用。 diff --git a/selfdrive/ui/translations/main_zh-CHT.qm b/selfdrive/ui/translations/main_zh-CHT.qm index 130bcfc92670cff84c6c6fcf359be599e4941e3e..0d448f2080322661cb712bd3c06b4049fabbf935 100644 GIT binary patch delta 1928 zcmX9;3s93+8a+w=KhHmZP=oDKfd~N+1cJo}2!c?s;I4q6wMF}&U`Ry}2%v+STA!3^ zrT73vtqQd-*BP|fwZ(NSVxbMTQ*7;I=_-n-W0$SnSzKN0o=!58Imx}>{l0V0cfPy5 zLE+w|*fq&z1(ajJ)cb(S4uqSDHN@$}eZ*`);J$GL5Tk(z2XPLugP6~lm%JDh1gM$A zCk@c}6IT%9h}($gc|Hq}E&;)@KxjYLdx0s8TjVp!9}FC~5J=k$*n)w~?JRr__+u^$ zDS(_9CLw{GV!-zc;ufxF0wqV7i1C$=iSGkW?oXWE@N=LmAHuc+z}z7SO*a9B455pa z!v`R^Kjq<22$uyQ;26X=Ex@!~h$oH%h9yvU{6yRUjb$m5$ z@(MPxFtFr!E1*lj(v01V8^#OouLF|Ou>5a5+&_v{g_PE}9BamS-WY}>y?sD(7}}jL zvTZ=u1WFrFf}uC7xL>K57&i?rSbY^w9AvF5)0+W5k5X^H2!s_VLxu){m;z{~qN)PyRDNRG{+OyS~6v&!~i`Cjj$!mH$1F0b5l;^+~+h z1yxlJ6VDt~eI%24#12(^2hC$?c~SOw(Y(%!f$c&|>jO6Kq;T|RA#qsv`0^egXn}Bg zWh?buCj3QWUyO%@uWos`{(F=@nnIwo#`(@wML_r7I%R;#xm(?TR(L_EfPpR^}YI#QMD?qI=tm z0hhcO_{fV%`^A=sRyNZ7vDor99buRzwr<@*B|a5TUb;qoUKhU@vvPRr#S4?arK8$J z&j1Mp{UF}h)Wb$U@5Lm8_;8E_qux;~C+E>wU21tGiV6m+6Yiu_!CUJ2?VUh;iaK9G z-K`DkV-Fs4e^C7}>xzp`aBG65QmQHUG;MyH*zsu1$9VS-QiOc@Cz}K=i~MD!zQjT*6)7I)`k@6n?65A zLT-J_)x~U4jsB3EtyVqKpOCljreve~vo?{#8{W8He8RO_fBRJ@1v+g|bZp>mi6Qv> zMOyHbA^oR1z6Bn`@&M>e1raL=)T8BgpL@#{1f#t|6MYlXSv8K zX>vQ)L-tCMiEHVIPANT=4Ndq_%ACC%i0hXYr10ADuS-kzFrOjUr|5R+YY#E%Mak1mg2FpSb(@u=t}#aY|3D&%#<(#OeX7oQB9{A; z4;s(Z5aU9PT|w{Bs%gfq6k_O?#@+-rULS7kU&z`w9%4N8f3q1RABtKa?pcR z>e49BzQ&gEn6)IJnLsWhftSGTb9 z#ir(>QcCuV>94E*N69vr25ukX46HF-OaC)4=Y|8AH{n#g=B&mjHD77=-kyR`A75pYG99nZWYapjOr^c>(qwM+hb$c87Y|8A5 z&xMt5UcGWfO72Kim`zEq(q#OWH2%TI8dFqSSyfSFaTdSgv=ml2s*5TttIA3p&aw(e fsohfiN~OhKR#s@Kc2qhF93>9t+EaBtzs>qT^2rE( delta 2026 zcmX|B3sjV48h+-V|DVf0|I80^v10?s1I0^;v8|aMEKJ0_gd`?rCv4qiaY@13X6{;NBVBMG4!b+&%z0+M?|a|x`JVTA z-}cR#jaxLEM|xfcgnnRb6rjx|+K45@JmOAbB_ML&G8T}=1LNw5Q;Gj1X7LQ;2Qg$3 zpnCv#tp)S}#CM4C#IwZHfVl!tz5qh=fl(cRw*-vlxw+o4{K13X<-jv#K+H=(+D2ad z3-IgT@S!CM>3h~xz6tjUgE{`s|JWS05|vjS8cf$ppcEGk`D`gXq@f`{HeT%uT{ltJO z%o9H6x()NP-{8elv7o*VFqU9p>NZ{&f*1bqDv7VfqBCvW??PTq2;)CMX+Pu5cD!@p z5|C&|gPSiOGZig9ELmVZdMk>!|Dnb|J`x^;WoVw*8%C|a)l8~lJ!85wnXO}hum_r5 zSGXQ;&|I1)GI5FKs&D`Zh|=77stkD2UyyUp0TFwI@ZRgdggruv>?W~Y!i!#faZH)8 zr^CqedBU+xBo-?PpQTm-YN_x|Ci4c0LRVYXuYl+mgzo)*Oz6>y(Zd1XIog2lS@eK2 z+K|cwzHC5Sl*z zSKDdZH^q;a*HO=%;&Fv_G5=Zo@@6O3d&DpA{=hDR3cjS9b|-}j-qg)% zI0;O7O_!yi?qL^o2l@tp-~e57bd871UAl+1E3}$HA2NoLMU2)T9I=isT&6$bx5!@fhz z<5Ok$q&JlRXBqWoPLseyV`!~`ts)we9(ZyYaKJc!b`MJsV_dL~(k1DQSuaxRQ5s`T zYci+DBV!flFzhpSbf(i$Ym8mq95d1hIcXe6mTrWcbGe-__Lj@H< z(;LOUjQ_>d`aMfDdaUXE94h8FT=6|k0#P3+p5O*O6!{?Y_t+s~+>Q68?x^Y;Fm8k6uVJwHE6H@BM>Zzi1h;feQF2mXN-gRO*sta(5&z-ej4*i3B+)AW35-oqM<2{oMmXrUYCq|yJTuQtQ3||nS8vemKsc%$$li1&r{-XNd z9N^d~QlIT%!U?geE4P;lC99jSuBQix$~_{9V-f~`2}ugp7Xcd<1xF# znwMYXaywnQ)`I+1PPa4PWnGeAXw7!4a{o7)CtOZ9zXpb D32iIQ diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 806dd54ad3..efd893ec4c 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -125,7 +125,7 @@ Driver Camera - 駕駛監控 + 駕駛員攝像頭 @@ -134,8 +134,8 @@ - Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off) - 預覽駕駛監控鏡頭畫面,方便調整設備安裝的位置,以提供更準確的駕駛監控。(車子必須保持在熄火的狀態) + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) + 預覽駕駛員監控鏡頭畫面,以確保其具有良好視野。僅在熄火時可用。 From ee6dc0311818fd97cb78c58fb9a47267385312a0 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 12 Jul 2022 17:25:54 -0700 Subject: [PATCH 288/302] fix accord years --- docs/CARS.md | 2 +- selfdrive/car/honda/values.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index c3efe87515..ec7da7a845 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -161,7 +161,7 @@ How We Rate The Cars |Chrysler|Pacifica Hybrid 2019-22|Adaptive Cruise|||||| |Genesis|G90 2017-18|All|||||| |GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise|||||| -|Honda|Accord 2016-22|All|||||| +|Honda|Accord 2018-22|All|||||| |Honda|Accord Hybrid 2018-22|All|||||| |Honda|Civic 2016-18|Honda Sensing|||||| |Honda|Civic 2019-21|All|||[2](#footnotes)||| diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index bfa42bd509..b8417ee19b 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -109,7 +109,7 @@ class HondaCarInfo(CarInfo): CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = { CAR.ACCORD: [ - HondaCarInfo("Honda Accord 2016-22", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), + HondaCarInfo("Honda Accord 2018-22", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), HondaCarInfo("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), ], CAR.ACCORDH: HondaCarInfo("Honda Accord Hybrid 2018-22", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), From 00bb07f6248010afb197854257c2958433159990 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 12 Jul 2022 17:45:00 -0700 Subject: [PATCH 289/302] fw_versions.py: fix debug scanning (#25144) * Fix scanning all requests * fix replace --- selfdrive/car/fw_versions.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index c4b158aebb..a8f5357f0e 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -394,7 +394,7 @@ def get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs, timeout=0.1, debug=Fa brand_matches = get_brand_ecu_matches(ecu_rx_addrs) for brand in sorted(brand_matches, key=lambda b: len(brand_matches[b]), reverse=True): - car_fw = get_fw_versions(logcan, sendcan, brand=brand, timeout=timeout, debug=debug, progress=progress) + car_fw = get_fw_versions(logcan, sendcan, query_brand=brand, timeout=timeout, debug=debug, progress=progress) all_car_fw.extend(car_fw) matches = match_fw_to_car_exact(build_fw_dict(car_fw)) if len(matches) == 1: @@ -403,10 +403,10 @@ def get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs, timeout=0.1, debug=Fa return all_car_fw -def get_fw_versions(logcan, sendcan, brand=None, extra=None, timeout=0.1, debug=False, progress=False): +def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1, debug=False, progress=False): versions = get_interface_attr('FW_VERSIONS', ignore_none=True) - if brand is not None: - versions = {brand: versions[brand]} + if query_brand is not None: + versions = {query_brand: versions[query_brand]} if extra is not None: versions.update(extra) @@ -434,7 +434,7 @@ def get_fw_versions(logcan, sendcan, brand=None, extra=None, timeout=0.1, debug= addrs.insert(0, parallel_addrs) fw_versions = {} - requests = [r for r in REQUESTS if brand is None or r.brand == brand] + requests = [r for r in REQUESTS if query_brand is None or r.brand == query_brand] for addr in tqdm(addrs, disable=not progress): for addr_chunk in chunks(addr): for r in requests: @@ -503,7 +503,7 @@ if __name__ == "__main__": print() t = time.time() - fw_vers = get_fw_versions(logcan, sendcan, brand=args.brand, extra=extra, debug=args.debug, progress=True) + fw_vers = get_fw_versions(logcan, sendcan, query_brand=args.brand, extra=extra, debug=args.debug, progress=True) _, candidates = match_fw_to_car(fw_vers) print() From 44c6ca7eb4c9ea83aca18d4f648764cabdad8861 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 12 Jul 2022 18:23:48 -0700 Subject: [PATCH 290/302] EV6: reject fake cruise engagements (#25143) * EV6: reject fake cruise engagements * bump panda * raise to 8 * update refs * bump panda Co-authored-by: Comma Device --- opendbc | 2 +- panda | 2 +- selfdrive/car/hyundai/carcontroller.py | 4 ++-- selfdrive/car/hyundai/carstate.py | 11 ++++++++--- selfdrive/car/hyundai/hda2can.py | 8 +++----- selfdrive/car/hyundai/interface.py | 5 ++--- selfdrive/car/hyundai/values.py | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 8 files changed, 19 insertions(+), 17 deletions(-) diff --git a/opendbc b/opendbc index 81148db67f..3fb3f5e821 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 81148db67fd00d4e2a107b5b8269c532436edf2b +Subproject commit 3fb3f5e82129ad76232bcdca10632ed0566b20f8 diff --git a/panda b/panda index baecd2ecc6..2abeab913f 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit baecd2ecc6a2a608e1305601f6f697feca69fe88 +Subproject commit 2abeab913f6432e4327b07e247b8a46994ac77a1 diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index a878ad3274..d0d9c40839 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -82,12 +82,12 @@ class CarController: if (self.frame - self.last_button_frame) * DT_CTRL > 0.25: if CC.cruiseControl.cancel: for _ in range(20): - can_sends.append(hda2can.create_buttons(self.packer, CS.buttons_counter+1, True, False)) + can_sends.append(hda2can.create_buttons(self.packer, CS.buttons_counter+1, Buttons.CANCEL)) self.last_button_frame = self.frame # cruise standstill resume elif CC.cruiseControl.resume: - can_sends.append(hda2can.create_buttons(self.packer, CS.buttons_counter+1, False, True)) + can_sends.append(hda2can.create_buttons(self.packer, CS.buttons_counter+1, Buttons.RES_ACCEL)) self.last_button_frame = self.frame else: diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index a10cdadbca..8afd851f00 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -8,7 +8,7 @@ from opendbc.can.can_define import CANDefine from selfdrive.car.hyundai.values import DBC, FEATURES, HDA2_CAR, EV_CAR, HYBRID_CAR, Buttons, CarControllerParams from selfdrive.car.interfaces import CarStateBase -PREV_BUTTON_SAMPLES = 4 +PREV_BUTTON_SAMPLES = 8 class CarState(CarStateBase): @@ -171,7 +171,10 @@ class CarState(CarStateBase): speed_factor = CV.MPH_TO_MS if cp.vl["CLUSTER_INFO"]["DISTANCE_UNIT"] == 1 else CV.KPH_TO_MS ret.cruiseState.speed = cp.vl["CRUISE_INFO"]["SET_SPEED"] * speed_factor - self.buttons_counter = cp.vl["CRUISE_BUTTONS"]["_COUNTER"] + self.cruise_buttons.extend(cp.vl_all["CRUISE_BUTTONS"]["CRUISE_BUTTONS"]) + self.main_buttons.extend(cp.vl_all["CRUISE_BUTTONS"]["ADAPTIVE_CRUISE_MAIN_BTN"]) + self.buttons_counter = cp.vl["CRUISE_BUTTONS"]["COUNTER"] + self.cam_0x2a4 = copy.copy(cp_cam.vl["CAM_0x2a4"]) return ret @@ -362,7 +365,9 @@ class CarState(CarStateBase): ("CRUISE_ACTIVE", "SCC1"), ("SET_SPEED", "CRUISE_INFO"), ("CRUISE_STANDSTILL", "CRUISE_INFO"), - ("_COUNTER", "CRUISE_BUTTONS"), + ("COUNTER", "CRUISE_BUTTONS"), + ("CRUISE_BUTTONS", "CRUISE_BUTTONS"), + ("ADAPTIVE_CRUISE_MAIN_BTN", "CRUISE_BUTTONS"), ("DISTANCE_UNIT", "CLUSTER_INFO"), diff --git a/selfdrive/car/hyundai/hda2can.py b/selfdrive/car/hyundai/hda2can.py index 437f5cf538..9a9e477cf5 100644 --- a/selfdrive/car/hyundai/hda2can.py +++ b/selfdrive/car/hyundai/hda2can.py @@ -18,11 +18,9 @@ def create_cam_0x2a4(packer, frame, camera_values): }) return packer.make_can_msg("CAM_0x2a4", 4, camera_values, frame % 255) -def create_buttons(packer, cnt, cancel, resume): +def create_buttons(packer, cnt, btn): values = { - "_COUNTER": cnt % 0xf, "SET_ME_1": 1, - "DISTANCE_BTN": 1 if resume else 0, - "PAUSE_RESUME_BTN": 1 if cancel else 0, + "CRUISE_BUTTONS": btn, } - return packer.make_can_msg("CRUISE_BUTTONS", 5, values) + return packer.make_can_msg("CRUISE_BUTTONS", 5, values, cnt % 0xf) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 069b0e74e5..a32ee2c0ab 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -2,7 +2,7 @@ from cereal import car from panda import Panda from common.conversions import Conversions as CV -from selfdrive.car.hyundai.values import CAR, DBC, HDA2_CAR, EV_CAR, HYBRID_CAR, LEGACY_SAFETY_MODE_CAR, Buttons, CarControllerParams +from selfdrive.car.hyundai.values import CAR, DBC, EV_CAR, HYBRID_CAR, LEGACY_SAFETY_MODE_CAR, Buttons, CarControllerParams from selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR from selfdrive.car import STD_CARGO_KG, create_button_enable_events, create_button_event, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase @@ -321,8 +321,7 @@ class CarInterface(CarInterfaceBase): # To avoid re-engaging when openpilot cancels, check user engagement intention via buttons # Main button also can trigger an engagement on these cars allow_enable = any(btn in ENABLE_BUTTONS for btn in self.CS.cruise_buttons) or any(self.CS.main_buttons) - allow_enable = allow_enable or self.CP.carFingerprint in HDA2_CAR - events = self.create_common_events(ret, pcm_enable=self.CS.CP.pcmCruise, allow_enable=allow_enable or True) + events = self.create_common_events(ret, pcm_enable=self.CS.CP.pcmCruise, allow_enable=allow_enable) if self.CS.brake_error: events.add(EventName.brakeUnavailable) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 6e184ce9ef..ffa29c60d4 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -167,7 +167,7 @@ class Buttons: RES_ACCEL = 1 SET_DECEL = 2 GAP_DIST = 3 - CANCEL = 4 + CANCEL = 4 # on newer models, this is a pause/resume button FINGERPRINTS = { CAR.ELANTRA: [{ diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index b165b163ba..e77a38de5f 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -11e721366f1c177a84e6cb8b48171113ac3b54f9 \ No newline at end of file +5efbbdf69e16db3d989bfaf62d10e958e80b9ca2 \ No newline at end of file From aadaaabd54988a286704ef2bea0bacf4bd62fa8b Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 12 Jul 2022 18:58:46 -0700 Subject: [PATCH 291/302] compatibility docs: print diff from PR (#24941) * print docs diff * revert car changes * cause a diff * temp so it works * text diff * tier inline is a bit too much * comments * fix * use paths * fix * temp * temp * diff * fix * remove something * more text diff * Delete comment if outdated * Smaller diff * remove * no diff * Don't try to run on fork PRs * cause some errors * Fix * Fix * Doesn't support env in job if, only step if * in case file was moved, don't throw error * See if this does what I think it does * See if this does what I think it does * should work * change something * revert * uncomment * no comment * this shouldn't fail * rename to base * Remove true * Remove other true --- .github/workflows/selfdrive_tests.yaml | 71 +++++++++++++++++++- selfdrive/debug/dump_car_info.py | 18 ++++++ selfdrive/debug/print_docs_diff.py | 90 ++++++++++++++++++++++++++ 3 files changed, 176 insertions(+), 3 deletions(-) create mode 100755 selfdrive/debug/dump_car_info.py create mode 100755 selfdrive/debug/print_docs_diff.py diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 99a21b58f3..298ea5fb49 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -10,6 +10,7 @@ env: CL_BASE_IMAGE: openpilot-base-cl DOCKER_REGISTRY: ghcr.io/commaai AZURE_TOKEN: ${{ secrets.AZURE_COMMADATACI_OPENPILOTCI_TOKEN }} + HAS_AZURE_TOKEN: $AZURE_TOKEN != '' DOCKER_LOGIN: docker login ghcr.io -u adeebshihadeh -p ${{ secrets.CONTAINER_TOKEN }} BUILD: | @@ -17,12 +18,12 @@ env: docker pull $DOCKER_REGISTRY/$BASE_IMAGE:latest || true docker build --cache-from $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $BASE_IMAGE:latest -f Dockerfile.openpilot_base . - RUN: docker run --shm-size 1G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/scons_cache:/tmp/scons_cache -v /tmp/comma_download_cache:/tmp/comma_download_cache $BASE_IMAGE /bin/sh -c + RUN: docker run --shm-size 1G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/scons_cache:/tmp/scons_cache -v /tmp/comma_download_cache:/tmp/comma_download_cache -v /tmp/openpilot_cache:/tmp/openpilot_cache $BASE_IMAGE /bin/sh -c BUILD_CL: | docker pull $DOCKER_REGISTRY/$CL_BASE_IMAGE:latest || true docker build --cache-from $DOCKER_REGISTRY/$CL_BASE_IMAGE:latest -t $DOCKER_REGISTRY/$CL_BASE_IMAGE:latest -t $CL_BASE_IMAGE:latest -f Dockerfile.openpilot_base_cl . - RUN_CL: docker run --shm-size 1G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/scons_cache:/tmp/scons_cache -v /tmp/comma_download_cache:/tmp/comma_download_cache $CL_BASE_IMAGE /bin/sh -c + RUN_CL: docker run --shm-size 1G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/scons_cache:/tmp/scons_cache -v /tmp/comma_download_cache:/tmp/comma_download_cache -v /tmp/openpilot_cache:/tmp/openpilot_cache $CL_BASE_IMAGE /bin/sh -c UNIT_TEST: coverage run --append -m unittest discover @@ -365,7 +366,7 @@ jobs: name: process_replay_diff.txt path: selfdrive/test/process_replay/diff.txt - name: Upload reference logs - if: ${{ failure() && github.event_name == 'pull_request' && github.repository == 'commaai/openpilot' && env.AZURE_TOKEN != '' }} + if: ${{ failure() && github.event_name == 'pull_request' && github.repository == 'commaai/openpilot' && env.HAS_AZURE_TOKEN }} run: | ${{ env.RUN }} "scons -j$(nproc) && \ CI=1 AZURE_TOKEN='$AZURE_TOKEN' python selfdrive/test/process_replay/test_processes.py -j$(nproc) --upload-only" @@ -510,3 +511,67 @@ jobs: run: | $DOCKER_LOGIN docker push $DOCKER_REGISTRY/openpilot-docs:latest + + car_docs_diff: + name: comment on PR with car docs diff + runs-on: ubuntu-20.04 + timeout-minutes: 50 + if: github.event_name == 'pull_request' + steps: + - uses: actions/checkout@v3 + with: + submodules: true + ref: ${{ github.event.pull_request.base.ref }} + - name: Cache scons + id: scons-cache + # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. + uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b + env: + CACHE_SKIP_SAVE: true + with: + path: /tmp/scons_cache + key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- + restore-keys: | + scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- + scons- + - name: Build Docker image + run: eval "$BUILD" + - name: Get base car info + run: | + ${{ env.RUN }} "scons -j$(nproc) && python selfdrive/debug/dump_car_info.py --path /tmp/openpilot_cache/base_car_info" + sudo chown -R $USER:$USER ${{ github.workspace }} + - uses: actions/checkout@v3 + with: + submodules: true + - name: Save car docs diff + id: save_diff + run: | + ${{ env.RUN }} "scons -j$(nproc)" + output=$(${{ env.RUN }} "python selfdrive/debug/print_docs_diff.py --path /tmp/openpilot_cache/base_car_info") + output="${output//$'\n'/'%0A'}" + echo "::set-output name=diff::$output" + - name: Find comment + if: env.HAS_AZURE_TOKEN + uses: peter-evans/find-comment@v1 + id: fc + with: + issue-number: ${{ github.event.pull_request.number }} + body-includes: This PR makes changes to + - name: Update comment + if: steps.save_diff.outputs.diff != '' && env.HAS_AZURE_TOKEN + uses: peter-evans/create-or-update-comment@v1 + with: + comment-id: ${{ steps.fc.outputs.comment-id }} + issue-number: ${{ github.event.pull_request.number }} + body: "${{ steps.save_diff.outputs.diff }}" + edit-mode: replace + - name: Delete comment + if: steps.fc.outputs.comment-id != '' && steps.save_diff.outputs.diff == '' && env.HAS_AZURE_TOKEN + uses: actions/github-script@v6 + with: + script: | + github.rest.issues.deleteComment({ + owner: context.repo.owner, + repo: context.repo.repo, + comment_id: ${{ steps.fc.outputs.comment-id }} + }) diff --git a/selfdrive/debug/dump_car_info.py b/selfdrive/debug/dump_car_info.py new file mode 100755 index 0000000000..c9a21c2848 --- /dev/null +++ b/selfdrive/debug/dump_car_info.py @@ -0,0 +1,18 @@ +#!/usr/bin/env python3 +import argparse +import pickle + +from selfdrive.car.docs import get_all_car_info + + +def dump_car_info(path): + with open(path, 'wb') as f: + pickle.dump(get_all_car_info(), f) + print(f'Dumping car info to {path}') + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("--path", required=True) + args = parser.parse_args() + dump_car_info(args.path) diff --git a/selfdrive/debug/print_docs_diff.py b/selfdrive/debug/print_docs_diff.py new file mode 100755 index 0000000000..5cf3867b2d --- /dev/null +++ b/selfdrive/debug/print_docs_diff.py @@ -0,0 +1,90 @@ +#!/usr/bin/env python3 +import argparse +import pickle + +from selfdrive.car.docs import get_all_car_info +from selfdrive.car.docs_definitions import Column + +STAR_ICON = '' +COLUMNS = "|" + "|".join([column.value for column in Column]) + "|" +COLUMN_HEADER = "|---|---|---|:---:|:---:|:---:|:---:|:---:|" +ARROW_SYMBOL = "➡️" + + +def load_base_car_info(path): + with open(path, "rb") as f: + return pickle.load(f) + + +def get_star_diff(base_car, new_car): + return [column for column, value in base_car.row.items() if value != new_car.row[column]] + + +def format_row(builder): + return "|" + "|".join(builder) + "|" + + +def print_car_info_diff(path): + base_car_info = {f"{i.make} {i.model}": i for i in load_base_car_info(path)} + new_car_info = {f"{i.make} {i.model}": i for i in get_all_car_info()} + + tier_changes = [] + star_changes = [] + removals = [] + additions = [] + + # Changes (tier + stars) + for base_car_model, base_car in base_car_info.items(): + if base_car_model not in new_car_info: + continue + + new_car = new_car_info[base_car_model] + + # Tier changes + if base_car.tier != new_car.tier: + tier_changes.append(f"- Tier for {base_car.make} {base_car.model} changed! ({base_car.tier.name.title()} {ARROW_SYMBOL} {new_car.tier.name.title()})") + + # Star changes + diff = get_star_diff(base_car, new_car) + if not len(diff): + continue + + row_builder = [] + for column in list(Column): + if column not in diff: + row_builder.append(new_car.get_column(column, STAR_ICON, "{}")) + else: + row_builder.append(base_car.get_column(column, STAR_ICON, "{}") + ARROW_SYMBOL + new_car.get_column(column, STAR_ICON, "{}")) + + star_changes.append(format_row(row_builder)) + + # Removals + for model in set(base_car_info) - set(new_car_info): + car_info = base_car_info[model] + removals.append(format_row([car_info.get_column(column, STAR_ICON, "{}") for column in Column])) + + # Additions + for model in set(new_car_info) - set(base_car_info): + car_info = new_car_info[model] + additions.append(format_row([car_info.get_column(column, STAR_ICON, "{}") for column in Column])) + + # Print diff + if len(star_changes) or len(tier_changes) or len(removals) or len(additions): + markdown_builder = ["### ⚠️ This PR makes changes to [CARS.md](../blob/master/docs/CARS.md) ⚠️"] + + for title, category in (("## 🏅 Tier Changes", tier_changes), ("## 🔀 Star Changes", star_changes), ("## ❌ Removed", removals), ("## ➕ Added", additions)): + if len(category): + markdown_builder.append(title) + if "Tier" not in title: + markdown_builder.append(COLUMNS) + markdown_builder.append(COLUMN_HEADER) + markdown_builder.extend(category) + + print("\n".join(markdown_builder)) + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("--path", required=True) + args = parser.parse_args() + print_car_info_diff(args.path) From 01de46ad82358efa12797a50f501d902ca711547 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 12 Jul 2022 19:25:03 -0700 Subject: [PATCH 292/302] Corolla Cross: Update minimum enable speed (#25132) * Update min steer speed for intl. Corolla Cross 27 km/h, thanks to Ale Sato * update docs --- docs/CARS.md | 6 +++--- selfdrive/car/toyota/values.py | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index ec7da7a845..e24672e9bc 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -35,7 +35,7 @@ How We Rate The Cars **All supported cars can move between the tiers as support changes.** -# Gold - 31 cars +# Gold - 30 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -60,7 +60,6 @@ How We Rate The Cars |Toyota|Camry 2021-22|All||[4](#footnotes)|||| |Toyota|Camry Hybrid 2021-22|All|||||| |Toyota|Corolla 2020-22|All|||||| -|Toyota|Corolla Cross 2020-21 (Non-US only)|All|||||| |Toyota|Corolla Hatchback 2019-22|All|||||| |Toyota|Corolla Hybrid 2020-22|All|||||| |Toyota|Highlander 2020-22|All|||||| @@ -71,7 +70,7 @@ How We Rate The Cars |Toyota|RAV4 2019-21|All|||||| |Toyota|RAV4 Hybrid 2019-21|All|||||| -# Silver - 69 cars +# Silver - 70 cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -126,6 +125,7 @@ How We Rate The Cars |Toyota|Alphard Hybrid 2021|All|||||| |Toyota|Camry 2018-20|All||[4](#footnotes)|||| |Toyota|Camry Hybrid 2018-20|All||[4](#footnotes)|||| +|Toyota|Corolla Cross 2020-21 (Non-US only)|All|||||| |Toyota|Highlander 2017-19|All|[3](#footnotes)||||| |Toyota|Highlander Hybrid 2017-19|All|[3](#footnotes)||||| |Toyota|Prius 2016-20|TSS-P|[3](#footnotes)||||| diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index f47ab87040..f40a58b5a7 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -119,7 +119,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { CAR.COROLLA: ToyotaCarInfo("Toyota Corolla 2017-19", footnotes=[Footnote.DSU]), CAR.COROLLA_TSS2: [ ToyotaCarInfo("Toyota Corolla 2020-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"), - ToyotaCarInfo("Toyota Corolla Cross 2020-21 (Non-US only)"), + ToyotaCarInfo("Toyota Corolla Cross 2020-21 (Non-US only)", min_enable_speed=7.5), ToyotaCarInfo("Toyota Corolla Hatchback 2019-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"), ], CAR.COROLLAH_TSS2: [ From 906a8a912cbd39863f43582677f2435f11ecb904 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 13 Jul 2022 04:28:48 +0200 Subject: [PATCH 293/302] casync: only when run from updater (#25130) * casync: only when run from updater * also here --- system/hardware/tici/agnos.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/system/hardware/tici/agnos.py b/system/hardware/tici/agnos.py index 750aa630ae..ca2498a00c 100755 --- a/system/hardware/tici/agnos.py +++ b/system/hardware/tici/agnos.py @@ -222,7 +222,7 @@ def extract_casync_image(target_slot_number: int, partition: dict, cloudlog): raise Exception(f"Raw hash mismatch '{partition['hash_raw'].lower()}'") -def flash_partition(target_slot_number: int, partition: dict, cloudlog): +def flash_partition(target_slot_number: int, partition: dict, cloudlog, standalone=False): cloudlog.info(f"Downloading and writing {partition['name']}") if verify_partition(target_slot_number, partition): @@ -236,7 +236,7 @@ def flash_partition(target_slot_number: int, partition: dict, cloudlog): path = get_partition_path(target_slot_number, partition) - if 'casync_caibx' in partition: + if ('casync_caibx' in partition) and not standalone: extract_casync_image(target_slot_number, partition, cloudlog) else: extract_compressed_image(target_slot_number, partition, cloudlog) @@ -263,7 +263,7 @@ def swap(manifest_path: str, target_slot_number: int, cloudlog) -> None: cloudlog.error(f"Swap failed {out}") -def flash_agnos_update(manifest_path: str, target_slot_number: int, cloudlog) -> None: +def flash_agnos_update(manifest_path: str, target_slot_number: int, cloudlog, standalone=False) -> None: update = json.load(open(manifest_path)) cloudlog.info(f"Target slot {target_slot_number}") @@ -276,7 +276,7 @@ def flash_agnos_update(manifest_path: str, target_slot_number: int, cloudlog) -> for retries in range(10): try: - flash_partition(target_slot_number, partition, cloudlog) + flash_partition(target_slot_number, partition, cloudlog, standalone) success = True break @@ -320,9 +320,9 @@ if __name__ == "__main__": elif args.swap: while not verify_agnos_update(args.manifest, target_slot_number): logging.error("Verification failed. Flashing AGNOS") - flash_agnos_update(args.manifest, target_slot_number, logging) + flash_agnos_update(args.manifest, target_slot_number, logging, standalone=True) logging.warning(f"Verification succeeded. Swapping to slot {target_slot_number}") swap(args.manifest, target_slot_number, logging) else: - flash_agnos_update(args.manifest, target_slot_number, logging) + flash_agnos_update(args.manifest, target_slot_number, logging, standalone=True) From 0eab1ed817ece20b25de7438d32238c482613df3 Mon Sep 17 00:00:00 2001 From: Jafar Al-Gharaibeh Date: Tue, 12 Jul 2022 20:38:18 -0600 Subject: [PATCH 294/302] Mazda: CX-5 22 FW FP (#24778) Mazda CX-5 2022 FW FP dongle-id: 661621a8442f0688 Signed-off-by: Jafar Al-Gharaibeh --- selfdrive/car/mazda/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 09b9b7732b..12e9eafc4f 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -65,6 +65,7 @@ FW_VERSIONS = { ], (Ecu.engine, 0x7e0, None): [ b'PX2G-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'SH54-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ From 3b4e939b9f88b70727e687613a912aef36178755 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 12 Jul 2022 19:58:39 -0700 Subject: [PATCH 295/302] UI: translations cleanup (#25120) * Make this one translation * Remote html from translations * getBrand as argument * some stuff * Forget Wi-Fi network * Update translations * Remove obsolete * compilation fixes * remove * Fix missing translation --- selfdrive/ui/qt/offroad/networking.cc | 8 +-- selfdrive/ui/qt/offroad/settings.cc | 2 +- selfdrive/ui/qt/widgets/input.cc | 2 +- selfdrive/ui/qt/widgets/prime.cc | 13 ++-- selfdrive/ui/translations/main_ko.qm | Bin 19981 -> 19439 bytes selfdrive/ui/translations/main_ko.ts | 79 +++++++++++------------ selfdrive/ui/translations/main_zh-CHS.qm | Bin 18469 -> 17931 bytes selfdrive/ui/translations/main_zh-CHS.ts | 79 +++++++++++------------ selfdrive/ui/translations/main_zh-CHT.qm | Bin 18509 -> 17969 bytes selfdrive/ui/translations/main_zh-CHT.ts | 79 +++++++++++------------ selfdrive/ui/update_translations.py | 10 ++- 11 files changed, 129 insertions(+), 143 deletions(-) diff --git a/selfdrive/ui/qt/offroad/networking.cc b/selfdrive/ui/qt/offroad/networking.cc index 536ca495ca..c7341d1987 100644 --- a/selfdrive/ui/qt/offroad/networking.cc +++ b/selfdrive/ui/qt/offroad/networking.cc @@ -84,7 +84,7 @@ void Networking::connectToNetwork(const Network &n) { } else if (n.security_type == SecurityType::OPEN) { wifi->connect(n); } else if (n.security_type == SecurityType::WPA) { - QString pass = InputDialog::getText(tr("Enter password"), this, tr("for \"") + n.ssid + "\"", true, 8); + QString pass = InputDialog::getText(tr("Enter password"), this, tr("for \"%1\"").arg(QString::fromUtf8(n.ssid)), true, 8); if (!pass.isEmpty()) { wifi->connect(n, pass); } @@ -94,7 +94,7 @@ void Networking::connectToNetwork(const Network &n) { void Networking::wrongPassword(const QString &ssid) { if (wifi->seenNetworks.contains(ssid)) { const Network &n = wifi->seenNetworks.value(ssid); - QString pass = InputDialog::getText(tr("Wrong password"), this, tr("for \"") + n.ssid +"\"", true, 8); + QString pass = InputDialog::getText(tr("Wrong password"), this, tr("for \"%1\"").arg(QString::fromUtf8(n.ssid)), true, 8); if (!pass.isEmpty()) { wifi->connect(n, pass); } @@ -174,7 +174,7 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid list->addItem(editApnButton); // Set initial config - wifi->updateGsmSettings(roamingEnabled, QString::fromStdString(params.get("GsmApn"))); + wifi->updateGsmSettings(roamingEnabled, QString::fromStdString(params.get("GsmApn"))); main_layout->addWidget(new ScrollView(list, this)); main_layout->addStretch(1); @@ -296,7 +296,7 @@ void WifiUI::refresh() { QPushButton *forgetBtn = new QPushButton(tr("FORGET")); forgetBtn->setObjectName("forgetBtn"); QObject::connect(forgetBtn, &QPushButton::clicked, [=]() { - if (ConfirmationDialog::confirm(tr("Forget Wi-Fi Network \"") + QString::fromUtf8(network.ssid) + "\"?", this)) { + if (ConfirmationDialog::confirm(tr("Forget Wi-Fi Network \"%1\"?").arg(QString::fromUtf8(network.ssid)), this)) { wifi->forgetConnection(network.ssid); } }); diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 9aeb966ccf..9a6e203966 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -249,7 +249,7 @@ SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) { }); - auto uninstallBtn = new ButtonControl(tr("Uninstall ") + getBrand(), tr("UNINSTALL")); + auto uninstallBtn = new ButtonControl(tr("Uninstall %1").arg(getBrand()), tr("UNINSTALL")); connect(uninstallBtn, &ButtonControl::clicked, [&]() { if (ConfirmationDialog::confirm(tr("Are you sure you want to uninstall?"), this)) { params.putBool("DoUninstall", true); diff --git a/selfdrive/ui/qt/widgets/input.cc b/selfdrive/ui/qt/widgets/input.cc index b0facfce83..dc54a3621c 100644 --- a/selfdrive/ui/qt/widgets/input.cc +++ b/selfdrive/ui/qt/widgets/input.cc @@ -165,7 +165,7 @@ void InputDialog::handleEnter() { done(QDialog::Accepted); emitText(line->text()); } else { - setMessage(tr("Need at least ") + QString::number(minLength) + tr(" characters!"), false); + setMessage(tr("Need at least %1 characters!").arg(minLength), false); } } diff --git a/selfdrive/ui/qt/widgets/prime.cc b/selfdrive/ui/qt/widgets/prime.cc index d2529821f4..5419475262 100644 --- a/selfdrive/ui/qt/widgets/prime.cc +++ b/selfdrive/ui/qt/widgets/prime.cc @@ -88,13 +88,16 @@ PairingPopup::PairingPopup(QWidget *parent) : QDialogBase(parent) { title->setWordWrap(true); vlayout->addWidget(title); - QLabel *instructions = new QLabel(tr(R"( + QLabel *instructions = new QLabel(QString(R"(
    -
  1. Go to https://connect.comma.ai on your phone
  2. -
  3. Click "add new device" and scan the QR code on the right
  4. -
  5. Bookmark connect.comma.ai to your home screen to use it like an app
  6. +
  7. %1
  8. +
  9. %2
  10. +
  11. %3
- )"), this); + )").arg(tr("Go to https://connect.comma.ai on your phone")) + .arg(tr("Click \"add new device\" and scan the QR code on the right")) + .arg(tr("Bookmark connect.comma.ai to your home screen to use it like an app")), this); + instructions->setStyleSheet("font-size: 47px; font-weight: bold; color: black;"); instructions->setWordWrap(true); vlayout->addWidget(instructions); diff --git a/selfdrive/ui/translations/main_ko.qm b/selfdrive/ui/translations/main_ko.qm index 40b0bb65a38d65ee901ac7a85257e88868b4513c..d59698e07432f37ed105ada86a1c83bc815e0e0f 100644 GIT binary patch delta 2085 zcmYLJ3s98T89lrE|NHp&1qcfgS@r=c1%WkcK?M{P0~C=K4Mjyk2tp9$p~gJAlTkwq zYBdWLX;|7-Q0vsO$ zsjsu}HQ;BzV4uIE&S_uS7$S8GDtRSrT2dnz$;ODP=3(QME zmi(_=FF{uRtE^_ms*??X6oBlMTAph{&Z(CHXW}`mz1YJ8=kdY>0}b2o&ZR3r(kV1o z<#I}a=$Mj0+PN5gV=MQ2WTw~%Af!zea5RKM?v%~l&*{yMk!5y<0il~^Z}oG1fkSpB zO8`u_WH;rU#I!52dr$8o;X1ig^a&7_BM%)Nh7+?N$&;ljsu&?(<7GR2j|31?|PqbSYe z1QuIFeN8zq|GJoD2qp0cV)lAYC`Kt3NgvTVLt;tD2~HqiENMK+5hoG9V|EM&B2u{r&21hG{@#O0UZOj^!O4-$7u~<6H+0cr!)v>##BQ;Df{M!< z#eqQ*u&)zu@1$iyy*-%tia0(&LQ&mHxiyQO#V8G9kyI>Lx$s^x6)RIFE+3}ntjcB0 zZNS0~ll=Wtddf(Q!xbLU_?P~1wL)n7Crn=UfWp;`P*5#u^FE7L|uv|Y2xxsy^Y$=9r2LuseiYYIAf+h)2o z`$2D^MbkI1oLji@Qq&@fe!k9;iaqMths<}fC2d7K5 zlN{;vFsc6hae6dEa^GCZ(bP#tdpTlZuGIK?EtM;moF7JuyuK!>y@-M07O6ur^D((D zb(j|Nwq;3oH&juwZmq2KSA1-4Y3&z2p%<=dlW*+-ri5$P4)Zy%*J{f@6DX;d_SJ2^ zR8X(&{E8!*aa-G+PUTD`I^PQ<5P4W%bzJE;VK?XO*i< zOQaHUa^0#rCJZ*|HZ6ZltXFqv{8=U_)-@mGEi>D7J;$h=BVPCE05R%K-9RS^3ZLth zCqh{8h(0Rl1{=xH$4-#wQ*rvnIo!97>CbH^F4(W{u)RyuItTR~iTs$+s=u_5UeJ2! z`?7f*{kjZ(@15W%HX8z~seo^+!S*nTO6@bm4DmgRzF|n)O9_2nG?XVUW!!zko+B%$ zK%?RJ4JAOZ zfcP85G*V;Be3jPA^{zD4<@WbpYVKWgaW5v&yM+EVOlSLlLfeyY z^>dpmEVfXG&1EtBwwyF)%jC#$jahS~Cr6T8ZhMj|H^d}c$+2U#BNlM+yvf{GJs=U%t5_bJN#=oU$ewUAIrfXZe Y#mB=C2~SQ3x{jrr1aeGpwWdG&KXjTDOaK4? delta 2644 zcmcIk2~bq`9sYLry=6zG(a>Wyk%k_Jfz*{i zM9jOR=-<7EHcHV|An8nG55pE_LUcsc+ z*MacGm~`_4AjXEt`gzQC6&YhUq3_99l1!4WBg^h0Nj`Y#DzkYPVd_us)4m+j)Sq&F z0jAAc&MY~|*;@}tgOQtFL%U;m`Im37%3GLyvK4TK-AD0!KW@ZgX)gnq7GvibGMRcA z4URd$=&5KLl*O_)qi5YB?zgI}v7^c8x2nP01AtM#RYh-L_o5c4vYSVd*uAQEJGh?s zs_NV{0kA$$T~f0X!?mhgkt=~=ZEC6TGaz`QIE$lW-P_0#3WcI{ zGVGo$R9;I0{EiE6%wtJ9gRolo28i1))TSS$0$&?IOX>hx{RYr>Q>d$d$kN<}UETAE znZo`rHc^2p;qXuDfi#ow8=1{9-51V&*~#^M;q2|Za169++cc_Yf!1^{lnl<$CfrIRgC*KY z4ab0_2iln`k{`5OyZhl|z<-SPQI@lVG8?M%8%3&u)w(@HR`6uKx_=isPYhK7Y&F1zL5`JTG3b$e?O=hXK_x1aB09M2B7 z4|@FhZPDwDuTaMRdjC4k`SW-56Tar38!c+R36{IX}jeh1VQatj!ett6t z?YVaS22fsT)VFs|p`5DqSKLc^^Y}{>f_Xb>H%jx*xACO1wDuM+7n=_;k^W<(svBm0 zuaasWv$Z4hq}rpqDbqr!?$UI&s7>15##Rf_lJmft8dA1f`Z!$V1W%Su71B{GlbR%7 z-Xj;JCTju*ZM}5!RR<}9LG|G>+FK0%Cq83ADnr`u*8+o5470ECMhN`eP<~M$lame0 z7kiRHqoMgLw&uB^hSM*SG3(D{&l4;l{DN$2;QGi~ryP=4Ns(-m(^A;uJHbpL;(pOlUyyejh2G}V#yu(3LX3DKQ$XsNZ{COua;*8wc%mRhW zM(v&eCTui@`TULt$uh?FvQVEz#sg8@4+t`Tw1k-GJYj6|`vui|#n_Zg9Cg=tCV^To zSd8tt980f1n7rQK!xQW^4OvYFJhM%H4^zn0aZ^keucAn^DRVs;^xSAFPfn%Z9n;$P zIO)MXrfoOIQyZnGU)3{F%r~ZE52y*>YSX##=PB}2X171_j-26^VfLKBxsJVVwto2- z7^^lO;+4 zX$SeOFQSkxHYV!~79Wq6>is0CV`6hnM^VG+hHluXKMIGh?E1C0&Glf!k6Z=b?!&ch zvrevu^24raN`C%)CC{PQ^Ya!ul*Xgp`?SO4j@*OcEkegEDDeBiR4gd1Q2bmLU(d!J zzPT!=dNCv#{Oy;3QrP+JKqbnMk3<9^g0F&w{cH9oYsJVz1qxAw5`@qr9|hcxqg@1| z>A4i~^h)}N=zVz-XkGLqUSwszYhRMT4>*ryIQT2&dSB3Jgg*`H%Ce20!zf|>asE?= z{~-aATt}4ga}oM~PLgL+Ttk#N=f6qRcgntgJafvYtyDQArTBXAwT%u- z2(uUcOQ(P0qqfET*FJNU6zj8j62eOD136tg6>DRst=u|PdwSUZvS-vTO)n`bS?I{K i+ZETzvEGd - Need at least - 최소 - - - - characters! - 자가 필요합니다! + Need at least %1 characters! + 최소 %1 자가 필요합니다!
@@ -481,8 +476,8 @@ location set - for " - 하기위한 " + for "%1" + 하기위한 "%1" @@ -547,52 +542,50 @@ location set 장치를 콤마 계정과 페어링합니다 - - - <ol type='1' style='margin-left: 15px;'> - <li style='margin-bottom: 50px;'>Go to https://connect.comma.ai on your phone</li> - <li style='margin-bottom: 50px;'>Click "add new device" and scan the QR code on the right</li> - <li style='margin-bottom: 50px;'>Bookmark connect.comma.ai to your home screen to use it like an app</li> - </ol> - - - <ol type='1' style='margin-left: 15px;'> - <li style='margin-bottom: 50px;'>https://connect.comma.ai에 접속하세요</li> - <li style='margin-bottom: 50px;'>"새 장치 추가"를 클릭하고 오른쪽 QR 코드를 검색합니다.</li> - <li style='margin-bottom: 50px;'>connect.comma.ai을 앱처럼 사용하려면 홈 화면에 바로가기를 만드십시오.</li> - </ol> - + + Go to https://connect.comma.ai on your phone + https://connect.comma.ai에 접속하세요 + + + + Click "add new device" and scan the QR code on the right + "새 장치 추가"를 클릭하고 오른쪽 QR 코드를 검색합니다 + + + + Bookmark connect.comma.ai to your home screen to use it like an app + connect.comma.ai을 앱처럼 사용하려면 홈 화면에 바로가기를 만드십시오 PrimeAdWidget - + Upgrade Now 지금 업그레이드 - + Become a comma prime member at connect.comma.ai connect.comma.ai에서 comma prime에 가입합니다 - + PRIME FEATURES: PRIME 기능: - + Remote access 원격 접속 - + 1 year of storage 1년간 저장 - + Developer perks 개발자 혜택 @@ -600,22 +593,22 @@ location set PrimeUserWidget - + ✓ SUBSCRIBED ✓ 구독함 - + comma prime comma prime - + CONNECT.COMMA.AI CONNECT.COMMA.AI - + COMMA POINTS COMMA POINTS @@ -857,17 +850,17 @@ location set SetupWidget - + Finish Setup 설정 완료 - + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. 장치를 (connect.comma.ai)에서 페어링하고 comma prime 오퍼를 청구합니다. - + Pair device 장치 페어링 @@ -1023,13 +1016,13 @@ location set - Uninstall - 제거 + UNINSTALL + 제거 - UNINSTALL - 제거 + Uninstall %1 + 제거 %1 @@ -1274,8 +1267,8 @@ location set - Forget Wi-Fi Network " - wifi 네트워크 저장안함 " + Forget Wi-Fi Network "%1"? + wifi 네트워크 저장안함 "%1"? diff --git a/selfdrive/ui/translations/main_zh-CHS.qm b/selfdrive/ui/translations/main_zh-CHS.qm index 2c7963cf17a496e356fb5b0372b565ac82514661..eed52b27788c46e02689a14fb9f11e17c776755a 100644 GIT binary patch delta 2088 zcmYLJ4OCQR8h+-^z4LQt<_;(zBIwKjA%Y-?3OT?L6a5v5t5eF!7x6L%^C2JkbL@>&65@Jm@YFdC+|kFy|E@Y!#6D zDlh&Vc#6q_{ei3qCK)EK06ae)D^25;|zy3gyak-FvU!iE0Nr_76?f~ z^6jHQWDw@+my&A@Qm6A_{H2yBFzee$JFo!ojzmVWi;umA%xk>W^AP5}{4d6pBU|`@ zB8DM*X*F-NAg84X&}U*{%1&|?@a%z?0H^&wSbV072RczP#6XiB`_EqlV!uGEgOv!9 z(J?xMw5xDqa~bz*RbDZnfGtGjy*B^|XjDzx%IbyPR%LYtbG=)&=VPux4yad~sNv@W&pOe%y4SvDgg6 zO%vL;*nlaD@P5ixz?>*t&f*2*E(uqBVvF2J9M8@lBcr(GxtcQ z+BFokTuM{|$$L;*xP%3Y(n*E#`*cpf^n5@w5bh;Cf4GGet|a~h=q5^)%PaW)G-+*= z!Zz3?)&8DD^o=9v`_%}JH;-WKJgFh1i3Ra^OKR9gYZ&6Bri~k@#AnjkAqp;RllrcZ zfaM42>-BVuZPf_cPf3GABox}C5v49 zq{&lJZ(EC|@%}@e8`KPDd`w4tsY`qF8oRQ(lq4h`v`JS!xeFI41ZfA0qT?#ML*958+oF_!VO<=R`cuwRk9^C3&> zUoG!`uaU$q%MHB?SeklyZ#PS<9+D5gx|7NslutOPNbKHp`D`HrB~k8>$8(mPkvqKX zY_?4EfSQP^-2LIFN=!H{;q%UhYB?b(O`#BA)7Q>p$A|(wqRKMuK_y>m0 zZ&;#$2ZoQHrg9!%8a+;vKuC+x+RAnRR^#N@N_wN)=uArd2k_)^V`}tbV8%sbS^|}b zUSZ6sV?w`3J^_&RAAIsitT{8OUP{PqZ%9?~ZG_R!8)MrwGM&-{< zydZKwIr$?!;ZtSSeb0HQ?KFGLV*5@#ZuYwQkkjQwvv*E5r$c(XdG2*43XeBuIOuZS zI&(?k4NBy0-rl=`9#~=iLqQ3p8aAI={a-4z#QfncD+!!6U%9=P-SL|FYSLRk%!MKv zsjKZtZI|NuWZc-kuD-X(eHUt~VL>1wU`d~pm%H|fVHGV( zPx0@YUQn>ilJBq-7vz^ZEP)X&Z!c?Gz1I{?z$j-{)fd^O%I}ALVEZ}T_Bc$peARC( zw!nzCo4zlo1Z29bmQ4BaZldd~HPN-s=B2W^_D`_=vJvgdvqnGKaETM*e_0NF%^Lb> zwJpLXd0OT97294OA^bR_aY0E@NvR{hxR?~%vS!S43-W!gxArf{MG=xv^oS}${!bI} Vj{|*Nr<1+JzzAEs>yzY+{{iv64I%&l delta 2662 zcmcIk3sjTm8Ge)ee=a}CAJ7n5x%~t%Ah%G#aS4cU#EKmkMPQ<}Fe1hVf)ER-mXuj* zDb~vg4pymJfnvw3J79J5Xs0bw(P8VU-RKybQY~W3Y;|X)BDe>zJ#;(U&UVg{!+FT} zy_e^E-sk)3c8FSci*{=q0+G0c$n6Q>IMKXtB1thY6Icl>2Q~ofi5Tqj3L-XwDCB)$ zJW(hQ%twrA8g+=5-XU^DO_?`vComRx6nKV6g*YX0{a+xOdxdC~D}wb1bn^uw(Crzb z#n?0)AWC})ja-SISONSIQC1|1JOHjIa=!)KhV?^4me8BxUq@IxXS_O%=KjQBj} z-%iZ-eME^DiD|q}B;ttaib7U2F}=S6Rul69L*(-nu`ff4&^Mh4A`eFr$wENRb+pI&4o81t(G0>Jv8;c?+W9`7aR7xhv+1&k+SRi34v8l7k}q#HpMO%=U;^ zyW+%#bK=*oVD#P=@rfNE_E@6$ouwG9dX4y_EEM)(#REOCL3o4s>OprR&pZhe?m?sp zm3V)_BJYeuSGN!f>Lr`9Q1=J(CG9+jhYU$Nj>Br|%aW5F$TQ?iy7bk~Yhq7FJM&aq zCm5V&%u6A#tBSD?CK3r}nJtB2B(*c!nY%;_4l<2PPr-mu)5woaqo#2heeW|(Eu&!O z!5q3?1k7cA@xfjq-9F~n(=CuRiTSk>vr!#qE`HXJ^>3JqxBh||xb-lD3y;BY4whR0 z%@Z!Ls=AHPu#HXO12IGcoA(rEvLJ>n=H7u>2H6b(tGnnPuQlA7R*3%o^9F%SGXjyEiZ0^61Ui+?_VW~ z7-iobhvwp4?0bHf;i_|N{{RU2>)B7Y_P_+K)0lXhy*Cbm5u8-)mkoCvmh!j5p`cl6 z98QITe~>QeI879{N}4Z%_5lOZ=FtfvKZEpM#>Wo0OeNC=L#m)4S?ipwI9Z$QXz8bD zoFluv{1Buw$-ce?MIWAQ^oUZ2ZTg1c}Hj?2>|AgZpHn?}Y!Fh~B%rdP3FEI-hW zIUZhBTR;AX`G)Xpsm!Q&+5xuOqyaZ-V+9md<@8xKstHF%b* z8&c!<0j_=mqYXU4HJ)k)p%JdBZzV=_ncLrsQA@_TBaWBqAz43n(!hdQHTP~Y5?O}p z;(YLooaMT-Mi6?7yZK`q8cn!}j#nc-)5ZVHIe6l>OX{C$iDpS$)(ql7@XvAC_z?r* zg)TMEXpleV()|TSqmOhs|3fII8C7b|fI!%Q(ys&Sfj5e!e8RjW}+Yb!?owC0h z1eu*GX=?x;0Do14_wPX@RuwxAqMi+^BT?A*8&RF81ja6RsJe7-z`ZL}UCBT_r@CN- z7dWHpN*=DIW-agjW-Hb&^K-UCfmz@1y3rIU^=CfjDqf<99)8&lC^$Qc-zjm`#=QW!7%t!I@fFcoL!!eIs>$B{#?!7)ou+` zTSLNk5q!GIR3sGG1dFMl!X`Kct$Sy!)*$s#I7= zdB-b9R57(?dAL?W1yoMOWTsLILxzdgVLuLW zkra*0DvC!|;y+ZM>|{i=`C+~J_Nmm#Cf_eu2pTqgtyrHd8cl|8i#jWPlb%GCh^adN zsl)%!fD)Y(KDz&Ri!`51$G<$q=yi2 zQczxOE)BDo*4g5O$mp`Fczxo-a6vFy%-@f54J)+TY}S%EA=)q%>OAWk8expEnEy@E zKjqBxjrp&0T6|KpGy51Ltd{AXog==U?w-;WRlA;>;c{+eskyYmR$#FR&aa|8I+LQ~ wUFXkQ+gJBX%7vLy$vo-y89vvhTFZ+~HX+v>mTDH#O}0vF`O`4|sl^$82ZSevfB*mh diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index d9377054a5..0870ff7028 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -308,13 +308,8 @@ - Need at least - 至少需要 - - - - characters! - 个字符! + Need at least %1 characters! + 至少需要 %1 个字符! @@ -479,8 +474,8 @@ location set - for " - 网络名称:" + for "%1" + 网络名称:"%1" @@ -545,52 +540,50 @@ location set 将您的设备与comma账号配对 - - - <ol type='1' style='margin-left: 15px;'> - <li style='margin-bottom: 50px;'>Go to https://connect.comma.ai on your phone</li> - <li style='margin-bottom: 50px;'>Click "add new device" and scan the QR code on the right</li> - <li style='margin-bottom: 50px;'>Bookmark connect.comma.ai to your home screen to use it like an app</li> - </ol> - - - <ol type='1' style='margin-left: 15px;'> - <li style='margin-bottom: 50px;'>在手机上访问 https://connect.comma.ai</li> - <li style='margin-bottom: 50px;'>点击“添加新设备”,扫描右侧二维码</li> - <li style='margin-bottom: 50px;'>将 connect.comma.ai 收藏到您的主屏幕,以便像应用程序一样使用它</li> - </ol> - + + Go to https://connect.comma.ai on your phone + 在手机上访问 https://connect.comma.ai + + + + Click "add new device" and scan the QR code on the right + 点击“添加新设备”,扫描右侧二维码 + + + + Bookmark connect.comma.ai to your home screen to use it like an app + 将 connect.comma.ai 收藏到您的主屏幕,以便像应用程序一样使用它 PrimeAdWidget - + Upgrade Now 现在升级 - + Become a comma prime member at connect.comma.ai 打开connect.comma.ai以注册comma prime会员 - + PRIME FEATURES: comma prime特权: - + Remote access 远程访问 - + 1 year of storage 1年数据存储 - + Developer perks 开发者福利 @@ -598,22 +591,22 @@ location set PrimeUserWidget - + ✓ SUBSCRIBED ✓ 已订阅 - + comma prime comma prime - + CONNECT.COMMA.AI CONNECT.COMMA.AI - + COMMA POINTS COMMA POINTS点数 @@ -855,17 +848,17 @@ location set SetupWidget - + Finish Setup 完成设置 - + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. 将您的设备与comma connect (connect.comma.ai)配对并领取您的comma prime优惠。 - + Pair device 配对设备 @@ -1021,13 +1014,13 @@ location set - Uninstall - 卸载 + UNINSTALL + 卸载 - UNINSTALL - 卸载 + Uninstall %1 + 卸载 %1 @@ -1272,8 +1265,8 @@ location set - Forget Wi-Fi Network " - 忘记WiFi网络" + Forget Wi-Fi Network "%1"? + 忘记WiFi网络 "%1"? diff --git a/selfdrive/ui/translations/main_zh-CHT.qm b/selfdrive/ui/translations/main_zh-CHT.qm index 0d448f2080322661cb712bd3c06b4049fabbf935..029332de238d74b5cf8c40073a31d27ea6f0bf4f 100644 GIT binary patch delta 2149 zcmZ`(eNa^Q6}@lwz1@9p-|hol5Y`3u0}RLlqJ#o2GC+iYDK3={Ctxe;x}tn2ELE#< zON}LnQFNsmgG3_)O=1%vV&X@l2Bl(=IGWTBLuw5wX0#gZBoxK;;Lg~;%FNDT-tXSu zJ@?%6yM2w!ku6N4&K*u9D<|?5fMY~2oFtMvf!_jG1D^nQ5rylCSe$F_6LB#_5i@`@ zfxib9A?7z;47p3Bcu3?ENu&${z5+}HqK5J`^5+tXJw(Q*L{qL3z3THZii`&i0uksN zM>P9&qNqni*>9jQey_{}UL?wm#U&t+yNt;12yhb!=!nYpBcCU##-%=6iCj4Me_{K* zV7DoZ*t)lgY)6URJw(K4iS0&(@OEPRJ_SA?wx1<3loPkvNHjHwxWny4>H<=9K?3y# zQX1!@+88M#L08>M(yrszp1!RM6f^#M@|o)=tEIL$4lO zPn7IO3(j0X!7^GihCEF;?eD#W?<3UV`ZcudrS6H))(}rOH`n02n(2GIwUY4#I6R!FdiBTV-K4 zZxF>ymt_bp=$a!d_Cd$dfwH|_C}BG%HtjY>OFjdt{$yVFr>#b|p6-1txoB zgBReC$UCy@`}~LkwQ@Fk64AsFdC*-B=XSZdAqAbiDX+;zfw&%d^O;5zx-9=di%ud6 z??8UkN1i@eh`X9y*xre#-?61xP+RI}*WQ>#6g-<CWSzN=PK!o4sMZ@vK7wK z?ckcX!5L~R*ZRjzP@{6N|n&7Ok zE@hj3BRcw7`BBApC~Q~$^gR@icPSswybWj6snR35@x~HV+4AccQGv>F?=h@yQ@vTU z2j{-3cRoP=#6;E6n-&=38(yiw8kyYBTbfmPQ*ZI1&;vJGmcYXcH&YRlO&$1dStv#&uZ1^G ziSCT_%S1_s#O#CxM89Yi=cGZ21iM(!gbNMBVtLLuF{ij|v=A3aV#jv8F#{uB*azjJ z{viH!0B8*t2hM{ayF;UB3q`?unwX%!fk?6@aSTKQ=V=bd;XK5tIkp-Y|D&ec{2oj@ z+pXzN!#|-rG`+Sa?8B*=tMl<3brD*>Lv84&NUN`d0uzpD%_HepbBnbJ*R3c#SvzM7 zB%Cm!U6nQ)d5^U9Z{u-KS*(4(6$Pg6)t>qhp3vJR)dQ?UWtXH&#q*s}Df!=eN;FN7 z0t)hoCgs#iFAw3O=pJdV3ochxNfpkUaO-8M@!BSMV43umqXJU>Abqj&36#o_dTyIQ zAX^$7Zh`b^()El#6D4+*!btZ!laz15=%C}0=W*VaBN z_9Y{QQ7jql>Y~Ej^q(166rRG*kmGPHF_yTDWsZ_+moY5XGva6JT<0IB2oYafiZt`H zMDz0m)zZo;qd6?r?1?q#I{$9SU=);BtR$o7ez3_i)fgi@4^8*HZ%Ut}L>19qQd(77 z;j~w-tXcVtS(2wbBtZclG)VP4oAL1|hFlNu`Oug0H2BkcY)@M{!IUO!zVQExGsWHdlT3uPS N;#p@Yp3%&C{{>l+97q5F delta 2681 zcmcIl3s98T89lrE|GVtJyZ?$V+ZJ{Cc_{dR1p@|QL4|^XElTj!phgJ`Zd@M18emX2 zj8S9oy&B&d6>4l^oq)kKiPkF7V1h9dlGveGix1SA+GwX*t+od+iD{?pv@?a-IqbdP zLS2DjQ9W;atqKD0z)mt3gQUjCgLPO;J)c5AliXpE@C3F ziI~fnXL>Ot1kkcZpEN)>kXS$*MO;oi#{7wZ@e~jm3k+@pp6+uR2=5NOLu8J-tI5y} zBV9usqRm8U9>%p)1CfCkcl9kGR)g{SJhHDw=E#lc{>iLJffqx!V4~Z{bDzSb-;qGT zHaxZHPfW_)x!NfD9Wd{0rOG$ zfcd5f>^^-47!!d8&n(UjXzoXCZEjqCc>(v!Rn}3%y+Bxi>iavxDE2m0+-eRqdXFmm zB%{L)tG0f|_4roRnaKhRJ5=Y?dw~JBRM(z(5eRHoONH+P5qauCmpg%&JaxL{p%Txi zXY}ETqchYy+VsG{5$eM$Ni62H`e?>#z?`K1G@Eq?wx~N=(&&t+AoYb;1AzWN)Cf`E z11x=iEc9=(7e;YJo|5b9qJ(ODq;4% zMz*gNTp3i?d`+n8Oa_!{VPPKWXqO7hh1;x>FKo_ukA95mMY+8fEem@ws6p6Xcb9`Z zDD1hEPwW!j_;@1_GC?>rua0`o5Po6gTueKK53jUyeZTPG^*;b!|J_38=tJ~hwJ43G z;7Om0rrP<`uR=_f2a)zUar$fyB<{LcC>^C!PK(cl)l;W4;&a`O(mRRtxL=@HRZz)e z4-ugXiP8{+mgbcA8JShs8`m3Uh`cfP$-Q#S_7w&{6ebdj|=Hd?8+3(!xRiq!&jU#Cs1&FlxP49Xy%NYSzj(qo`o0 z)^RPJ3SQBUYd8WVq-b+h)IDsScJJMX-0#%hoA?=>6w#^+8A7STZ|Ld+mvG{C-NE9E zY&=PK^Qk?Qu10s~Iu+40>Fy_X(Md=AQinA2t`+-bYDm;v>gW9OJ_$PfRxQ}d{c(P~ zUT2+tIeu?l4&`^FUT5MnViWbD+x>tiTJ&RY6*7LVe#!*zB}yNypSpySjrmBQJA)Dr zI;qb;nLD7UuuOaPkI6Gx((G|3TTdMan^ z__Z-JekL%g%{U>2N+i5soVt+(gKWm4tZrh3#!dI8u|S%!VIA+7?MY+Ht5nY3VEm|^ z7&Xh-ev$-*^(Jk77%#uhWFPnii6oguJs{EkD@+GsxgWg4bhv^zYOvST9P(4TH_g9m7hkcOJtrt?}_QssdC^&G`IIdC}@==+HrayOMq`Q-QueB12V@`ROCuwP$! zeo7kiZp$mS@sdYuk#}^Bp*KYNXLW28+bSRVGd(e2nS5r$qKJ>y?MVhy?TaODq_D$2`$Pm;05OiwiGPDxG=lxux{NT=N!ZF%|pD{L9k6QnAJ6 zj;lL)D=N(w(ti#lUUUIt`!%NM_R9ehlu3r%Y1yfNQ_*)c3_nKScx$lFBmKZ9Sp7q# zO;}M=b9;tAly4&BET=PHnd4F1&N<~CWxX|^(PfR*251)*KtaeiabiJ9nbP>~fLxVV zoe%bU?AL)3xcS|KDwM*BB!nY|9|h$-YwkyDMVNy!6vBmKL^8vP0`4a;E(USTtVANS zlK-K4cP9sAB`#9_+?%tlhWX0O}`=EMDe{D|X8vSD~m!=fEipxE7+-{}u&Dbk_ z5(A4x{=ZT%jkbzJdbhb2HLSYHm2WL?O)n`cbb6F&uE=zklI8SNl$6a=LVV}ba{dnW C?SW|k diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index efd893ec4c..0620382a63 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -308,13 +308,8 @@ - Need at least - 需要至少 - - - - characters! - 個字元! + Need at least %1 characters! + 需要至少 %1 個字元! @@ -481,8 +476,8 @@ location set - for " - 給 " + for "%1" + 給 "%1" @@ -547,52 +542,50 @@ location set 將設備與您的 comma 帳號配對 - - - <ol type='1' style='margin-left: 15px;'> - <li style='margin-bottom: 50px;'>Go to https://connect.comma.ai on your phone</li> - <li style='margin-bottom: 50px;'>Click "add new device" and scan the QR code on the right</li> - <li style='margin-bottom: 50px;'>Bookmark connect.comma.ai to your home screen to use it like an app</li> - </ol> - - - <ol type='1' style='margin-left: 15px;'> - <li style='margin-bottom: 50px;'>用手機連至 https://connect.comma.ai</li> - <li style='margin-bottom: 50px;'>點選 "add new device" 後掃描右邊的二維碼</li> - <li style='margin-bottom: 50px;'>將 connect.comma.ai 加入您的主屏幕,以便像手機 App 一樣使用它</li> - </ol> - + + Go to https://connect.comma.ai on your phone + 用手機連至 https://connect.comma.ai + + + + Click "add new device" and scan the QR code on the right + 點選 "add new device" 後掃描右邊的二維碼 + + + + Bookmark connect.comma.ai to your home screen to use it like an app + 將 connect.comma.ai 加入您的主屏幕,以便像手機 App 一樣使用它 PrimeAdWidget - + Upgrade Now 馬上升級 - + Become a comma prime member at connect.comma.ai 成為 connect.comma.ai 的高級會員 - + PRIME FEATURES: 高級會員特點: - + Remote access 遠程訪問 - + 1 year of storage 一年的雲端行車記錄 - + Developer perks 開發者福利 @@ -600,22 +593,22 @@ location set PrimeUserWidget - + ✓ SUBSCRIBED ✓ 已訂閱 - + comma prime comma 高級會員 - + CONNECT.COMMA.AI CONNECT.COMMA.AI - + COMMA POINTS COMMA 積分 @@ -860,17 +853,17 @@ location set SetupWidget - + Finish Setup 完成設置 - + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. 將您的設備與 comma connect (connect.comma.ai) 配對並領取您的 comma 高級會員優惠。 - + Pair device 配對設備 @@ -1026,13 +1019,13 @@ location set - Uninstall - 卸載 + UNINSTALL + 卸載 - UNINSTALL - 卸載 + Uninstall %1 + 卸載 %1 @@ -1277,8 +1270,8 @@ location set - Forget Wi-Fi Network " - 清除 Wi-Fi 網路 " + Forget Wi-Fi Network "%1"? + 清除 Wi-Fi 網路 "%1"? diff --git a/selfdrive/ui/update_translations.py b/selfdrive/ui/update_translations.py index d872be0d86..f06d54b2d5 100755 --- a/selfdrive/ui/update_translations.py +++ b/selfdrive/ui/update_translations.py @@ -10,7 +10,7 @@ TRANSLATIONS_DIR = os.path.join(UI_DIR, "translations") LANGUAGES_FILE = os.path.join(TRANSLATIONS_DIR, "languages.json") -def update_translations(release=False, translations_dir=TRANSLATIONS_DIR): +def update_translations(release=False, vanish=False, translations_dir=TRANSLATIONS_DIR): with open(LANGUAGES_FILE, "r") as f: translation_files = json.load(f) @@ -20,7 +20,10 @@ def update_translations(release=False, translations_dir=TRANSLATIONS_DIR): continue tr_file = os.path.join(translations_dir, f"{file}.ts") - ret = os.system(f"lupdate -recursive {UI_DIR} -ts {tr_file}") + args = f"lupdate -recursive {UI_DIR} -ts {tr_file}" + if vanish: + args += " -no-obsolete" + ret = os.system(args) assert ret == 0 if release: @@ -32,6 +35,7 @@ if __name__ == "__main__": parser = argparse.ArgumentParser(description="Update translation files for UI", formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument("--release", action="store_true", help="Create compiled QM translation files used by UI") + parser.add_argument("--vanish", action="store_true", help="Remove translations with source text no longer found") args = parser.parse_args() - update_translations(args.release) + update_translations(args.release, args.vanish) From 97d7ee369b9b8193fe1580fbaa00e65a26235432 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 12 Jul 2022 23:11:55 -0700 Subject: [PATCH 296/302] Chrysler: send LKAS control bit while above minSteerSpeed (#25150) * Chrysler: send LKAS control bit while above minSteerSpeed * update refs * rework that a bit * little more * update refs --- selfdrive/car/chrysler/carcontroller.py | 11 ++++++----- selfdrive/car/chrysler/chryslercan.py | 4 ++-- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 9 insertions(+), 8 deletions(-) diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py index 8156e7841e..00893b6bc4 100644 --- a/selfdrive/car/chrysler/carcontroller.py +++ b/selfdrive/car/chrysler/carcontroller.py @@ -14,7 +14,7 @@ class CarController: self.hud_count = 0 self.last_lkas_falling_edge = 0 - self.lkas_active_prev = False + self.lkas_control_bit_prev = False self.last_button_frame = 0 self.packer = CANPacker(dbc_name) @@ -24,7 +24,8 @@ class CarController: can_sends = [] # EPS faults if LKAS re-enables too quickly - lkas_active = CC.latActive and not low_speed_alert and (self.frame - self.last_lkas_falling_edge > 200) + lkas_control_bit = not low_speed_alert and (self.frame - self.last_lkas_falling_edge > 200) + lkas_active = CC.latActive and self.lkas_control_bit_prev # *** control msgs *** @@ -59,12 +60,12 @@ class CarController: self.apply_steer_last = apply_steer idx = self.frame // 2 - can_sends.append(create_lkas_command(self.packer, self.CP, int(apply_steer), lkas_active, idx)) + can_sends.append(create_lkas_command(self.packer, self.CP, int(apply_steer), lkas_control_bit, idx)) self.frame += 1 - if not lkas_active and self.lkas_active_prev: + if not lkas_control_bit and self.lkas_control_bit_prev: self.last_lkas_falling_edge = self.frame - self.lkas_active_prev = lkas_active + self.lkas_control_bit_prev = lkas_control_bit new_actuators = CC.actuators.copy() new_actuators.steer = self.apply_steer_last / self.params.STEER_MAX diff --git a/selfdrive/car/chrysler/chryslercan.py b/selfdrive/car/chrysler/chryslercan.py index 632c0d2bcf..1e26a6d275 100644 --- a/selfdrive/car/chrysler/chryslercan.py +++ b/selfdrive/car/chrysler/chryslercan.py @@ -52,12 +52,12 @@ def create_lkas_hud(packer, CP, lkas_active, hud_alert, hud_count, car_model, au return packer.make_can_msg("DAS_6", 0, values) -def create_lkas_command(packer, CP, apply_steer, lat_active, frame): +def create_lkas_command(packer, CP, apply_steer, lkas_control_bit, frame): # LKAS_COMMAND Lane-keeping signal to turn the wheel enabled_val = 2 if CP.carFingerprint in RAM_CARS else 1 values = { "STEERING_TORQUE": apply_steer, - "LKAS_CONTROL_BIT": enabled_val if lat_active else 0, + "LKAS_CONTROL_BIT": enabled_val if lkas_control_bit else 0, } return packer.make_can_msg("LKAS_COMMAND", 0, values, frame % 0x10) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index e77a38de5f..c99a1653f4 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -5efbbdf69e16db3d989bfaf62d10e958e80b9ca2 \ No newline at end of file +7fbe776f271ed2d45abe989736133a5cfa0ec826 \ No newline at end of file From e710ba549a3e0b1aba50ba8d4ed47e695a02c538 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 13 Jul 2022 00:20:35 -0700 Subject: [PATCH 297/302] Car docs diff bot: skip PRs from forks (#25151) * check permissions explicitly * fix syntax * Fix * Diff * fix * revert --- .github/workflows/selfdrive_tests.yaml | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 298ea5fb49..fc151cc2e2 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -10,7 +10,6 @@ env: CL_BASE_IMAGE: openpilot-base-cl DOCKER_REGISTRY: ghcr.io/commaai AZURE_TOKEN: ${{ secrets.AZURE_COMMADATACI_OPENPILOTCI_TOKEN }} - HAS_AZURE_TOKEN: $AZURE_TOKEN != '' DOCKER_LOGIN: docker login ghcr.io -u adeebshihadeh -p ${{ secrets.CONTAINER_TOKEN }} BUILD: | @@ -366,7 +365,7 @@ jobs: name: process_replay_diff.txt path: selfdrive/test/process_replay/diff.txt - name: Upload reference logs - if: ${{ failure() && github.event_name == 'pull_request' && github.repository == 'commaai/openpilot' && env.HAS_AZURE_TOKEN }} + if: ${{ failure() && github.event_name == 'pull_request' && github.repository == 'commaai/openpilot' && env.AZURE_TOKEN != '' }} run: | ${{ env.RUN }} "scons -j$(nproc) && \ CI=1 AZURE_TOKEN='$AZURE_TOKEN' python selfdrive/test/process_replay/test_processes.py -j$(nproc) --upload-only" @@ -551,22 +550,22 @@ jobs: output="${output//$'\n'/'%0A'}" echo "::set-output name=diff::$output" - name: Find comment - if: env.HAS_AZURE_TOKEN - uses: peter-evans/find-comment@v1 + if: ${{ env.AZURE_TOKEN != '' }} + uses: peter-evans/find-comment@1769778a0c5bd330272d749d12c036d65e70d39d id: fc with: issue-number: ${{ github.event.pull_request.number }} body-includes: This PR makes changes to - name: Update comment - if: steps.save_diff.outputs.diff != '' && env.HAS_AZURE_TOKEN - uses: peter-evans/create-or-update-comment@v1 + if: ${{ steps.save_diff.outputs.diff != '' && env.AZURE_TOKEN != '' }} + uses: peter-evans/create-or-update-comment@b95e16d2859ad843a14218d1028da5b2c4cbc4b4 with: comment-id: ${{ steps.fc.outputs.comment-id }} issue-number: ${{ github.event.pull_request.number }} body: "${{ steps.save_diff.outputs.diff }}" edit-mode: replace - name: Delete comment - if: steps.fc.outputs.comment-id != '' && steps.save_diff.outputs.diff == '' && env.HAS_AZURE_TOKEN + if: ${{ steps.fc.outputs.comment-id != '' && steps.save_diff.outputs.diff == '' && env.AZURE_TOKEN != '' }} uses: actions/github-script@v6 with: script: | From a7b778c324bf4eaba7f5db32ec60f88212e2c6fe Mon Sep 17 00:00:00 2001 From: Jafar Al-Gharaibeh Date: Wed, 13 Jul 2022 01:31:52 -0600 Subject: [PATCH 298/302] Mazda: Support CX-9 2022 (#25147) * Mazda: Support CX-9 2022 dongle-id: 8c6e0e30decb68f7 Signed-off-by: Jafar Al-Gharaibeh * update years Co-authored-by: Shane Smiskol --- docs/CARS.md | 2 +- selfdrive/car/mazda/values.py | 5 ++++- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index e24672e9bc..754052085d 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -198,7 +198,7 @@ How We Rate The Cars |Lexus|RX 2016-18|All|[3](#footnotes)||||| |Lexus|RX Hybrid 2016-19|All|[3](#footnotes)||||| |Mazda|CX-5 2022|All|||||| -|Mazda|CX-9 2021|All|||||| +|Mazda|CX-9 2021-22|All|||||| |Ram|1500 2019-22|Adaptive Cruise|||||| |Subaru|Crosstrek 2018-19|EyeSight|||||| |Subaru|Impreza 2017-19|EyeSight|||||| diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 12e9eafc4f..e1d6907991 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -40,7 +40,7 @@ CAR_INFO: Dict[str, Union[MazdaCarInfo, List[MazdaCarInfo]]] = { CAR.CX9: MazdaCarInfo("Mazda CX-9 2016-17"), CAR.MAZDA3: MazdaCarInfo("Mazda 3 2017"), CAR.MAZDA6: MazdaCarInfo("Mazda 6 2017"), - CAR.CX9_2021: MazdaCarInfo("Mazda CX-9 2021"), + CAR.CX9_2021: MazdaCarInfo("Mazda CX-9 2021-22"), CAR.CX5_2022: MazdaCarInfo("Mazda CX-5 2022"), } @@ -267,6 +267,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'PXM4-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXM4-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM6-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -279,9 +280,11 @@ FW_VERSIONS = { b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'GSH7-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.transmission, 0x7e1, None): [ b'PXM4-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], } } From 3a8f17111c3439cb22eb627aec805898d9d9a41a Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 13 Jul 2022 01:10:56 -0700 Subject: [PATCH 299/302] Log VIN response address (#25148) * log vin rx addr * clean up --- selfdrive/car/car_helpers.py | 8 ++++---- selfdrive/car/fw_versions.py | 6 +++--- selfdrive/car/isotp_parallel_query.py | 2 +- selfdrive/car/vin.py | 10 +++++----- selfdrive/debug/disable_ecu.py | 2 +- 5 files changed, 14 insertions(+), 14 deletions(-) diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index b6bdece676..1a9a5f50f3 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -93,17 +93,17 @@ def fingerprint(logcan, sendcan): if cached_params is not None and len(cached_params.carFw) > 0 and cached_params.carVin is not VIN_UNKNOWN: cloudlog.warning("Using cached CarParams") - vin = cached_params.carVin + vin, vin_rx_addr = cached_params.carVin, 0 car_fw = list(cached_params.carFw) else: cloudlog.warning("Getting VIN & FW versions") - _, vin = get_vin(logcan, sendcan, bus) + _, vin_rx_addr, vin = get_vin(logcan, sendcan, bus) ecu_rx_addrs = get_present_ecus(logcan, sendcan) car_fw = get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs) exact_fw_match, fw_candidates = match_fw_to_car(car_fw) else: - vin = VIN_UNKNOWN + vin, vin_rx_addr = VIN_UNKNOWN, 0 exact_fw_match, fw_candidates, car_fw = True, set(), [] if len(vin) != 17: @@ -166,7 +166,7 @@ def fingerprint(logcan, sendcan): source = car.CarParams.FingerprintSource.fixed cloudlog.event("fingerprinted", car_fingerprint=car_fingerprint, source=source, fuzzy=not exact_match, - fw_count=len(car_fw), ecu_responses=list(ecu_rx_addrs), error=True) + fw_count=len(car_fw), ecu_responses=list(ecu_rx_addrs), vin_rx_addr=vin_rx_addr, error=True) return car_fingerprint, finger, vin, car_fw, source, exact_match diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index a8f5357f0e..5a33cdf6b7 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -444,7 +444,7 @@ def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1, if addrs: query = IsoTpParallelQuery(sendcan, logcan, r.bus, addrs, r.request, r.response, r.rx_offset, debug=debug) - fw_versions.update({(r.brand, addr): (version, r) for addr, version in query.get_data(timeout).items()}) + fw_versions.update({(r.brand, addr): (version, r) for (addr, _), version in query.get_data(timeout).items()}) except Exception: cloudlog.warning(f"FW query exception: {traceback.format_exc()}") @@ -497,8 +497,8 @@ if __name__ == "__main__": t = time.time() print("Getting vin...") - addr, vin = get_vin(logcan, sendcan, 1, retry=10, debug=args.debug) - print(f"VIN: {vin}") + addr, vin_rx_addr, vin = get_vin(logcan, sendcan, 1, retry=10, debug=args.debug) + print(f'TX: {hex(addr)}, RX: {hex(vin_rx_addr)}, VIN: {vin}') print(f"Getting VIN took {time.time() - t:.3f} s") print() diff --git a/selfdrive/car/isotp_parallel_query.py b/selfdrive/car/isotp_parallel_query.py index 0e807512cf..bb96572c33 100644 --- a/selfdrive/car/isotp_parallel_query.py +++ b/selfdrive/car/isotp_parallel_query.py @@ -126,7 +126,7 @@ class IsoTpParallelQuery: msg.send(self.request[counter + 1]) request_counter[tx_addr] += 1 else: - results[tx_addr] = dat[len(expected_response):] + results[(tx_addr, msg._can_client.rx_addr)] = dat[len(expected_response):] request_done[tx_addr] = True else: error_code = dat[2] if len(dat) > 2 else -1 diff --git a/selfdrive/car/vin.py b/selfdrive/car/vin.py index fd1ca61e66..007c10e772 100755 --- a/selfdrive/car/vin.py +++ b/selfdrive/car/vin.py @@ -22,18 +22,18 @@ def get_vin(logcan, sendcan, bus, timeout=0.1, retry=5, debug=False): for request, response in ((UDS_VIN_REQUEST, UDS_VIN_RESPONSE), (OBD_VIN_REQUEST, OBD_VIN_RESPONSE)): try: query = IsoTpParallelQuery(sendcan, logcan, bus, FUNCTIONAL_ADDRS, [request, ], [response, ], functional_addr=True, debug=debug) - for addr, vin in query.get_data(timeout).items(): + for (addr, rx_addr), vin in query.get_data(timeout).items(): # Honda Bosch response starts with a length, trim to correct length if vin.startswith(b'\x11'): vin = vin[1:18] - return addr[0], vin.decode() + return addr[0], rx_addr, vin.decode() print(f"vin query retry ({i+1}) ...") except Exception: cloudlog.warning(f"VIN query exception: {traceback.format_exc()}") - return 0, VIN_UNKNOWN + return 0, 0, VIN_UNKNOWN if __name__ == "__main__": @@ -41,5 +41,5 @@ if __name__ == "__main__": sendcan = messaging.pub_sock('sendcan') logcan = messaging.sub_sock('can') time.sleep(1) - addr, vin = get_vin(logcan, sendcan, 1, debug=False) - print(hex(addr), vin) + addr, vin_rx_addr, vin = get_vin(logcan, sendcan, 1, debug=False) + print(f'TX: {hex(addr)}, RX: {hex(vin_rx_addr)}, VIN: {vin}') diff --git a/selfdrive/debug/disable_ecu.py b/selfdrive/debug/disable_ecu.py index af007207eb..c01c22fdd0 100644 --- a/selfdrive/debug/disable_ecu.py +++ b/selfdrive/debug/disable_ecu.py @@ -16,7 +16,7 @@ def disable_ecu(ecu_addr, logcan, sendcan, bus, timeout=0.5, retry=5, debug=Fals try: # enter extended diagnostic session query = IsoTpParallelQuery(sendcan, logcan, bus, [ecu_addr], [EXT_DIAG_REQUEST], [EXT_DIAG_RESPONSE], debug=debug) - for addr, dat in query.get_data(timeout).items(): # pylint: disable=unused-variable + for _, _ in query.get_data(timeout).items(): # pylint: disable=unused-variable print("ecu communication control disable tx/rx ...") # communication control disable tx and rx query = IsoTpParallelQuery(sendcan, logcan, bus, [ecu_addr], [COM_CONT_REQUEST], [COM_CONT_RESPONSE], debug=debug) From 0edd8201cb8d8f21f361d0be581b02bc43c1b80e Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 13 Jul 2022 15:12:49 +0200 Subject: [PATCH 300/302] README.md: update directory structure --- README.md | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 34b17625f9..3dce9d4475 100755 --- a/README.md +++ b/README.md @@ -105,23 +105,25 @@ Directory Structure ├── third_party # External libraries ├── pyextra # Extra python packages └── system # Generic services + ├── camerad # Driver to capture images from the camera sensors + ├── clocksd # Broadcasts current time + ├── hardware # Hardware abstraction classes ├── logcatd # systemd journal as a service └── proclogd # Logs information from /proc └── selfdrive # Code needed to drive the car ├── assets # Fonts, images, and sounds for UI ├── athena # Allows communication with the app ├── boardd # Daemon to talk to the board - ├── camerad # Driver to capture images from the camera sensors ├── car # Car specific code to read states and control actuators - ├── common # Shared C/C++ code for the daemons ├── controls # Planning and controls ├── debug # Tools to help you debug and do car ports ├── locationd # Precise localization and vehicle parameter estimation ├── loggerd # Logger and uploader of car data + ├── manager # Deamon that starts/stops all other daemons as needed ├── modeld # Driving and monitoring model runners - ├── proclogd # Logs information from proc - ├── sensord # IMU interface code + ├── monitoring # Daemon to determine driver attention ├── navd # Turn-by-turn navigation + ├── sensord # IMU interface code ├── test # Unit tests, system tests, and a car simulator └── ui # The UI From a006cd168ea5a2fec2f03b29460a3a685538b9cf Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 13 Jul 2022 17:55:05 +0200 Subject: [PATCH 301/302] run pre-commit in release CI (#25158) * run pre-commit in release * add pylintrc and init files * build first * add mypy ini * limit amount of debug scripts shipped in release * add python version? * add more missing __init__.py * excluded rednose for cppcheck * remove files before dirty check --- .github/workflows/selfdrive_tests.yaml | 7 +++++++ .pre-commit-config.yaml | 2 +- release/files_common | 16 +++++++++++++++- 3 files changed, 23 insertions(+), 2 deletions(-) diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index fc151cc2e2..fbc0d94194 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -58,6 +58,9 @@ jobs: run: | TARGET_DIR=$STRIPPED_DIR release/build_devel.sh cp Dockerfile.openpilot_base $STRIPPED_DIR + cp .pre-commit-config.yaml $STRIPPED_DIR + cp .pylintrc $STRIPPED_DIR + cp mypy.ini $STRIPPED_DIR - name: Build Docker image run: | eval "$BUILD" @@ -66,6 +69,10 @@ jobs: run: | cd $STRIPPED_DIR ${{ env.RUN }} "CI=1 python selfdrive/manager/build.py && \ + pre-commit run --all && \ + rm .pre-commit-config.yaml && \ + rm .pylintrc && \ + rm mypy.ini && \ release/check-dirty.sh && \ python -m unittest discover selfdrive/car" diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index b901e07721..8b8bc1f1b9 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -54,7 +54,7 @@ repos: entry: cppcheck language: system types: [c++] - exclude: '^(third_party/)|(pyextra/)|(cereal/)|(opendbc/)|(panda/)|(tools/)|(selfdrive/modeld/thneed/debug/)|(selfdrive/modeld/test/)|(selfdrive/camerad/test/)/|(installer/)' + exclude: '^(third_party/)|(pyextra/)|(cereal/)|(rednose/)|(rednose_repo/)|(opendbc/)|(panda/)|(tools/)|(selfdrive/modeld/thneed/debug/)|(selfdrive/modeld/test/)|(selfdrive/camerad/test/)/|(installer/)' args: - --error-exitcode=1 - --language=c++ diff --git a/release/files_common b/release/files_common index fb91170561..954726d967 100644 --- a/release/files_common +++ b/release/files_common @@ -57,6 +57,7 @@ common/api/__init__.py release/* +tools/__init__.py tools/lib/* tools/joystick/* tools/replay/*.cc @@ -128,7 +129,15 @@ system/clocksd/.gitignore system/clocksd/SConscript system/clocksd/clocksd.cc -selfdrive/debug/*.py +selfdrive/debug/can_printer.py +selfdrive/debug/check_freq.py +selfdrive/debug/dump.py +selfdrive/debug/filter_log_message.py +selfdrive/debug/get_fingerprint.py +selfdrive/debug/uiview.py + +selfdrive/debug/hyundai_enable_radar_points.py +selfdrive/debug/vw_mqb_config.py common/SConscript common/version.h @@ -187,6 +196,9 @@ selfdrive/controls/lib/lateral_mpc_lib/* selfdrive/controls/lib/longitudinal_mpc_lib/* selfdrive/hardware + +system/__init__.py + system/hardware/__init__.py system/hardware/base.h system/hardware/base.py @@ -220,6 +232,7 @@ selfdrive/locationd/laikad_helpers.py selfdrive/locationd/locationd.h selfdrive/locationd/locationd.cc selfdrive/locationd/paramsd.py +selfdrive/locationd/models/__init__.py selfdrive/locationd/models/.gitignore selfdrive/locationd/models/car_kf.py selfdrive/locationd/models/gnss_kf.py @@ -330,6 +343,7 @@ selfdrive/manager/process.py selfdrive/manager/test/__init__.py selfdrive/manager/test/test_manager.py +selfdrive/modeld/__init__.py selfdrive/modeld/SConscript selfdrive/modeld/modeld.cc selfdrive/modeld/dmonitoringmodeld.cc From 49dd56fc241d5ea3e0ab37e10175ad545ef4d528 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 13 Jul 2022 17:58:45 +0200 Subject: [PATCH 302/302] nav: draw inactive lanes with 50% opacity (#25157) * nav: draw inactive lanes with 50% opacity * update ts --- .../navigation/direction_turn_left_inactive.png | Bin 0 -> 7221 bytes .../navigation/direction_turn_right_inactive.png | Bin 0 -> 7239 bytes .../direction_turn_straight_inactive.png | Bin 0 -> 5452 bytes selfdrive/ui/qt/maps/map.cc | 4 ++++ selfdrive/ui/translations/main_ko.ts | 10 +++++----- selfdrive/ui/translations/main_zh-CHS.ts | 10 +++++----- selfdrive/ui/translations/main_zh-CHT.ts | 10 +++++----- 7 files changed, 19 insertions(+), 15 deletions(-) create mode 100644 selfdrive/assets/navigation/direction_turn_left_inactive.png create mode 100644 selfdrive/assets/navigation/direction_turn_right_inactive.png create mode 100644 selfdrive/assets/navigation/direction_turn_straight_inactive.png diff --git a/selfdrive/assets/navigation/direction_turn_left_inactive.png b/selfdrive/assets/navigation/direction_turn_left_inactive.png new file mode 100644 index 0000000000000000000000000000000000000000..2946984acd3252f257898cec9f6cda866811adc3 GIT binary patch literal 7221 zcmZu#2Q*yYw?;&XUZVFtIuVS{5R5)V7(~?QC3*>>MHzjR=w%SmMXw2h=)H^H%jhHO z^Lu6e|LeVX&pqd^`>kE>{qEjppK~L%HI)gT(L6&#LnBaCQG`5R`~K-TSdU}5K}9wi z8qqsnJp*@$nHQ7G2WM+r2P-Cb9~UboD{otCG&Jw|wlB7cw339O4`<|Vm`+T6>n<^A zw1X$xPYT~IU7k^BMd|;3O&%SFDNI(o@Nk24eOOIqS58&3w=ML3+q6j`Y5Fa&b^Z=t zW_jc$U0|lO_w49GVMA{%jp1SPo^BZ^;4JH%_1<3!xpxLG8;R`P??xpb3}1e1GiBRe zU-$1DiJTAc2bAyK6vl2Vo&k^fH~*$CGa%a!mXEq{*}-a!I#I60@waznanIRqqD$QL zWI*OR{?_ekcCnyVP!}r`BLi}C=k5mWBhKl77z%h@xh(Tk_Hz60IUr?|nzh~Ehq{=@VD)Q-iZt22pb>kNdiyrFX5j;;)`#-cN+aAYv2DU z_GijV_LKkLU2G&ZG$Qwdai3WjgXSzsyvs5Yc=VOdB2#F|?WL`QYZ10)Ygc4C6k38Y z4O=Me-o0v0aX~H|-C2KK^m!WI^TTqr^C7F@X6%=#Pm5bo7}wP`4bSv*zDmPz=Jz=; zjChyq#@__T12?!GfvK_xZk&Dsw@vgG#yCKDXu~3ya=Tl6^@=NR#a)_{NpaE0KwX7t zMNNeid`wdiE=R|M=AqA^8~X$^SjCuEcnc18r?Ic~JEJA=a)2A;XN6~=DM0e-xp6#x z^v4_Iaqs{q*;OeLSh%NDliospD}ez}*hVwQ5I0n>&TitZ?$B$y5~#gnUBfIX9ap)C zV_n^}pL-Uq$JQPUnMv)6NcapBcAp%3m4g@=)V2O1vG4G`vT;0^L*KA@&#n}?BC1|} zmSR$W)Vy%?*;sOSgSD7W`l5EiRL3v>dgz8y8&7L;O{u?Um&Y#CklqHfp{{Hr0D!(h^;l@%2Jh`u>KD{-QX=!+-Dcprwr2S0P-f z@QA%4S%j25z&vfEoBD12jGz~x@gEBt$@VzvL_73DojBR?5A*C;z>-kt`p&|qni;cx z@4bTuYuKxqbya~KyUce$GE1tMb3>yqFOV;aYRpfkO9$)iWg>jiX5$k*rKO*f9vv_k z%`DZ{a&72*(*gI#GJbw(l-{j;y=&-2CGmunP~G5_u`maW`gc#l{ya@_p{;&EHR$VN zwG&eGQz1hd*Kd}GF1Zyj{X)`w1S5QYV23Y{8w2_kie~@#Op`Y(?Gq zU8?kAVSv2^z1c*)k&Q4Dz5&ax`jGUi$)=LqWX0{o7azv=d?WG9|A2yCcHx!|{^ z($ok~=!0pG{P8RF)ZCpa25gcM9tp5rh>_Lp*#9Q?WA}c2n>HHsIk1y74MRL4B=gHD z`rw!n2VB02e%(Hg%lY zb~urOi8nI-Iv|HO)T4iPtm^zuZ#>41mZ0*@bkSp$W(M|KYPEapVf!o1=gf!q^_!r- z>B~2}^Y|O!^XHCG=d-XQ$S9leu^9DmSJ(RDs@g;Q8wnBnCU{5%EJ`wn4ZZ zdpqjb5`BGe<*(t16J(G*?mI$}{wCFh<8823cgxF{65!bdF2s|KC_#z9t?Ma&U z0@ZMvM|m^wdxW_;e*|V;LFhPPjnTZG?fgI@NgLz`*VJ6Um5#anfDM9CDKarpQBcTj zY{UcKmcl-C!<9U3kO&?ZI{$S}!c1J;i?FN$rR`CaW|ZSsVx0#Can+SvwrUbZnU9}o z%QQYY?B*?cdB?t6# zyyYQlQ6=stRah*`vBVb+AJ`IjS8Px8T=376x8w-R%4imq?^{H>ikkPQ6<4&g!1W1j zWa$ODx7_RyBJbT_nU;qL!(j0?ChdrV@Q+ngT}u7@hblg?h6rUFs_#=f;woq1JX0nx zA3qSGsyr-MRbW7|;ECS%PMU#Jo6+~7?WqY;MA$P>_G9+j@v#KbmXVsZpMLyK-DeZ0 zV+&q!#Pbu}p{mnI>(tOUnX^Hv=weWn>J)sfHu^2-(>DaR20a$}8^-zJFrvEPzvyUm zVw#j4bIikvPw2nDK9}Gdp-M>Dm=qxYsY?JSNkDPX84WOnTcq{CK%TES=9n8|u}3y2 zqYF#FO*_!9WUX-xE@;HyudW}6qSIB2YUw~SKc|#kFRt}a#0>X;mEB2#*V);2PIA;%V@B+xP3?U+^YX&r zj?;BY5p8rO0O4G2PZb7wbnunW1a1)QpJLC{lOeZGxyhcs+0Ly03RXwIh@q4x;iK8y%c2?@Dd z`cB(#)Oc#_4q16sGQXd&)#gxT61~&aL4b4~V2}jQIs#N^uk*5cv)IeuNmsdeK<&@Kw3^ zMH&!BG6rorzhfT*vfF%~rJiIzPH(MvXVvA~4g#vF5mk7ZfosvC;jFsnc`M;)!rW|( zn6n5l_2n=H7!fV{jK5r^=PALPE1x5oo%_yM;-LehXa}0TckZsXU$j$qSUfCAF&x24 z(dHe#KClN^9omOGx|N)S*6LjqIP&A178W0B<+8lXpzX0AH5*)XiP2lDYF0j1U^vkR z%#pDh#DhUIQ9x~HDyC^`naH2b8B$U-MHuNu=cjEApyqImll1LSB&WTkqpV}n4Si17 z((lVJo+%T+L_w_IFw*B^ij2wg?{JP90#_DlE*8tb(L z*AHwPq27yf9>D;q9`kLou_x}hN$f>gqA#q2r|-C}^D;mu$E9%By|QQK3w50#OWUBc zAoa9A8x}WK#I=s3ma_rqJ|fxq@!Wt{38OiQ$|*n$l9sB$Y%Kg-F)iEkxpHbD+)it` z2g&nyaR%ke=k)_bWbr@j{E|h+{WsE&FYmPEIOFEcX zmn^Y>4ndQH>U_On%|#a7^F>7N^2=TQqI?Fa5TYns1^KAA867q-*MoY{+77a)gO)v> z04v{|X}ZprnpREUNcGja>IqjWepwJft_L&PWe(}Lt%R&>Z%2^N+`$iR^}?3kX)-q$ z$vwIs38}Qfpa|oqX*60%6`GZ?P&!@ZBg{eelrlLcsk3hJFMgaadDjO|)1r&2+p|AR zME01g0|i%JtgQ|i$LMGF0KYo32iiD(lcIPXU}(5lOlB#wFL_1Yx$gJ^9~opIQrI2w zbcsjowUx(I>p+u2uPmK?*7`Sr#d3oj`YsbcLtMrX^yQ}n8`$uXD$k&|MMgBE&EIgn zL42BSY4?Ag+A;}dB?Y_8m=A^zcd1^@_6Vm6K`Mbixi*#@Hdl(V9jgxQyBaIf)rM(u zNlnAQyzb^P(@WHtBkhrbqFAVvN4bb$tn4yF76O(MA>Nhao?D<;~;4i z>qi|jcO%%Z7p+sDP$z>sk*bW+dJ?du;=zdBF_&ojrHyZ^{*T{$JvK?_r}6aMEFS?W z{#{2Sw4T3WCVQnb)4N}j-(9|(sEsK_)~pe5Dun_0>h1sfj9NqxyzBhpAcLYET1)L^ z)Iw~nDc2Ng2dq}ijCRa!+ss;Mcpf_gR!A2F}|Ft~;Hg^O|kGAwC zF6TX19CRq$oA0$_UPyioRF8SH5m;V)S6pzze0u-n61ji>=}zfh=kjP||6Zv3&SyzB z_K2ujS$U-2l`*yDP%;mBne#E>PeLpem=Vu8W`ry5V`9wq%hFie5MDeP0$|#0%|ePq z(RhoQfx^lqV?Hs@q1;c({zLn?i_bYNvvn>PSF}Q|Fe-z|UHE!GU>Zr1weY77Q>JZ6 z&;m5}pqXwxCn_21G^_tZ@FsMqD9_6C%V*I^Gxhr(&w8&wThm()meQE5d!nNUt_aOr z)D0RMdWbCuq^$}9{m)+eafhAxF+p0TOOEcBscs<)AE76)YoB%&Z$y-Y-Sa4I=E-N} z5^2WQPc>)~$tjh8)~&4cnos@wW%vgBjXd!!nydQT#cv#F~&EMj~!c<%{ zv`!N}!8(~Na&-B_8C#QBMw&wwm+mgVrd+|p(BaD8%zHfe^^58VnR4VWb8H^^L2%J4 zDOEb%mszJ_Wxd?ne8bSf9w=%<0Dt=;*{WiKPJuMqAQ+S6nH^UF2CXa91Hy~2m0ewD zbiX5QBL9&5v#&acTcodo@s=pS%lPaDDoV<*5hGtP{u7Efe9_Uz+<_z)S>6~6JV zV_+Tnpnu|9XZvc_TxZ(GMko7z2A8HM_)^q0fEGx6kv10^^8L96F!zCC$K=e{{&4*q zy-)j13GK=XF%F8+bnN*J;w!5l^680800lp;XBJ;&BG_+^Es*3V@-t&h`$T;KI^t~r; zBTa7a-}h>M@uU<@KF)P8D=$jK`o(0IuL_EX*G92lFFy2e$`mLDld3aSW0BH=ekkTe z;mOgi8?-8U(hHTpc{8ZAJ{IWDTN1-`%&ttonYEw-7)0vEDX=#U;aI)bL zhWVclZwr3m^mXHO9Y?@V;qVW>pJm63rf~WcN1=hH;J-^Inkx^l21w!|`>2}>-?jiK z*aztpFihoEqF;JpBaZ=r{w6)525jC7`DTjQ{&TNG{!tfjF)J=>4{M^q{3%>+!@O~n|u^)^RG0`a~#a-y{ zU#Zr}%CQYk7VQ3@RXPQM?vu46AJ|G=wDlE;))1DsC>Z=Sn>UciiXF2XXe+Q9i=&)c zLyEBm=Za#`2WR!Id;M}9?0=5#3OaT8mIUc9@VS-g2QP{w6ml3D8F^i|2fhOP2v#nu z8sbVv@PNKqWN%BSPjOH2`4aVm>0SyAv_6t(0WO*F31^l6N2V=NKs2l07Z;_^#ly@r z{jBS_3Vz!A^qgj)t27#(OiXOFO}nfEzRT@H<<$;BM?bj#=Po2E zKh;H9V>lTy;^s3JLJnN!^2hZGm29j{3n9;++1Icw543X?4~3t;qY77UY^5^a+|%dm zp6{dj?gaZQ&0~nkR>?edLQfZLYo#4ZY_AZ(w3)q(!_300$Q3$EtbiX%oYUj#{~~rh zTWIT5<;;z{lao`Q)!VfocZsZbo}QOFfK6AKifWAONa8hFS31)PsA;Kw>5Of1B4&3F z`ywf(wF!3eg9yzNX!oZeghwlyCw+<< zbiW~(sS#{%KowsbNBQIGEJZx_p}n^D{Jyg@n1hL8b^y1!&#C=UJ%fjb2dTbim-Za} z_l`F@f)Y;aO4o68bFYMvSnwDGu7FJ;eh_DHOc-99Rj|^ijlaq*tHd9e89^Uz2trkomXU_x6gsp;QA6@KsE zzaOcE@+lD|GWTm|B31bt77i&*=$(Kk$wtqpadFX`Vk`kyk@<`&Z3B1~LQ(l%_4V~w z$zXPsi;y!ZKw+70w%Df6A9{s|=4~Gh=5AQbz-CXH8n`4CN97X4&*`}wEtOO?WmnSm znP{24uyx_A)yK$*n?HMEXCvvk58W~uFQ!bx00Dd8>uLC;vw z09@F0EI$-ZU%$2(gjP^4K6oyUocp!`eB*D!ji(RWKbu{Z;hFN<)j{n70`8d$CnGcc z61|ckmBjIxv-LMlu%)!E*DU-Qj;CA9pl zbHl>>GhV7>NOtYVudmY?Hr%{8cs!R)s9*X2aS?A-26%ACeGa9y;O8zJ9t+v%L*4xn z#2=xta3WufrbD7`JZ9zvaDq$k0v>jyd@UYBC?hV4%StYh$j3*JD)VKJG2ry$m9iI5p6FZXQJMg$97vRyY_NqHs8u;VWAsnqc++?RbnTM-PTRT^`} zfGo!E$8bdjBuULlA)hs4Q;CM&nC_dVPQ|p>jHoSt6U&nHNDcQeV?OtH9*Jfa8JD8cXL!{sj&H- zTn(|rNWutWg~6dAg2yUWJH73O6QR4w+3=Gq3$5(EQW-S z*`_QeDw>Yj-I)iPZb4S0o2xqaQrwm3OCnW&~QL0wC0Sxb&L z^`QNM`)~;*49{^;%kH>&i`7;36l1MVPyyia*8U@Zxug|!zm|->I9+?zPr?26d^{@L zzN0Png%)IqI#_yyXUOuOFs|XUmU3D7L5J?DQgd_fPD2^;SPK8K`J(5RHRSDv6UN#~ zni1dvLeqkT^pBsjl$Mq<7E2qVq~aL5SD9zbslrE&tR6p>kF#OFR^spL4oJY902%S; zr}8cyl`Y72q%0)mGGg5uu*p3AlLZCCQF&JHwcN|s5)WbcUU+F!na_1CemGM$v+qS3 zPpS>R14QLh_E3N3B!YYXnVg)on?EB4Y|>*Q*tnCyeuGP>ad-|6vpyuCO@Jhxl=?lY z&2p1-X57De1CtK}!m)nP?w5_aNK~JcEyVsAd+-6ZB%mtiL`r;MPzP=MgGA-b{XDwi z#N5D}!d3arKGICzbW>3m@Et#}bXww2x6~g)7znC(^Bv~tQ$8fwL+B*&o*X%RuNAN(T5V`4%>N5{dDlS9M6ASMn9 zLc_#-g#Hik-!lJ__&25hQu#OFzpVrTA#9$#@KBnNbu zR?h6pJ}$`UU(o$$sc33yVn&y@b#!nL`M8`zqM+w_#kx9_A@;E3ASz}n{r{~R(Q>sP Zo~{oAPRia=wfrNXs-&q{q3|yFKLGp@*MI;3 literal 0 HcmV?d00001 diff --git a/selfdrive/assets/navigation/direction_turn_right_inactive.png b/selfdrive/assets/navigation/direction_turn_right_inactive.png new file mode 100644 index 0000000000000000000000000000000000000000..7d327766af13be26a23159e354cce5df6453f920 GIT binary patch literal 7239 zcmaKQ1yoy2v@Y%xcMBy*a4TLQc!CEBq*!tH;)NF10)YahXt7eHMO&b>Sa2!O;$CQ= z5Zv|h-*x|c-+ODld(N8KXTG!7e0$H{b7tlw80cw|lQ5HDVPTO&wA5htvj3k#L~vi% znAH|wVNsNY7@PUSo(2NEeZ3rA+#LY^!QKu4haeY6EUcipkz5ZXt8{Ag-4SglUieEu zYPX2m4*BW%RZ;6B_7n&6`sMgV7kzkDYoa<%!Z2Rn>g`y>lXH>q56%z1o=72*u74V8 z7KCjcoJbU$(QY5zUhjAs#k#qd6zK3sbdCtz1x9nEX z73Uc@M;8i^QS|hM@iK18)#VS3=`kbAy_cs~T~7Ra%a?tJ1sr#Q=eyC=Wn2pH*Tb~= z4}$kTGSS|RIQSYb89jx4g)3?^t;#l@+2F0WZ9JFnJ(pEp#=n@a*nf1%QTPo{Y3%Ic zkUI;*#-(_@p9HiX%}(uGAEOZFkQiK!5aYfHmff>%m>k)4d)6TJaBe9+Br^XSd3Q`w zS~j}5SNnoaar=n*Ye=3?#vx6h#n%94PzD`oWqF2Uy?^0vy|79txs+0BYs6dVfg<;|i zm+7#8eC?Z9r_tq>#AskBTDJfzBD8&yLur-pJrW$;wP3!Iy#1&rWaBWV=5W2mJKsC( zwE;=U5-#P#0wEn9I&sP;{76J%ZbP{mt2}Y;utIh&1C!Rn3()}!Z5LVR-PyvC$GHV= z4eMDqk_&1N`2em}8O4x#SGxU@rl?|&`iFQ)!!2;^uqnc00x|gqDBa|2GG6|{GH%o= z1T*nudg*G@Z{2W3naN{w(=J)oFGs;yd}{r2;LU5e`Lh96ZMe1F2zgk*V*UKo;@Qm6 zy3qqkpSkhLF`1)s@281RJ}v~DoXYP?esV;8NO)wlE#)3=kIDa~)E>^|ww2#>Z9n*N zGPT-A>U}uNL)rXzbaL`WZvU4M0xbX2JXC?}NP+B_IqREuX~RI2AC2B&a(Y*Y5xq7? z%N3X3_sq|Lo9x4^J7K?0qqD+(3&698(Rqsc01NbKMjf0kM8~f9^8EIc$+uA0^=O&> zZjYeeWUl#bPlzY)-rKC)7JGPpsMHXzBU{vQIrfvRmWg%`jHfhQX1f}4jb_#)bHpqn z%*F9^_SbUqogolM6Xic&{)aC;qf%_B1}Kkq z7s{63K5j}?dGz+g7tzwfs-q@vYyd>Ic2xF=HKv#HyV-lsy@?fXdj9*%lvhfq4oi1w zp&IZ_XFgID_w&)P93Nqrp6iX7+_$^xcU& zdLi?TwjjP{fPkOf=@UMWnpn+9!QBa#>0&+*_(|sFW36*0D^zPYtA#|eD=*rCrtr}% z@t1C;n#4!tjpl# z>DQZ?!@Sj^#R{Y`U&!0O*j3<7ZOE2SrxDrWtI9v}@ddjE7h3dwAw&)b?8dCRQu0hc z5m;O>pHId-4$Sdv!X6s+BYX`FkjIDD0`$`oqT$qV@W<-!bA z&+t3eG0IIFpEI(WLcV5<% zJ4`%ns9LpSof%nz8Ss9(L*TsvZ$u5w5O^0qoi0IUEdTWV{^=t6i5xdg-JJekvzrRL z^N=-os+;b~Pl=dC*IY15FxVe4JK|Po`-*UP9^QGK{22?I1z>qNoD^pA;W0U^X|z)I zB#ityG3ke&)yDnowI68OAr1}5bh@fH4}R{afm$ppKuALyO{MP4S_y-bvRMg=tB_xQ zBg>25R#xiEX>=&a5k8;X-;|iU=mCq0^P66cA|X<4nHHe!p-P+sRW5O|;l~684~ENQ ziKmd-QF-6Os7Y)7BoNMiBM;wce{OFHeRXlNz6_4OAHRm_3jrNv58&@nc#NA%mu3e_jh z)t)P`r$>K|2Rw)w(gG?Ty-GPQIZu+1P5k?wqJ+*Li=HqZaLw9D#cD64U$D4O*maUg z94%B`&M1warf;6--x;!?oGfe)reP#c%bHpV==iiJzL{^57r;AF@p{G}*^FPuvVhF~ zZ81su8@j4zp3Af>`vcO{09MoE*6xoj`3c1I`(4MaI*ND4a9(@K2!6VlD+z^P_QrB&xe_?;BkYDg&YzBo*+0hTGD-QRq0H4P{aWKNNA&OoC>nY)5#qR zG5TOxmz4oKMwj>|D43Q`0mXuFbnv5n-%~ro7_Uimk7p2Pt6kO!Gt*o+psVU!TDhSI z4VDa}lP7qHUXhj9X;MqL5N9@(I2PeXtuIaaGc18HsgWP6YA3=5Rqn1IAbSigsHV$U zLcHZBm;%{%Zw6yu3|sDKjHd}eNA4pXwPS6u%nTlPlK)6X8|~jHHc?ELbfC1^@=cx; zz3O$Yuv_5E-l&S=LCqI%(ZKhzk#QU%mhU%0MmPQ*?x4KU_^;zXq-?QhDcP^=b3vtC zS9#VswI5R*qQ~R(sQqB6p_ts0=AWKEO1>$8Mal!ieqMIEXbbLxTo;z^BT9> z*5zfcd>?k!Oz(fQk>$t2qW1&C?oTxpE)kedB@~Y zP}_{z$>w7NS-Dq~>ZE4l2!H64BQc)QjPaXRG4e53_mN2|$`+L#=UB1@+?q+06G~Pb zDQDg8oZ)MDTQ}~^a(4TG_kz>oqg#sYy8XK5E_S(@2Fh4CjgLEC(@n}sS^IS(qTF{0 z!gUU{tvk92w7e9t<5R4pf(c6~%o25ND}T}(SQ#rxlW@x9 z9?lTRaV!(q`NX-#Xed`v4fkOShN8)$lFBTFpM-|^u)bTsmRM^ZIbbKw)%E1$;@+A{ zt1+q~loY}vTlkT_G#Q2F{IKdYdyheJ=O!DY~9`WS;4@$zwwKa1#m=671_e<7ec(@A>Cq z)qH*+e~k}7-Gi{-TXz7SZ;kA;n@ zCw~r_iMF4cu6jzsn|S==7ammZ7P{o~t`lwsAGoXZsa4k9zCP z8oSE5e;3Oeq9&rDj5ryWmqhIL0V1M4nEfu5CJRX#R-XM|wC^2aNFGXgAeP7_u-hkV zvu)3PwNuiH*3#Vs08ui@dPv6?NVO!fG-DQzb3O)JKSF(!mBKm)H-=YS>>xy^l%)tf zB_lSBXHVf^lLl7wSUxKR(fSEcidyoH1vWO=4Hb-7vhL(O`KXMT~PQSW+JI(1%jhN+s)#_@r1x} zfwogx*9;!rq|*L_RESu7isk{w!HZ*l$NgbT4YeE!NbAeX9Q{N;P`v!yW`uc{EjT^M z`=v+X8SKX_9+;6V*>Ro?)%nMu(-ZZhV8wBrngapQ0fT8_H98(h^JP6V8aoY{m6G(j z$lB&(BFUB!`S7r!WeBBtL&q%Y7XxF_H{< z2Wpi{^b&jeqR55)%$aeqmuH%?H)=QNc7**&q>=QjDB~;k;ZN>FZB>dB7ds#7v(C81 zUa?xipE6rbKX3ax8BYKJoo=(@iZm!Q(i*KUsLBpZj#IfG!bcW%~3LDerO!hvLdsTTh&K;+`d6rBdP_%To!}dP2 z%Uh?@Lm<3!zvfF^oPnWsNP!whLY+vGC$eG<_mlfDbxF)=!_I0r`eb_iITaw02K6lV z`ebB$KZ8_}a%Jl#X(!wUaQ#T{n=00>;h>uqvu7xI3wige?<_t`FM=zsJt)oz{lmJn z?rNHat{o%JHr^*H3P>Wl{plnUQyZDpHzLIMpRcA0EHQi!Mmpq|)R&k=r^Xl6vWJ`84V_IFoxtNm55qu@c zaHOqjz`m!+MRIa=hY)o!SDDmOedKITKEHo$UNpQ^zGpWUmlC{MHB$M-a*rWhzYK-A z^H0T~`|dPxD;tO{Pw#LZsx#xV(Eq-~!orSnQB^g7sH*;ZV81`6=RHqz@3LtTJwe_JsexzgfqPiRhEH>UJtA;!^(fCE7JK`IPW2-ZXQXI3=ispTA0P;S z`QTY9mi6A6!qDA9A=kS*Bde(kX;O3j!E2he0_@*? zgj)sohu^<}jL~Q&plk^R*oL9y8VV3rqeuCNG1YziXrWO=Suf&jU4#sM^4g(xl2wH| z$t)6&io}(#1c${3@eC$d>Y}vzo5TNxx`o#Fb!UIw3x3J|T8?Xq@IW^@p5FFSZ=B6= zpS;wkfJRcu?N>+7cVtFr0Ow>DTOJWj*u!B+D=)V?t|Bj%FJC;}2HCw^aLE*y>OpO= zv~mMJtUae=UD={L`c2ED5I4;4W9)tdcqPlq3MC^5cG^1D7AhBdb*5AGog>HHx0xvU zUHkoS6argqO*O2$f9|68ii~@N*jvlo4-1Qw=AVL%m7B+S4-)!Abkzy}5R#M0%YEm4 z!-|DPk_k}*8wbr{^7oP~elfimOAY0*bCeiqt#Y3X;1vEcE>&9n=m5^eV`B(SBuZ2f zq7x`9B)Rc|f*P%%)e};*f>5J)#-?IUWV6qp=R`SW+)i!+4Uc@wS%KdbCl_skTwCbg zu&h%7+D;{a7u`Pg75#NDbdL__-kSgATA9+y>QK78xlI=P^NG?HOjIWveXgJ7!29>) zQnUI&Bp^;qgujgW?hZZL@(jHo(3?YAJ+WyZ_|lruj{UZgRfVWHvsDO!P*d^nN?u#0!>n6oARb_7^l@6rceF{0bD$XrDfm3aZc9f6bj|bI^OSoJWow-J_5%~Z zQVon$OAz}L>9;#U4{WI#cfO8?iAJhv8`AE%gT7=&QUM)JO-)B-(Y2n2NPTFhz9Gqy zOlI(7-m#+_#5S+C+_c4L{SIH5jkuO%bxlpa&*&l__Y8Cq0?HwyW}BK*g;v5Ug7W=% z8>jlrEycC=k3-teV%d~tm8FVlbqEspliY)@?fZ3nM-W%@h?;{gX;<}|R~32) z0iCm(vi{qwzYm2|O;hS;M2$Ui`Ypfd3p2Nf51Dha?>rV!Rv!Z!XWdWx0hCaBS=oA0 zwaN>Pl7kFMT{IP5q>X5Jy`l<)xi^R5NFjm<+!6Zc&mS0PPo?3VRn5uosW~T}tv41# z)O;q%g=BAZcRi%uis(Z@IjSKuaVOAw2Nb?KsT;CtBi99)@V=IQxVK*-VH~04QS*CPdHuN#BQ(90nLdgh<+1HvAn3{vTHO-Z!O}{3irl_*AG=nZG2JuW=;bC*kY%QYb zz@Quymx1J#(t*L;QPVqpiSeXr8%daJF-9VR` zGa}AYzOr3=b^g~tfyA{FAViNVzOV5=WzaeM6o-JJFAN+ez8O(7Nbp zcXf(6gMjwVDrp`UBZJ^1Ss8*FCF3%D(Pl6xld!%Quw^wbbcFFp1dj<96VN6lFMlNj z+9-imdRQQr64y}MOgzvug|Razh$8jx8`viY$mm%}`*d$G*OVI3#NL@xve>c_bi{8K zpLf7ayK`L0RDA4+8?+HPqZcy(nBSvONmfsDmgrxh47Xo6bL-Bk@0%&iqb>uOXJJgC zkGmPQe)tCYbes4`-Vc0flVTS)eIx7LPC#2C#dAs`L2VZER0sL%^0J`MA2rnIPE@A%}V<~(!DZ?>mD zI&nl?*9jb*2?-1Ti88!-4jb%KNk>gzDZZPvy?_lq8$F4pj0haP34Q+jW=)17hx0f* z?7N?6A{i2WF(GqLwn(XxS2uOrUEynw1XkS7t&5Oucz-GM*7Gvc;cij51jG00@}!HP8v#ex>jH{fGa3lOnz9kJ3yo0gN0vWV8jIBF4~z zhYX@WFH4Nfb1*-RW5mgFn0*YboY%Y`9m|7}A_dYg?$=fC_?F1(#(aiefKFE8*JWD1 ze!bp?WOY}Oy~}L<{=uvBN3W)0(tQ}K*aevUQ4wCrvb-G>U;?()wi(28MZ`8Cf7Wl` zEC)@yf#z}dx@55{{yD@Aca{zOv8niG;vJ6c^@1&?60nkO%dc(v$W$C+c>us?3X{mX z{jhP*oxrVSlJYuwzu+)|0SH0Hkl;jkI5=?Usyfo$6hn3r2|@9h^~V?!L)r@478fT` zQ<$sEG$K?1f~2vyEg+rP^8f1q|Cr}Dd$K)!N3Z?D(aGt%`IP%yX&@?!#@^NS?-1Sf zOoP~?&!w3ZnZUlDK$LV8v)}%A)6R?E?t+~lx9aHHpduzUs4TpmReH2g>2BHiTYIyN zsR~@-S~X-=-{}sJ)qP>w2i;60{Dxv?{h`gKCzxm}o7Lf5!?6^}x;IHjp%7*4qdaz` zkQh5%6x{lSSZp(~?_qqVZ|nL|Ux?sxPH#?}^ub+)0Q)SH{fG6!v!`U(Ov$fz7K>Q@ zQC!0Shh?M1SDb(pjo%#_z4ttQZ^6*#+3JS0aIS;_gA!?f)U2(Cahh8OwPfpBiK;qK zOORnG&Kf{yc|be>a7gvi^y#!W59nfSKu_v7RR|~sM`q@>Pe`V`i~MKFhfW^DRpK>c zC<}Gu3dibq$eAOEa8%;KBEO}pd+ZCrSd@5J|5g1f{|EW^>0kMOYTsl39~g}FfA_SW zC6mQLi3k2qR2KXHef{73_uXC7l>T(Fa;xFaqs#zQmA(11(6qI+rMMdHjOR0&&%fMr_W9=9-|X3QW}TTZEe#dQn`}1$001Qd4%NXwd;b

52)T=qZliR zTL?r$hEYGM?9PvrUo~gS>5*Jd|IUpl*Y1l|4O}aUdG3o7y**A9wL%L z4BK7KoM3>%^Ta5o?A318nUcOA@xEs#tFXMk*mUgk3hTYtq+x97eRxQ$c+>mRc=nQ)kox4-f zXL82yYu)Gm;&x+3&g=6nQXH#ssLgs^bmvWlw6fAYideyoy6mzKuHEkJk^TpHSi~DB;1vX`-mikQ7mvxj9s$O688xGTCO3Rw#wOlHG z647w~e3qmRw`nsN;dI=m%YLf_j3@T6V647DcmHcW|?|R3u8*aJCl|au??>jiJ z>y3hC^qKq-LJjGh-k02jFGP7?Af^(w=9?s66+U{OKbpCDTD$<;<8!>!ti29Fle})e zq%m~sRh}fV)P!X^BmNR)*e z(i-3F)Adwps^6-m2q+`71@fu6oEGiGNxhz{#BrbsTSPRujC5`RD=XlN4c&3*AhAcQ zuXpaomyZP2-)hcj=eu&D{M%~% zM9wy=D5RB<=fWYUO%ZBe;2$R_xb%|wld_mc;_YT!X@iqA=4piO3S*BD=X7I+8~Le7 zc281H%tg#4{TfjcM8SF$;OwA)L27(H-29pSsB=2+v0r0YNLrnE%o7f45~j;4ox6qn ziE=e`N%ke>o#is5N^{LY)#X`(<4j5xuSBJV?mQU@?5he>5zr1Pv!IS+Gy9N{MUe#M zx5P+M-n?llytbG)H`ToRXDb1nlY7^iPsG2h;c50LP0xGA1n(`T!is* zOA9!XT?+u1sh265)n;ZOb51Kxh}CM~kyr~Aja`a`s1d8c#oCkYy-|oZPXmz2s5Crq z>~3tZP}Fy(Z0a`3Pf5*h+UVAljML==l4oLW|PK(KW2b)KL=+lhSz0~ z3=?qcFOsvun%U_HjBOa0I%vp;iYbq$wUD(SV4?RN+8HfTJ?yd?caqvZfZ!n-`jpg) zDp?CwN02pXmA!p8m~`E4SD6joLTWW?@F0xDK=Nc{>0981-}#S93l1%n3f6*3GAHUA zyT&deG7?t>@zcP&x0#5dDb=!>Y)4-@sq4-2Ow6xt1r=%Z#eLNGj0m-trfL(=Ra$&e z$FGGnU8KG9PG41fdXK^Yvh;(_J)@V-W0O}_iKIZ+2&JInXzSCpqeV8K*6!dV@OxRy zMVK+qS~4Gige!b2vy-7$hB*Faxgep;VB0nOmSBg{w22cpD%g3|+&07Z!etEjVE+-R zMj6)Q5qUN%aYdUIzw&yerFx3AZy@ay2zm^o63IFtQjzpLC!%wyd2=~o;V1|CKKZIs zZVW%V)TBq!@F*Yb$KhQ&13HK8Jbzd`^k(jOc=xQ|twn)1lJ-MHJ;e87lfgdbyS$9i zmn5^q9={PEM2*43Y}5qSIZaHnt;VLlFw@rt?DiV-dA72HB+@Dvgvulvn6a*5_hA;V z*aU%A_T)W+AP3-y^N_9jAF(N(WoEh$hsrt2{DGFDnam)Re&E@`WK4zq)9KgSu5Xs8 zMCz^cAi6Hd@QY{Jqq_rfn(00yB_PN-jm=0e;fm_QNJsJFJ%0hHC}{=F?WSnoSSaHL z&y5YI6PAM!F#!p)%9~gvLq>|KJ1fgsnKaQ71B9^djc6YMvJ{>02s<}o--2=py|-*H z=3x{gL1Mv1b@TFqYu`0ry#HwTijByt2bNUA@7wm)HTq4d!!$Erv_r9FY^O8TLi_jI zLQM5-M6nr4TqZmnmt5TTg1Xj&lC&FJq#AIc-}jcog3nFtbxW1nyI7m~#k4FYtv}Pw zr!_eZuk@3()w~MXfATh&Rq12ph$EJuj{y>HslO_>5kaueJi3~*x56M(>_r(e*{R7j z9&78>A(IlNc97{sw$>lPVpip2O0vA@oN_WXDrPUP<@u!hTGZ!Bx6-d2uJS!%J%LKM z*k*QYBm}|>_7z3Y(ss=okV#sgq&*<^d!&boQxnuan&m@$7n;r3R7i)D;w=a?g)91Kot1 z(s=aRrz*L&xge(!0-B7*ii+H(T9HE-pz{t!1RQXt6H$*Z>b z+&B=3;5@1*0H3w}fzlUY4iVSdHxizEUB2TZ0tOE;28g!l=T_5P;igA3D2~}Yo_~Kf zzqfT(%8gqLzH(j*V4FB~4M+u^^2yyx=H$Mn%((Pr_NNH+6(uw$ZBt-Iml7>sY49KR zqg$v6PECnhsQ%IPav=k{;S88Rg6(_%cYQUueXT%NxA}hg2=KQyFSv>#a9LVy$Lsh- zkp{2_1~mTWq@BLK8aMoSkP)|Z;}+8|@~Onp3m$jDgq96=)ZDdyIh8_^hi{B6Dm4;&f8wYVm37C%Tb{e9yJ z8-{^drM-H2xyNd<{fm(Ssev-hAAqa7n~r-7-E|^^ahI3Ne3a)YhbIn@rEQrqDNXXc z!TED6xkRc7Bczm!D@gn^SKol-23YXM(t$@5z#R8ozW;hYgXhzR2njLtyOCYey#tbi ziOPn{{ z1{d`RZHf#TW4nz{*Tg6`PvUJ$#(|IM-WvuH)82Fx$R@n)YV4sSoa3OlvdZaxNmtL{ z7T?}m9w;Q$Tf+H=+TRn&$k*MR<3jku-!(1D5>$0dYA5o@Z&zlJ9&|=wy5$^DO)&5p zWA+kR&Xf7_c3s^IWFLo1JrRXGYlUE=PV{Fj0RYba_=#-hHPer0M?T2C)nkHQEra~q z%gZz@f;zt%h8uk!_+Ff<7q)UHIl0x4MSN<;AFN2M)Ks8=>%Vtqb8ajiA$Nfrq3~xd z`oDz$kdnrN2T9!#Phg}Qq?D8Zp^Rk;PdpNWfGX>G&F(GWkU$tq+d;kkD_lYX&{U0D z_qlS+9TH)>stJ7)b0ttq04yZ?LsCMN-(>^U4`h z3lF~14m$OO>Q~y(joS0ZRAriZ>v)+raUQzo0bD=vr4EF1NZR3H)`u2!v+P$AC4F#bSHs7Gc6CKFzH97^R!J-*yH=d&gR+5_-`B z;fs#7b196x(H+lg=N^QAs;yb1m{$S!7#B|=iyR-;X(tgO_jqY#V-L(W#>FWNjGhgF z##?Yn{SP9K)elLirRjS0)Hol#wiYJ+i3?#{+Q@oLn5>$vk<0dOWzJ|F{aTee=WAmYl zBgf+UFgVD6=fvl(@eVc&2#-k?2=~g1QToFO8G1E`pm``b`m5SY5;M-t!8SkWn2qF3w7MRC zj%Z@C7dcF0ysZc1Rl=3r>?4w|Tf@LD7Wnox(R6r)jEK2dtTq|=ezrRJ;D^rpuL8uF zC~ba>7XvvSw%NUiRCoeDc&^xC!$8Oyb*X_Tsdqp=5Mzpk`S2vNzrJ!tcvt{qU97+3 z5&3f{$+6;%>t8kB3wg4j3!v=~$aleWfKi$X8&{wwbW45$4)T>83IjjfQ|S$cg z|A_a{CiWvf2Vi_Uq63a>xx-Xq{<5z&=Ad*@+?JB6GeifjcoZ$piXA|o$^TVWRb<6h zq0b)v!&YF$#-Y{w@x8=(OR8=WCfDFIL>9EXAo*~@ut4eaU*|;QyS8Z&I`}t_za7NA zkW_Ubl;}=N-N1*mr=lv&ie*6O&?7_-SJP*bbEK%HnI1+X)WNPp#j>0JZbQY)TPSDp zH6;cZE)E}3R>-}oIp+n(>P6-lYuVs($B6R={X&l#)7inORrA3#RO(RuaEJIGkN#vg z4XD}B!Ns#t<0bBBLEGYHVeZ_+Gi3y3tx+JH!}-X=wD-5SnDqd^CCk;HoL04f()Fs) zf%UTP;Exe>3|{!9nC2?8c`u}M<*>WETQz$$)N`6>p>)!5v+~dU+?T94ok_ebFI z^!_%PAG{6IK87RxP$<+9(dK;OQ2k(eQyo4A`?~&P%iLSiLUg#gAb- zSNf+&KL>G^KiY4ZV>@nOzCba@Y?m*9JxjTXyupbl?;fT{9BOM%m5QUE7c>8&?f&f| zW9omlze2rb3*XAI?@Mhq!@XjFi3wrNX8RwC;@Jf{+e~P$Dv70jF~vRm)n|IF&Ob8N z>H13z6j>!AGK#7_!`+M1I^SKz)0(}dKzrqkKJS{ERrGui2wU>~A_4a)n%{=@gX4 z{k}X{?P>IB2vp+pT0Wy4@`Pku34$L-5fT&9kST!xXu!W1fl2^E0y1I{&A%J}oAwXK z|4aLe{HxkO_5WS%pN{`8Sqt!+cF@-|2w#y9n&C123r$BMS^ayL44)DT#;v&2rA_uo zcF)_w$aA!UKy{mGCNsF6@~Oq5Nk?{lDNe=&kU0V~5Z2qz?dDXATTPqOQ@yk+epaGi iNNouFPyatW#)lKrGMo{QA7APG%Rs<1pe2tig8mDZ^ZIoF literal 0 HcmV?d00001 diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc index a486110a73..3967416f73 100644 --- a/selfdrive/ui/qt/maps/map.cc +++ b/selfdrive/ui/qt/maps/map.cc @@ -526,6 +526,10 @@ void MapInstructions::updateInstructions(cereal::NavInstruction::Reader instruct fn += "turn_straight"; } + if (!active) { + fn += "_inactive"; + } + auto icon = new QLabel; int wh = active ? 125 : 75; icon->setPixmap(loadPixmap(fn + ICON_SUFFIX, {wh, wh}, Qt::IgnoreAspectRatio)); diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 2fefa69a80..07d6877463 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -338,27 +338,27 @@ MapETA - + eta 도착 - + min - + hr 시간 - + km km - + mi mi diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 0870ff7028..424488fc56 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -338,27 +338,27 @@ MapETA - + eta 埃塔 - + min 分钟 - + hr 小时 - + km km - + mi mi diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 0620382a63..1eab75a6b4 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -338,27 +338,27 @@ MapETA - + eta 埃塔 - + min 分鐘 - + hr 小時 - + km km - + mi mi