From 36701a82a344447fe33476f42cd83034dbc373a4 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Sat, 8 Oct 2022 00:02:57 -0700 Subject: [PATCH 001/101] Kia: update Optima platform name (#25852) * https://en.wikipedia.org/wiki/Kia_K5 * it's actually the same generation, but 2019+ is a facelift * g4 * fix * rename --- selfdrive/car/hyundai/hyundaican.py | 2 +- selfdrive/car/hyundai/interface.py | 4 ++-- selfdrive/car/hyundai/values.py | 20 ++++++++++---------- selfdrive/car/tests/routes.py | 4 ++-- selfdrive/car/torque_data/substitute.yaml | 4 ++-- 5 files changed, 17 insertions(+), 17 deletions(-) diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py index 139a14d5e8..7f3f6a72c5 100644 --- a/selfdrive/car/hyundai/hyundaican.py +++ b/selfdrive/car/hyundai/hyundaican.py @@ -38,7 +38,7 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req, values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 # Likely cars lacking the ability to show individual lane lines in the dash - elif car_fingerprint in (CAR.KIA_OPTIMA, CAR.KIA_OPTIMA_2019): + elif car_fingerprint in (CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL): # SysWarning 4 = keep hands on wheel + beep values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 97c1f7a5dc..2d960ed17f 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -202,12 +202,12 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.indi.timeConstantV = [1.4] ret.lateralTuning.indi.actuatorEffectivenessBP = [0.] ret.lateralTuning.indi.actuatorEffectivenessV = [1.8] - elif candidate in (CAR.KIA_OPTIMA, CAR.KIA_OPTIMA_2019, CAR.KIA_OPTIMA_H): + elif candidate in (CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.KIA_OPTIMA_H): ret.mass = 3558. * CV.LB_TO_KG ret.wheelbase = 2.80 ret.steerRatio = 13.75 tire_stiffness_factor = 0.5 - if candidate == CAR.KIA_OPTIMA: + if candidate == CAR.KIA_OPTIMA_G4: ret.minSteerSpeed = 32 * CV.MPH_TO_MS CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.KIA_STINGER: diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 52a5088319..a43f17ac00 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -85,8 +85,8 @@ class CAR: KIA_NIRO_EV = "KIA NIRO EV 2020" KIA_NIRO_PHEV = "KIA NIRO HYBRID 2019" KIA_NIRO_HEV_2021 = "KIA NIRO HYBRID 2021" - KIA_OPTIMA = "KIA OPTIMA 2016" - KIA_OPTIMA_2019 = "KIA OPTIMA 2019" + KIA_OPTIMA_G4 = "KIA OPTIMA 4TH GEN" + KIA_OPTIMA_G4_FL = "KIA OPTIMA 4TH GEN FACELIFT" KIA_OPTIMA_H = "KIA OPTIMA HYBRID 2017 & SPORTS 2019" KIA_SELTOS = "KIA SELTOS 2021" KIA_SORENTO = "KIA SORENTO GT LINE 2018" @@ -155,8 +155,8 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { HyundaiCarInfo("Kia Niro Hybrid 2021", harness=Harness.hyundai_f), # TODO: could be hyundai_d, verify HyundaiCarInfo("Kia Niro Hybrid 2022", harness=Harness.hyundai_h), ], - CAR.KIA_OPTIMA: HyundaiCarInfo("Kia Optima 2017", "Advanced Smart Cruise Control", harness=Harness.hyundai_b), # TODO: may support 2016, 2018 - CAR.KIA_OPTIMA_2019: HyundaiCarInfo("Kia Optima 2019-20", harness=Harness.hyundai_g), + CAR.KIA_OPTIMA_G4: HyundaiCarInfo("Kia Optima 2017", "Advanced Smart Cruise Control", harness=Harness.hyundai_b), # TODO: may support 2016, 2018 + CAR.KIA_OPTIMA_G4_FL: HyundaiCarInfo("Kia Optima 2019-20", harness=Harness.hyundai_g), CAR.KIA_OPTIMA_H: [ HyundaiCarInfo("Kia Optima Hybrid 2017", "Advanced Smart Cruise Control"), # TODO: may support adjacent years HyundaiCarInfo("Kia Optima Hybrid 2019"), @@ -1136,7 +1136,7 @@ FW_VERSIONS = { b'\xf1\x87954A22D200\xf1\x81T01950A1 \xf1\000T0190XBL T01950A1 DSP2T16X4X950NS8\r\xfe\x9c\x8b', ], }, - CAR.KIA_OPTIMA: { + CAR.KIA_OPTIMA_G4: { (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4100 ', ], @@ -1150,7 +1150,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\x816T6J0051\x00\x00\xf1\x006T6J0_C2\x00\x006T6J0051\x00\x00TJF0T20NSB\x00\x00\x00\x00', ], }, - CAR.KIA_OPTIMA_2019: { + CAR.KIA_OPTIMA_G4_FL: { (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4110 ', ], @@ -1367,7 +1367,7 @@ CHECKSUM = { FEATURES = { # which message has the gear "use_cluster_gears": {CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KONA}, - "use_tcu_gears": {CAR.KIA_OPTIMA, CAR.KIA_OPTIMA_2019, CAR.SONATA_LF, CAR.VELOSTER, CAR.TUCSON}, + "use_tcu_gears": {CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.SONATA_LF, CAR.VELOSTER, CAR.TUCSON}, "use_elect_gears": {CAR.KIA_NIRO_EV, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.KONA_EV_2022}, # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 @@ -1383,7 +1383,7 @@ HYBRID_CAR = {CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_PHEV, CAR.KIA_N EV_CAR = {CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_NIRO_EV, CAR.KONA_EV_2022} # these cars require a special panda safety mode due to missing counters and checksums in the messages -LEGACY_SAFETY_MODE_CAR = {CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_LF, CAR.KIA_OPTIMA, CAR.KIA_OPTIMA_2019, CAR.VELOSTER, CAR.KIA_STINGER, CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.KIA_CEED, CAR.ELANTRA, CAR.IONIQ_HEV_2022} +LEGACY_SAFETY_MODE_CAR = {CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_LF, CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.VELOSTER, CAR.KIA_STINGER, CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.KIA_CEED, CAR.ELANTRA, CAR.IONIQ_HEV_2022} # If 0x500 is present on bus 1 it probably has a Mando radar outputting radar points. # If no points are outputted by default it might be possible to turn it on using selfdrive/debug/hyundai_enable_radar_points.py @@ -1408,8 +1408,8 @@ DBC = { CAR.KIA_NIRO_EV: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar_generated'), CAR.KIA_NIRO_PHEV: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar_generated'), CAR.KIA_NIRO_HEV_2021: dbc_dict('hyundai_kia_generic', None), - CAR.KIA_OPTIMA: dbc_dict('hyundai_kia_generic', None), - CAR.KIA_OPTIMA_2019: dbc_dict('hyundai_kia_generic', None), + CAR.KIA_OPTIMA_G4: dbc_dict('hyundai_kia_generic', None), + CAR.KIA_OPTIMA_G4_FL: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA_H: dbc_dict('hyundai_kia_generic', None), CAR.KIA_SELTOS: dbc_dict('hyundai_kia_generic', None), CAR.KIA_SORENTO: dbc_dict('hyundai_kia_generic', None), # Has 0x5XX messages, but different format diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 3ae3a357ce..82c0614493 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -88,8 +88,8 @@ routes = [ CarTestRoute("37398f32561a23ad|2021-11-18--00-11-35", HYUNDAI.SANTA_FE_HEV_2022), CarTestRoute("656ac0d830792fcc|2021-12-28--14-45-56", HYUNDAI.SANTA_FE_PHEV_2022, segment=1), CarTestRoute("e0e98335f3ebc58f|2021-03-07--16-38-29", HYUNDAI.KIA_CEED), - CarTestRoute("7653b2bce7bcfdaa|2020-03-04--15-34-32", HYUNDAI.KIA_OPTIMA), - CarTestRoute("018654717bc93d7d|2022-09-19--23-11-10", HYUNDAI.KIA_OPTIMA_2019, segment=0), + CarTestRoute("7653b2bce7bcfdaa|2020-03-04--15-34-32", HYUNDAI.KIA_OPTIMA_G4), + CarTestRoute("018654717bc93d7d|2022-09-19--23-11-10", HYUNDAI.KIA_OPTIMA_G4_FL, segment=0), CarTestRoute("c75a59efa0ecd502|2021-03-11--20-52-55", HYUNDAI.KIA_SELTOS), CarTestRoute("5b7c365c50084530|2020-04-15--16-13-24", HYUNDAI.SONATA), CarTestRoute("b2a38c712dcf90bd|2020-05-18--18-12-48", HYUNDAI.SONATA_LF), diff --git a/selfdrive/car/torque_data/substitute.yaml b/selfdrive/car/torque_data/substitute.yaml index 92361d37f4..f5e3d1d61d 100644 --- a/selfdrive/car/torque_data/substitute.yaml +++ b/selfdrive/car/torque_data/substitute.yaml @@ -17,8 +17,8 @@ LEXUS RC 2020: LEXUS NX 2020 TOYOTA AVALON HYBRID 2019: TOYOTA AVALON 2019 TOYOTA AVALON HYBRID 2022: TOYOTA AVALON 2022 -KIA OPTIMA 2016: HYUNDAI SONATA 2020 -KIA OPTIMA 2019: HYUNDAI SONATA 2020 +KIA OPTIMA 4TH GEN: HYUNDAI SONATA 2020 +KIA OPTIMA 4TH GEN FACELIFT: 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 From 2e7fa330b346b6435d0b15524f3b5ce878d213de Mon Sep 17 00:00:00 2001 From: Greg Hogan Date: Sat, 8 Oct 2022 04:07:35 -0700 Subject: [PATCH 002/101] hyundai: fix logging stock AEB events (#25152) --- selfdrive/car/hyundai/carstate.py | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index b9c7327a93..1f2de3286e 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -126,12 +126,12 @@ class CarState(CarStateBase): ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear)) if not self.CP.openpilotLongitudinalControl: - if self.CP.carFingerprint in FEATURES["use_fca"]: - ret.stockAeb = cp_cruise.vl["FCA11"]["FCA_CmdAct"] != 0 - ret.stockFcw = cp_cruise.vl["FCA11"]["CF_VSM_Warn"] == 2 - else: - ret.stockAeb = cp_cruise.vl["SCC12"]["AEB_CmdAct"] != 0 - ret.stockFcw = cp_cruise.vl["SCC12"]["CF_VSM_Warn"] == 2 + aeb_src = "FCA11" if self.CP.carFingerprint in FEATURES["use_fca"] else "SCC12" + aeb_sig = "FCA_CmdAct" if self.CP.carFingerprint in FEATURES["use_fca"] else "AEB_CmdAct" + aeb_warning = cp_cruise.vl[aeb_src]["CF_VSM_Warn"] != 0 + aeb_braking = cp_cruise.vl[aeb_src]["CF_VSM_DecCmdAct"] != 0 or cp_cruise.vl[aeb_src][aeb_sig] != 0 + ret.stockFcw = aeb_warning and not aeb_braking + ret.stockAeb = aeb_warning and aeb_braking if self.CP.enableBsm: ret.leftBlindspot = cp.vl["LCA11"]["CF_Lca_IndLeft"] != 0 @@ -294,12 +294,14 @@ class CarState(CarStateBase): signals += [ ("FCA_CmdAct", "FCA11"), ("CF_VSM_Warn", "FCA11"), + ("CF_VSM_DecCmdAct", "FCA11"), ] checks.append(("FCA11", 50)) else: signals += [ ("AEB_CmdAct", "SCC12"), ("CF_VSM_Warn", "SCC12"), + ("CF_VSM_DecCmdAct", "SCC12"), ] if CP.enableBsm: @@ -383,12 +385,14 @@ class CarState(CarStateBase): signals += [ ("FCA_CmdAct", "FCA11"), ("CF_VSM_Warn", "FCA11"), + ("CF_VSM_DecCmdAct", "FCA11"), ] checks.append(("FCA11", 50)) else: signals += [ ("AEB_CmdAct", "SCC12"), ("CF_VSM_Warn", "SCC12"), + ("CF_VSM_DecCmdAct", "SCC12"), ] return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2) From 2ed82387a5df5b86113d23fc4cc7d7aeadabdb52 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 9 Oct 2022 05:10:00 +0800 Subject: [PATCH 003/101] cabana: fix Incorrect Y-Axis Scale (#26018) --- tools/cabana/chartswidget.cc | 33 +++++++++++++++------------------ tools/cabana/chartswidget.h | 1 + 2 files changed, 16 insertions(+), 18 deletions(-) diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index 3e1a8b8410..5caa8d5a43 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -194,8 +194,6 @@ ChartWidget::ChartWidget(const QString &id, const QString &sig_name, QWidget *pa void ChartWidget::updateState() { auto chart = chart_view->chart(); auto axis_x = dynamic_cast(chart->axisX()); - if (axis_x->max() <= axis_x->min()) return; - int x = chart->plotArea().left() + chart->plotArea().width() * (parser->currentSec() - axis_x->min()) / (axis_x->max() - axis_x->min()); if (line_marker_x != x) { line_marker->setX(x); @@ -214,7 +212,6 @@ void ChartWidget::updateSeries() { vals.clear(); vals.reserve(3 * 60 * 100); - double min_y = 0, max_y = 0; uint64_t route_start_time = parser->replay->routeStartTime(); for (auto &evt : *events) { if (evt->which == cereal::Event::Which::CAN) { @@ -226,9 +223,6 @@ void ChartWidget::updateSeries() { val -= ((val >> (sig->size - 1)) & 0x1) ? (1ULL << sig->size) : 0; } double value = val * sig->factor + sig->offset; - if (value < min_y) min_y = value; - if (value > max_y) max_y = value; - double ts = (evt->mono_time - route_start_time) / (double)1e9; // seconds vals.push_back({ts, value}); } @@ -239,7 +233,7 @@ void ChartWidget::updateSeries() { series->replace(vals); auto [begin, end] = parser->range(); chart_view->chart()->axisX()->setRange(begin, end); - chart_view->chart()->axisY()->setRange(min_y * 0.95, max_y * 1.05); + updateAxisY(); } void ChartWidget::rangeChanged(qreal min, qreal max) { @@ -247,17 +241,20 @@ void ChartWidget::rangeChanged(qreal min, qreal max) { if (axis_x->min() != min || axis_x->max() != max) { axis_x->setRange(min, max); } - // auto zoom on yaxis - double min_y = 0, max_y = 0; - for (auto &p : vals) { - if (p.x() > max) break; - - if (p.x() >= min) { - if (p.y() < min_y) min_y = p.y(); - if (p.y() > max_y) max_y = p.y(); - } - } - chart_view->chart()->axisY()->setRange(min_y * 0.95, max_y * 1.05); + updateAxisY(); +} + +// auto zoom on yaxis +void ChartWidget::updateAxisY() { + const auto axis_x = dynamic_cast(chart_view->chart()->axisX()); + // vals is a sorted list + auto begin = std::lower_bound(vals.begin(), vals.end(), axis_x->min(), [](auto &p, double x) { return p.x() < x; }); + if (begin == vals.end()) + return; + + auto end = std::upper_bound(vals.begin(), vals.end(), axis_x->max(), [](double x, auto &p) { return x < p.x(); }); + const auto [min, max] = std::minmax_element(begin, end, [](auto &p1, auto &p2) { return p1.y() < p2.y(); }); + chart_view->chart()->axisY()->setRange(min->y(), max->y()); } // LineMarker diff --git a/tools/cabana/chartswidget.h b/tools/cabana/chartswidget.h index 0413d65e09..81df2237bc 100644 --- a/tools/cabana/chartswidget.h +++ b/tools/cabana/chartswidget.h @@ -37,6 +37,7 @@ private: void addData(const CanData &can_data, const Signal &sig); void updateSeries(); void rangeChanged(qreal min, qreal max); + void updateAxisY(); QString id; QString sig_name; From f31aa6853354226baada15f6a12b57f16bc3853b Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Sat, 8 Oct 2022 23:28:33 -0700 Subject: [PATCH 004/101] Subaru: log stock FCW (#26012) * log stock FCW * Update selfdrive/car/subaru/carstate.py * never seen 1 (could be aeb?) --- selfdrive/car/subaru/carstate.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py index 128e4245b2..ba873c48d7 100644 --- a/selfdrive/car/subaru/carstate.py +++ b/selfdrive/car/subaru/carstate.py @@ -58,9 +58,6 @@ class CarState(CarStateBase): ret.cruiseState.available = cp_cruise.vl["CruiseControl"]["Cruise_On"] != 0 ret.cruiseState.speed = cp_cam.vl["ES_DashStatus"]["Cruise_Set_Speed"] * CV.KPH_TO_MS - if self.car_fingerprint not in PREGLOBAL_CARS: - ret.cruiseState.standstill = cp_cam.vl["ES_DashStatus"]["Cruise_State"] == 3 - if (self.car_fingerprint in PREGLOBAL_CARS and cp.vl["Dash_State2"]["UNITS"] == 1) or \ (self.car_fingerprint not in PREGLOBAL_CARS and cp.vl["Dashlights"]["UNITS"] == 1): ret.cruiseState.speed *= CV.MPH_TO_KPH @@ -78,6 +75,8 @@ class CarState(CarStateBase): else: ret.steerFaultTemporary = cp.vl["Steering_Torque"]["Steer_Warning"] == 1 ret.cruiseState.nonAdaptive = cp_cam.vl["ES_DashStatus"]["Conventional_Cruise"] == 1 + ret.cruiseState.standstill = cp_cam.vl["ES_DashStatus"]["Cruise_State"] == 3 + ret.stockFcw = cp_cam.vl["ES_LKAS_State"]["LKAS_Alert"] == 2 self.es_lkas_msg = copy.copy(cp_cam.vl["ES_LKAS_State"]) cp_es_distance = cp_body if self.car_fingerprint in GLOBAL_GEN2 else cp_cam From 754b44e7ceb2b6b029cf511b821f4328b90364f9 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 9 Oct 2022 23:44:19 +0800 Subject: [PATCH 005/101] Cabana: increase slider precision to milliseconds (#26025) --- tools/cabana/videowidget.cc | 52 ++++++++++++++++++++++++------------- tools/cabana/videowidget.h | 3 +++ 2 files changed, 37 insertions(+), 18 deletions(-) diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc index 7edbe5e38f..957747584c 100644 --- a/tools/cabana/videowidget.cc +++ b/tools/cabana/videowidget.cc @@ -31,9 +31,7 @@ VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) { slider = new Slider(this); slider->setSingleStep(0); slider->setMinimum(0); - slider->setTickInterval(60); - slider->setTickPosition(QSlider::TicksBelow); - slider->setMaximum(parser->replay->totalSeconds()); + slider->setMaximum(parser->replay->totalSeconds() * 1000); slider_layout->addWidget(slider); total_time_label = new QLabel(formatTime(parser->replay->totalSeconds())); @@ -63,7 +61,7 @@ VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) { QObject::connect(parser, &Parser::rangeChanged, this, &VideoWidget::rangeChanged); QObject::connect(parser, &Parser::updated, this, &VideoWidget::updateState); - QObject::connect(slider, &QSlider::sliderMoved, [=]() { time_label->setText(formatTime(slider->value())); }); + QObject::connect(slider, &QSlider::sliderMoved, [=]() { time_label->setText(formatTime(slider->value() / 1000)); }); QObject::connect(slider, &QSlider::sliderReleased, [this]() { setPosition(slider->value()); }); QObject::connect(slider, &Slider::setPosition, this, &VideoWidget::setPosition); @@ -75,8 +73,8 @@ VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) { } void VideoWidget::setPosition(int value) { - time_label->setText(formatTime(value)); - parser->seekTo(value); + time_label->setText(formatTime(value / 1000.0)); + parser->seekTo(value / 1000.0); } void VideoWidget::rangeChanged(double min, double max) { @@ -86,16 +84,16 @@ void VideoWidget::rangeChanged(double min, double max) { } time_label->setText(formatTime(min)); total_time_label->setText(formatTime(max)); - slider->setMinimum(min); - slider->setMaximum(max); - slider->setValue(parser->currentSec()); + slider->setMinimum(min * 1000); + slider->setMaximum(max * 1000); + slider->setValue(parser->currentSec() * 1000); } void VideoWidget::updateState() { if (!slider->isSliderDown()) { - int current_sec = parser->currentSec(); + double current_sec = parser->currentSec(); time_label->setText(formatTime(current_sec)); - slider->setValue(current_sec); + slider->setValue(current_sec * 1000); } } @@ -103,10 +101,25 @@ void VideoWidget::updateState() { Slider::Slider(QWidget *parent) : QSlider(Qt::Horizontal, parent) { QTimer *timer = new QTimer(this); timer->setInterval(2000); - timer->callOnTimeout([this]() { timeline = parser->replay->getTimeline(); }); + timer->callOnTimeout([this]() { + timeline = parser->replay->getTimeline(); + update(); + }); timer->start(); } +void Slider::sliderChange(QAbstractSlider::SliderChange change) { + if (change == QAbstractSlider::SliderValueChange) { + qreal x = width() * ((value() - minimum()) / double(maximum() - minimum())); + if (x != slider_x) { + slider_x = x; + update(); + } + } else { + QAbstractSlider::sliderChange(change); + } +} + void Slider::paintEvent(QPaintEvent *ev) { auto getPaintRange = [this](double begin, double end) -> std::pair { double total_sec = maximum() - minimum(); @@ -117,17 +130,21 @@ void Slider::paintEvent(QPaintEvent *ev) { QPainter p(this); const int v_margin = 2; - p.fillRect(rect().adjusted(0, v_margin, 0, -v_margin), QColor(0, 0, 128)); + p.fillRect(rect().adjusted(0, v_margin, 0, -v_margin), QColor(111, 143, 175)); for (auto [begin, end, type] : timeline) { + begin *= 1000; + end *= 1000; if (begin > maximum() || end < minimum()) continue; if (type == TimelineType::Engaged) { auto [start_pos, end_pos] = getPaintRange(begin, end); - p.fillRect(QRect(start_pos, v_margin, end_pos - start_pos, height() - v_margin * 2), QColor(0, 135, 0)); + p.fillRect(QRect(start_pos, v_margin, end_pos - start_pos, height() - v_margin * 2), QColor(0, 163, 108)); } } for (auto [begin, end, type] : timeline) { + begin *= 1000; + end *= 1000; if (type == TimelineType::Engaged || begin > maximum() || end < minimum()) continue; auto [start_pos, end_pos] = getPaintRange(begin, end); @@ -136,14 +153,13 @@ void Slider::paintEvent(QPaintEvent *ev) { } else { QColor color(Qt::green); if (type != TimelineType::AlertInfo) - color = type == TimelineType::AlertWarning ? Qt::yellow : Qt::red; + color = type == TimelineType::AlertWarning ? QColor(255, 195, 0) : QColor(199, 0, 57); p.fillRect(QRect(start_pos, height() - v_margin - 3, end_pos - start_pos, 3), color); } } - p.setPen(QPen(Qt::black, 2)); - qreal x = width() * ((value() - minimum()) / double(maximum() - minimum())); - p.drawLine(QPointF{x, 0.}, QPointF{x, (qreal)height()}); + p.setPen(QPen(QColor(88, 24, 69), 3)); + p.drawLine(QPoint{slider_x, 0}, QPoint{slider_x, height()}); } void Slider::mousePressEvent(QMouseEvent *e) { diff --git a/tools/cabana/videowidget.h b/tools/cabana/videowidget.h index 188456ecbe..060565d322 100644 --- a/tools/cabana/videowidget.h +++ b/tools/cabana/videowidget.h @@ -13,6 +13,7 @@ class Slider : public QSlider { public: Slider(QWidget *parent); void mousePressEvent(QMouseEvent* e) override; + void sliderChange(QAbstractSlider::SliderChange change) override; signals: void setPosition(int value); @@ -20,6 +21,8 @@ signals: private: void paintEvent(QPaintEvent *ev) override; std::vector> timeline; + + int slider_x = -1; }; class VideoWidget : public QWidget { From c719b3b7ddd05d8369aab13e11f99af7990c73ea Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 10 Oct 2022 23:24:14 -0700 Subject: [PATCH 006/101] HKG CAN-FD: log temporary steering faults (#26031) * log hkg can-fd temporary steering faults * bump to master --- opendbc | 2 +- selfdrive/car/hyundai/carstate.py | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/opendbc b/opendbc index ae2fd934ce..c35e8139bf 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit ae2fd934ceb8501c56a0802564c14963dbb201ac +Subproject commit c35e8139bf9e9d87b9efb6764ab7e65983e8d33e diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 1f2de3286e..4d60afe1fd 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -180,6 +180,7 @@ class CarState(CarStateBase): ret.steeringTorque = cp.vl["MDPS"]["STEERING_COL_TORQUE"] ret.steeringTorqueEps = cp.vl["MDPS"]["STEERING_OUT_TORQUE"] ret.steeringPressed = abs(ret.steeringTorque) > self.params.STEER_THRESHOLD + ret.steerFaultTemporary = cp.vl["MDPS"]["LKA_FAULT"] != 0 ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(50, cp.vl["BLINKERS"]["LEFT_LAMP"], cp.vl["BLINKERS"]["RIGHT_LAMP"]) @@ -414,6 +415,7 @@ class CarState(CarStateBase): ("STEERING_ANGLE", "STEERING_SENSORS"), ("STEERING_COL_TORQUE", "MDPS"), ("STEERING_OUT_TORQUE", "MDPS"), + ("LKA_FAULT", "MDPS"), ("CRUISE_ACTIVE", "SCC1"), ("COUNTER", cruise_btn_msg), From 478693771bf2570da0b0370c65c6f4113766eaca Mon Sep 17 00:00:00 2001 From: YassineYousfi Date: Tue, 11 Oct 2022 10:27:00 -0700 Subject: [PATCH 007/101] bump tinygrad (#26029) --- tinygrad_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tinygrad_repo b/tinygrad_repo index 46f6db7522..870ea766ee 160000 --- a/tinygrad_repo +++ b/tinygrad_repo @@ -1 +1 @@ -Subproject commit 46f6db75228cb7744a3a0a87616bfffeffa93658 +Subproject commit 870ea766eec7a38d7d590c81436f15271ba2667e From 32a4dfe2fe549edff352dc54055cff680c96755f Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 11 Oct 2022 12:53:35 -0700 Subject: [PATCH 008/101] Add CarInfo for Elantra GT and i30 (#26034) Fixup car info for Elantra GT/i30 --- selfdrive/car/hyundai/values.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index a43f17ac00..68a16b096e 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -110,7 +110,10 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { CAR.ELANTRA: HyundaiCarInfo("Hyundai Elantra 2017-19", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_b), CAR.ELANTRA_2021: HyundaiCarInfo("Hyundai Elantra 2021-22", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k), CAR.ELANTRA_HEV_2021: HyundaiCarInfo("Hyundai Elantra Hybrid 2021-22", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k), - CAR.ELANTRA_GT_I30: None, # dashcamOnly and same platform as CAR.ELANTRA + CAR.ELANTRA_GT_I30: [ + HyundaiCarInfo("Hyundai Elantra GT 2017-19", harness=Harness.hyundai_e), + HyundaiCarInfo("Hyundai i30 2019", harness=Harness.hyundai_e), + ], CAR.HYUNDAI_GENESIS: HyundaiCarInfo("Hyundai Genesis 2015-16", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_j), # TODO: check 2015 packages CAR.IONIQ: HyundaiCarInfo("Hyundai Ioniq Hybrid 2017-19", harness=Harness.hyundai_c), CAR.IONIQ_HEV_2022: HyundaiCarInfo("Hyundai Ioniq Hybrid 2020-22", harness=Harness.hyundai_h), # TODO: confirm 2020-21 harness From e062d2387e37f92121979803e11e9fcbb550b63b Mon Sep 17 00:00:00 2001 From: Nelson Chen Date: Tue, 11 Oct 2022 13:17:21 -0700 Subject: [PATCH 009/101] Add missing Corolla TSS2 firmware (#26032) --- 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 0075a483f6..137db5612b 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -757,6 +757,7 @@ FW_VERSIONS = { b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', b'\x02312K4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02312U5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', From dbdb3a02a8efb637275ef6d65fa0ab08b51d3b05 Mon Sep 17 00:00:00 2001 From: wjxjmj Date: Wed, 12 Oct 2022 05:16:40 +0800 Subject: [PATCH 010/101] Add ip and port arguments to /tools/sim/bridge.py (#26011) * Add ip and port arguments * Add descriptions of ip and port arguments * Update README.md * Update README.md * prefer host/port options Co-authored-by: Cameron Clough --- tools/sim/README.md | 2 ++ tools/sim/bridge.py | 8 +++++--- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/tools/sim/README.md b/tools/sim/README.md index cb1aea35ac..40603f3f71 100644 --- a/tools/sim/README.md +++ b/tools/sim/README.md @@ -39,6 +39,8 @@ Options: --high_quality Set simulator to higher quality (requires good GPU) --town TOWN Select map to drive in --spawn_point NUM Number of the spawn point to start in + --host HOST Host address of Carla client (127.0.0.1 as default) + --port PORT Port of Carla client (2000 as default) ``` To engage openpilot press 1 a few times while focused on bridge.py to increase the cruise speed. diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index e436e92292..a105ed751e 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -39,6 +39,8 @@ def parse_args(add_args=None): parser.add_argument('--dual_camera', action='store_true') parser.add_argument('--town', type=str, default='Town04_Opt') parser.add_argument('--spawn_point', dest='num_selected_spawn_point', type=int, default=16) + parser.add_argument('--host', dest='host', type=str, default='127.0.0.1') + parser.add_argument('--port', dest='port', type=int, default=2000) return parser.parse_args(add_args) @@ -233,8 +235,8 @@ def can_function_runner(vs: VehicleState, exit_event: threading.Event): i += 1 -def connect_carla_client(): - client = carla.Client("127.0.0.1", 2000) +def connect_carla_client(host: str, port: int): + client = carla.Client(host, port) client.set_timeout(5) return client @@ -291,7 +293,7 @@ class CarlaBridge: self.close() def _run(self, q: Queue): - client = connect_carla_client() + client = connect_carla_client(self._args.host, self._args.port) world = client.load_world(self._args.town) settings = world.get_settings() From 2c9b150761f533a6132fac3639df24bb286386bb Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Tue, 11 Oct 2022 14:53:43 -0700 Subject: [PATCH 011/101] Low speed lateral like before (#26022) * Add explicit cost on steering wheel movement * Laxer low speed control * Laxer low speed control * Lower min speed now there is a cost * 3m/s * Similar to old master * Add cost * Crazy high * Update ref * comment --- selfdrive/controls/lib/latcontrol_torque.py | 14 ++++++---- .../controls/lib/lateral_mpc_lib/lat_mpc.py | 28 +++++++++++++------ selfdrive/controls/lib/lateral_planner.py | 10 +++++-- selfdrive/controls/tests/test_lateral_mpc.py | 6 ++-- selfdrive/test/process_replay/ref_commit | 2 +- 5 files changed, 41 insertions(+), 19 deletions(-) diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index fa1bb480f1..7d656b55a9 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -17,6 +17,8 @@ from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY # friction in the steering wheel that needs to be overcome to # move it at all, this is compensated for too. +LOW_SPEED_FACTOR = 100 + class LatControlTorque(LatControl): def __init__(self, CP, CI): @@ -55,13 +57,15 @@ class LatControlTorque(LatControl): actual_lateral_accel = actual_curvature * CS.vEgo ** 2 lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2 - 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 + setpoint = desired_lateral_accel + LOW_SPEED_FACTOR * desired_curvature + measurement = actual_lateral_accel + LOW_SPEED_FACTOR * actual_curvature error = setpoint - measurement gravity_adjusted_lateral_accel = desired_lateral_accel - params.roll * ACCELERATION_DUE_TO_GRAVITY - pid_log.error = self.torque_from_lateral_accel(error, self.torque_params, error, lateral_accel_deadzone, friction_compensation=False) - ff = self.torque_from_lateral_accel(gravity_adjusted_lateral_accel, self.torque_params, error, lateral_accel_deadzone, friction_compensation=True) + pid_log.error = self.torque_from_lateral_accel(error, self.torque_params, error, + lateral_accel_deadzone, friction_compensation=False) + ff = self.torque_from_lateral_accel(gravity_adjusted_lateral_accel, self.torque_params, + desired_lateral_accel - actual_lateral_accel, + lateral_accel_deadzone, friction_compensation=True) freeze_integrator = steer_limited or CS.steeringPressed or CS.vEgo < 5 output_torque = self.pid.update(pid_log.error, diff --git a/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py b/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py index 0cbd576341..9607532ace 100755 --- a/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py +++ b/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py @@ -19,7 +19,7 @@ X_DIM = 4 P_DIM = 2 N = 16 COST_E_DIM = 3 -COST_DIM = COST_E_DIM + 1 +COST_DIM = COST_E_DIM + 2 SPEED_OFFSET = 10.0 MODEL_NAME = 'lat' ACADOS_SOLVER_TYPE = 'SQP_RTI' @@ -89,13 +89,21 @@ def gen_lat_ocp(): ocp.cost.yref = np.zeros((COST_DIM, )) ocp.cost.yref_e = np.zeros((COST_E_DIM, )) + # Add offset to smooth out low speed control + # TODO unclear if this right solution long term + v_ego_offset = v_ego + SPEED_OFFSET + # TODO there are two costs on psi_rate_ego_dot, one + # is correlated to jerk the other to steering wheel movement + # the steering wheel movement cost is added to prevent excessive + # wheel movements ocp.model.cost_y_expr = vertcat(y_ego, - ((v_ego + SPEED_OFFSET) * psi_ego), - ((v_ego + SPEED_OFFSET) * psi_rate_ego), - ((v_ego + SPEED_OFFSET) * psi_rate_ego_dot)) + v_ego_offset * psi_ego, + v_ego_offset * psi_rate_ego, + v_ego_offset * psi_rate_ego_dot, + psi_rate_ego_dot / (v_ego + 0.1)) ocp.model.cost_y_expr_e = vertcat(y_ego, - ((v_ego + SPEED_OFFSET) * psi_ego), - ((v_ego + SPEED_OFFSET) * psi_rate_ego)) + v_ego_offset * psi_ego, + v_ego_offset * psi_rate_ego) # set constraints ocp.constraints.constr_type = 'BGH' @@ -144,8 +152,12 @@ class LateralMpc(): self.solve_time = 0.0 self.cost = 0 - def set_weights(self, path_weight, heading_weight, yaw_rate_weight, yaw_accel_cost): - W = np.asfortranarray(np.diag([path_weight, heading_weight, yaw_rate_weight, yaw_accel_cost])) + def set_weights(self, path_weight, heading_weight, + lat_accel_weight, lat_jerk_weight, + steering_rate_weight): + W = np.asfortranarray(np.diag([path_weight, heading_weight, + lat_accel_weight, lat_jerk_weight, + steering_rate_weight])) for i in range(N): self.solver.cost_set(i, 'W', W) self.solver.cost_set(N, 'W', W[:COST_E_DIM,:COST_E_DIM]) diff --git a/selfdrive/controls/lib/lateral_planner.py b/selfdrive/controls/lib/lateral_planner.py index d4c832b53b..9fbfd4a11f 100644 --- a/selfdrive/controls/lib/lateral_planner.py +++ b/selfdrive/controls/lib/lateral_planner.py @@ -17,8 +17,13 @@ PATH_COST = 1.0 LATERAL_MOTION_COST = 0.11 LATERAL_ACCEL_COST = 0.0 LATERAL_JERK_COST = 0.05 +# Extreme steering rate is unpleasant, even +# when it does not cause bad jerk. +# TODO this cost should be lowered when low +# speed lateral control is stable on all cars +STEERING_RATE_COST = 800.0 -MIN_SPEED = 1.5 +MIN_SPEED = .3 class LateralPlanner: @@ -67,7 +72,8 @@ class LateralPlanner: d_path_xyz = self.path_xyz self.lat_mpc.set_weights(PATH_COST, LATERAL_MOTION_COST, - LATERAL_ACCEL_COST, LATERAL_JERK_COST) + LATERAL_ACCEL_COST, LATERAL_JERK_COST, + STEERING_RATE_COST) y_pts = np.interp(self.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(self.v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw) diff --git a/selfdrive/controls/tests/test_lateral_mpc.py b/selfdrive/controls/tests/test_lateral_mpc.py index 9b986c053d..df5154b2b4 100644 --- a/selfdrive/controls/tests/test_lateral_mpc.py +++ b/selfdrive/controls/tests/test_lateral_mpc.py @@ -10,7 +10,7 @@ def run_mpc(lat_mpc=None, v_ref=30., x_init=0., y_init=0., psi_init=0., curvatur if lat_mpc is None: lat_mpc = LateralMpc() - lat_mpc.set_weights(1., 1., 0.0, 1.) + lat_mpc.set_weights(1., .1, 0.0, .05, 800) y_pts = poly_shift * np.ones(LAT_MPC_N + 1) heading_pts = np.zeros(LAT_MPC_N + 1) @@ -77,9 +77,9 @@ class TestLateralMpc(unittest.TestCase): def test_switch_convergence(self): lat_mpc = LateralMpc() - sol = run_mpc(lat_mpc=lat_mpc, poly_shift=30.0, v_ref=7.0) + sol = run_mpc(lat_mpc=lat_mpc, poly_shift=3.0, v_ref=7.0) right_psi_deg = np.degrees(sol[:,2]) - sol = run_mpc(lat_mpc=lat_mpc, poly_shift=-30.0, v_ref=7.0) + sol = run_mpc(lat_mpc=lat_mpc, poly_shift=-3.0, v_ref=7.0) left_psi_deg = np.degrees(sol[:,2]) np.testing.assert_almost_equal(right_psi_deg, -left_psi_deg, decimal=3) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index a4a24ca603..0d806ae5f1 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -f636c68e2b4ed88d3731930cf15b6dee984eb6dd +0f0a9aa8fed425468c488a4f8b7581c48d724e67 From 741867813285672a723b8fc53ead65a5cbe5c6dd Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 11 Oct 2022 16:27:46 -0700 Subject: [PATCH 012/101] Use longActive for car-specific override signals (#26030) * add override field to cruiseControl * need to check if long *can* be active * bump cereal to master * revert * better * fix * update refs * rename variable --- cereal | 2 +- selfdrive/car/hyundai/carcontroller.py | 2 +- selfdrive/car/hyundai/hyundaican.py | 6 +++--- selfdrive/controls/controlsd.py | 1 + selfdrive/test/process_replay/ref_commit | 2 +- 5 files changed, 7 insertions(+), 6 deletions(-) diff --git a/cereal b/cereal index b29717c4c3..b1003dd012 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit b29717c4c328d5cf34d46f682f25267150f82637 +Subproject commit b1003dd0128a451439d4fe98d098d90e994f81ed diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 6f7cc319e4..4a1f7bcb51 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -133,7 +133,7 @@ class CarController: stopping = actuators.longControlState == LongCtrlState.stopping set_speed_in_units = hud_control.setSpeed * (CV.MS_TO_MPH if CS.clu11["CF_Clu_SPEED_UNIT"] == 1 else CV.MS_TO_KPH) can_sends.extend(hyundaican.create_acc_commands(self.packer, CC.enabled, accel, jerk, int(self.frame / 2), - hud_control.leadVisible, set_speed_in_units, stopping, CS.out.gasPressed)) + hud_control.leadVisible, set_speed_in_units, stopping, CC.cruiseControl.override)) self.accel = accel # 20 Hz LFA MFA message diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py index 7f3f6a72c5..f4fe8f1126 100644 --- a/selfdrive/car/hyundai/hyundaican.py +++ b/selfdrive/car/hyundai/hyundaican.py @@ -94,7 +94,7 @@ def create_lfahda_mfc(packer, enabled, hda_set_speed=0): } return packer.make_can_msg("LFAHDA_MFC", 0, values) -def create_acc_commands(packer, enabled, accel, upper_jerk, idx, lead_visible, set_speed, stopping, gas_pressed): +def create_acc_commands(packer, enabled, accel, upper_jerk, idx, lead_visible, set_speed, stopping, long_override): commands = [] scc11_values = { @@ -111,7 +111,7 @@ def create_acc_commands(packer, enabled, accel, upper_jerk, idx, lead_visible, s commands.append(packer.make_can_msg("SCC11", 0, scc11_values)) scc12_values = { - "ACCMode": 2 if enabled and gas_pressed else 1 if enabled else 0, + "ACCMode": 2 if enabled and long_override else 1 if enabled else 0, "StopReq": 1 if stopping else 0, "aReqRaw": accel, "aReqValue": accel, # stock ramps up and down respecting jerk limit until it reaches aReqRaw @@ -127,7 +127,7 @@ def create_acc_commands(packer, enabled, accel, upper_jerk, idx, lead_visible, s "ComfortBandLower": 0.0, # stock usually is 0 but sometimes uses higher values "JerkUpperLimit": upper_jerk, # stock usually is 1.0 but sometimes uses higher values "JerkLowerLimit": 5.0, # stock usually is 0.5 but sometimes uses higher values - "ACCMode": 2 if enabled and gas_pressed else 1 if enabled else 4, # stock will always be 4 instead of 0 after first disengage + "ACCMode": 2 if enabled and long_override else 1 if enabled else 4, # stock will always be 4 instead of 0 after first disengage "ObjGap": 2 if lead_visible else 0, # 5: >30, m, 4: 25-30 m, 3: 20-25 m, 2: < 20 m, 0: no lead } commands.append(packer.make_can_msg("SCC14", 0, scc14_values)) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 6ce1156baf..8abb1a02a6 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -705,6 +705,7 @@ class Controls: if len(angular_rate_value) > 2: CC.angularVelocity = angular_rate_value + CC.cruiseControl.override = self.enabled and not CC.longActive and self.CP.openpilotLongitudinalControl CC.cruiseControl.cancel = CS.cruiseState.enabled and (not self.enabled or not self.CP.pcmCruise) if self.joystick_mode and self.sm.rcv_frame['testJoystick'] > 0 and self.sm['testJoystick'].buttons[0]: CC.cruiseControl.cancel = True diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 0d806ae5f1..db3684fb0b 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -0f0a9aa8fed425468c488a4f8b7581c48d724e67 +02c6922762fef41c8188a5a4f1f3267b76651330 \ No newline at end of file From 182c5c48102a8d719402eece658c16f36f3d7046 Mon Sep 17 00:00:00 2001 From: Kurt Nistelberger Date: Tue, 11 Oct 2022 17:41:20 -0700 Subject: [PATCH 013/101] add extra logging for rawgpsd opcode crash --- selfdrive/sensord/rawgps/rawgpsd.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/sensord/rawgps/rawgpsd.py b/selfdrive/sensord/rawgps/rawgpsd.py index c68e7aff99..95f8dab1c2 100755 --- a/selfdrive/sensord/rawgps/rawgpsd.py +++ b/selfdrive/sensord/rawgps/rawgpsd.py @@ -179,6 +179,8 @@ def main() -> NoReturn: while 1: opcode, payload = diag.recv() + if opcode != DIAG_LOG_F: + cloudlog.exception(f"Unhandled opcode: {opcode}") assert opcode == DIAG_LOG_F (pending_msgs, log_outer_length), inner_log_packet = unpack_from(' Date: Tue, 11 Oct 2022 18:55:10 -0700 Subject: [PATCH 014/101] GPS test station first unittests (#25950) * init gps test * gps test v1 * add static signal gen script * update readme * remove LD_PRELOAD by using rpath, update values after testing * remove LD_PRELOAD * update fuzzy testing * address comments * cleanup Co-authored-by: Kurt Nistelberger --- selfdrive/sensord/pigeond.py | 99 +++++++++--- tools/gpstest/.gitignore | 2 +- tools/gpstest/README.md | 14 +- tools/gpstest/fuzzy_testing.py | 142 ++++++++++++++++++ tools/gpstest/gpstest.sh | 8 - .../limeGPS/inc_ephem_array_size.patch | 13 ++ tools/gpstest/patches/limeGPS/makefile.patch | 11 ++ .../gpstest/patches/limeSuite/mcu_error.patch | 13 ++ .../patches/limeSuite/reference_print.patch | 13 ++ tools/gpstest/remote_checker.py | 48 ++++++ tools/gpstest/run_static_gps_signal.py | 83 ++++++++++ tools/gpstest/setup.sh | 6 +- tools/gpstest/test_gps.py | 140 +++++++++++++++++ 13 files changed, 547 insertions(+), 45 deletions(-) create mode 100755 tools/gpstest/fuzzy_testing.py delete mode 100755 tools/gpstest/gpstest.sh create mode 100644 tools/gpstest/patches/limeGPS/inc_ephem_array_size.patch create mode 100644 tools/gpstest/patches/limeGPS/makefile.patch create mode 100644 tools/gpstest/patches/limeSuite/mcu_error.patch create mode 100644 tools/gpstest/patches/limeSuite/reference_print.patch create mode 100644 tools/gpstest/remote_checker.py create mode 100755 tools/gpstest/run_static_gps_signal.py create mode 100644 tools/gpstest/test_gps.py diff --git a/selfdrive/sensord/pigeond.py b/selfdrive/sensord/pigeond.py index 5fe120c061..f56af1c705 100755 --- a/selfdrive/sensord/pigeond.py +++ b/selfdrive/sensord/pigeond.py @@ -7,7 +7,7 @@ import struct import requests import urllib.parse from datetime import datetime -from typing import List, Optional +from typing import List, Optional, Tuple from cereal import messaging from common.params import Params @@ -34,7 +34,6 @@ def set_power(enabled: bool) -> None: gpio_set(GPIO.UBLOX_PWR_EN, enabled) gpio_set(GPIO.UBLOX_RST_N, enabled) - def add_ubx_checksum(msg: bytes) -> bytes: A = B = 0 for b in msg[2:]: @@ -115,35 +114,70 @@ class TTYPigeon(): raise TimeoutError('No response from ublox') time.sleep(0.001) + def reset_device(self) -> bool: + # deleting the backup does not always work on first try (mostly on second try) + for _ in range(5): + # device cold start + self.send(b"\xb5\x62\x06\x04\x04\x00\xff\xff\x00\x00\x0c\x5d") + time.sleep(1) # wait for cold start + init_baudrate(self) + + # clear configuration + self.send_with_ack(b"\xb5\x62\x06\x09\x0d\x00\x00\x00\x1f\x1f\x00\x00\x00\x00\x00\x00\x00\x00\x17\x71\x5b") + + # clear flash memory (almanac backup) + self.send_with_ack(b"\xB5\x62\x09\x14\x04\x00\x01\x00\x00\x00\x22\xf0") + + # try restoring backup to verify it got deleted + self.send(b"\xB5\x62\x09\x14\x00\x00\x1D\x60") + # 1: failed to restore, 2: could restore, 3: no backup + status = self.wait_for_backup_restore_status() + if status == 1 or status == 3: + return True + return False + +def init_baudrate(pigeon: TTYPigeon): + # ublox default setting on startup is 9600 baudrate + pigeon.set_baud(9600) + + # $PUBX,41,1,0007,0003,460800,0*15\r\n + pigeon.send(b"\x24\x50\x55\x42\x58\x2C\x34\x31\x2C\x31\x2C\x30\x30\x30\x37\x2C\x30\x30\x30\x33\x2C\x34\x36\x30\x38\x30\x30\x2C\x30\x2A\x31\x35\x0D\x0A") + time.sleep(0.1) + pigeon.set_baud(460800) + def initialize_pigeon(pigeon: TTYPigeon) -> bool: # try initializing a few times for _ in range(10): try: - pigeon.set_baud(9600) - - # up baud rate - pigeon.send(b"\x24\x50\x55\x42\x58\x2C\x34\x31\x2C\x31\x2C\x30\x30\x30\x37\x2C\x30\x30\x30\x33\x2C\x34\x36\x30\x38\x30\x30\x2C\x30\x2A\x31\x35\x0D\x0A") - time.sleep(0.1) - pigeon.set_baud(460800) - - # other configuration messages - pigeon.send_with_ack(b"\xB5\x62\x06\x00\x14\x00\x03\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x01\x00\x01\x00\x00\x00\x00\x00\x1E\x7F") - pigeon.send_with_ack(b"\xB5\x62\x06\x00\x14\x00\x00\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x19\x35") - pigeon.send_with_ack(b"\xB5\x62\x06\x00\x14\x00\x01\x00\x00\x00\xC0\x08\x00\x00\x00\x08\x07\x00\x01\x00\x01\x00\x00\x00\x00\x00\xF4\x80") - pigeon.send_with_ack(b"\xB5\x62\x06\x00\x14\x00\x04\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x1D\x85") - pigeon.send_with_ack(b"\xB5\x62\x06\x00\x00\x00\x06\x18") - pigeon.send_with_ack(b"\xB5\x62\x06\x00\x01\x00\x01\x08\x22") - pigeon.send_with_ack(b"\xB5\x62\x06\x00\x01\x00\x03\x0A\x24") + + # setup port config + pigeon.send_with_ack(b"\xb5\x62\x06\x00\x14\x00\x03\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x01\x00\x01\x00\x00\x00\x00\x00\x1E\x7F") + pigeon.send_with_ack(b"\xb5\x62\x06\x00\x14\x00\x00\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x19\x35") + pigeon.send_with_ack(b"\xb5\x62\x06\x00\x14\x00\x01\x00\x00\x00\xC0\x08\x00\x00\x00\x08\x07\x00\x01\x00\x01\x00\x00\x00\x00\x00\xF4\x80") + pigeon.send_with_ack(b"\xb5\x62\x06\x00\x14\x00\x04\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x1D\x85") + pigeon.send_with_ack(b"\xb5\x62\x06\x00\x00\x00\x06\x18") + pigeon.send_with_ack(b"\xb5\x62\x06\x00\x01\x00\x01\x08\x22") + pigeon.send_with_ack(b"\xb5\x62\x06\x00\x01\x00\x03\x0A\x24") + + # UBX-CFG-RATE (0x06 0x08) pigeon.send_with_ack(b"\xB5\x62\x06\x08\x06\x00\x64\x00\x01\x00\x00\x00\x79\x10") + + # UBX-CFG-NAV5 (0x06 0x24) pigeon.send_with_ack(b"\xB5\x62\x06\x24\x24\x00\x05\x00\x04\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x5A\x63") + + # UBX-CFG-ODO (0x06 0x1E) pigeon.send_with_ack(b"\xB5\x62\x06\x1E\x14\x00\x00\x00\x00\x00\x01\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x3C\x37") pigeon.send_with_ack(b"\xB5\x62\x06\x39\x08\x00\xFF\xAD\x62\xAD\x1E\x63\x00\x00\x83\x0C") pigeon.send_with_ack(b"\xB5\x62\x06\x23\x28\x00\x00\x00\x00\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x01\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x56\x24") + + # UBX-CFG-NAV5 (0x06 0x24) pigeon.send_with_ack(b"\xB5\x62\x06\x24\x00\x00\x2A\x84") pigeon.send_with_ack(b"\xB5\x62\x06\x23\x00\x00\x29\x81") pigeon.send_with_ack(b"\xB5\x62\x06\x1E\x00\x00\x24\x72") pigeon.send_with_ack(b"\xB5\x62\x06\x39\x00\x00\x3F\xC3") + + # UBX-CFG-MSG (set message rate) pigeon.send_with_ack(b"\xB5\x62\x06\x01\x03\x00\x01\x07\x01\x13\x51") pigeon.send_with_ack(b"\xB5\x62\x06\x01\x03\x00\x02\x15\x01\x22\x70") pigeon.send_with_ack(b"\xB5\x62\x06\x01\x03\x00\x02\x13\x01\x20\x6C") @@ -224,13 +258,11 @@ def deinitialize_and_exit(pigeon: Optional[TTYPigeon]): set_power(False) sys.exit(0) -def main(): - assert TICI, "unsupported hardware for pigeond" +def create_pigeon() -> Tuple[TTYPigeon, messaging.PubMaster]: + pigeon = None # register exit handler - pigeon = None signal.signal(signal.SIGINT, lambda sig, frame: deinitialize_and_exit(pigeon)) - pm = messaging.PubMaster(['ubloxRaw']) # power cycle ublox @@ -240,15 +272,20 @@ def main(): time.sleep(0.5) pigeon = TTYPigeon() - r = initialize_pigeon(pigeon) - Params().put_bool("UbloxAvailable", r) + return pigeon, pm - # start receiving data - while True: +def run_receiving(pigeon: TTYPigeon, pm: messaging.PubMaster, duration: int = 0): + + start_time = time.monotonic() + def end_condition(): + return True if duration == 0 else time.monotonic() - start_time < duration + + while end_condition(): dat = pigeon.receive() if len(dat) > 0: if dat[0] == 0x00: cloudlog.warning("received invalid data from ublox, re-initing!") + init_baudrate(pigeon) initialize_pigeon(pigeon) continue @@ -260,5 +297,17 @@ def main(): # prevent locking up a CPU core if ublox disconnects time.sleep(0.001) + +def main(): + assert TICI, "unsupported hardware for pigeond" + + pigeon, pm = create_pigeon() + init_baudrate(pigeon) + r = initialize_pigeon(pigeon) + Params().put_bool("UbloxAvailable", r) + + # start receiving data + run_receiving(pigeon, pm) + if __name__ == "__main__": main() diff --git a/tools/gpstest/.gitignore b/tools/gpstest/.gitignore index b33aaa403c..f11597286e 100644 --- a/tools/gpstest/.gitignore +++ b/tools/gpstest/.gitignore @@ -1,2 +1,2 @@ LimeGPS/ -LimeSuite/ +LimeSuite/ \ No newline at end of file diff --git a/tools/gpstest/README.md b/tools/gpstest/README.md index 4125bf00af..5aff0ee3d7 100644 --- a/tools/gpstest/README.md +++ b/tools/gpstest/README.md @@ -1,20 +1,18 @@ # GPS test setup +Testing the GPS receiver using GPS spoofing. At the moment only +static location relpay is supported. # Usage ``` -# replaying a static location -./gpstest.sh -e -s - -# replaying a prerecorded route (NMEA cvs file) -./gpstest.sh -e -d +# on host, start gps signal simulation +./run_static_lime.py ``` -If `-e` is not provided the latest ephemeris file will be downloaded from +`run_static_lime.py` downloads the latest ephemeris file from https://cddis.nasa.gov/archive/gnss/data/daily/20xx/brdc/. -(TODO: add auto downloader) -# Hardware Setup +# Hardware Setup * [LimeSDR USB](https://wiki.myriadrf.org/LimeSDR-USB) * Asus AX58BT antenna diff --git a/tools/gpstest/fuzzy_testing.py b/tools/gpstest/fuzzy_testing.py new file mode 100755 index 0000000000..216e7d0dde --- /dev/null +++ b/tools/gpstest/fuzzy_testing.py @@ -0,0 +1,142 @@ +#!/usr/bin/env python3 +import sys +import time +import random +import datetime as dt +import subprocess as sp +import multiprocessing +import threading +from typing import Tuple, Any + +from laika.downloader import download_nav +from laika.gps_time import GPSTime +from laika.helpers import ConstellationId + +cache_dir = '/tmp/gpstest/' + + +def download_rinex(): + # TODO: check if there is a better way to get the full brdc file for LimeGPS + gps_time = GPSTime.from_datetime(dt.datetime.utcnow()) + utc_time = dt.datetime.utcnow() - dt.timedelta(1) + gps_time = GPSTime.from_datetime(dt.datetime(utc_time.year, utc_time.month, utc_time.day)) + return download_nav(gps_time, cache_dir, ConstellationId.GPS) + + +def exec_LimeGPS_bin(rinex_file: str, location: str, duration: int): + # this functions should never return, cause return means, timeout is + # reached or it crashed + try: + cmd = ["LimeGPS/LimeGPS", "-e", rinex_file, "-l", location] + sp.check_output(cmd, timeout=duration) + except sp.TimeoutExpired: + print("LimeGPS timeout reached!") + except Exception as e: + print(f"LimeGPS crashed: {str(e)}") + + +def run_lime_gps(rinex_file: str, location: str, duration: int): + print(f"LimeGPS {location} {duration}") + + p = multiprocessing.Process(target=exec_LimeGPS_bin, + args=(rinex_file, location, duration)) + p.start() + return p + + +def get_random_coords(lat, lon) -> Tuple[int, int]: + # jump around the world + # max values, lat: -90 to 90, lon: -180 to 180 + + lat_add = random.random()*20 + 10 + lon_add = random.random()*20 + 20 + + lat = ((lat + lat_add + 90) % 180) - 90 + lon = ((lon + lon_add + 180) % 360) - 180 + return round(lat, 5), round(lon, 5) + +def get_continuous_coords(lat, lon) -> Tuple[int, int]: + # continuously move around the world + + lat_add = random.random()*0.01 + lon_add = random.random()*0.01 + + lat = ((lat + lat_add + 90) % 180) - 90 + lon = ((lon + lon_add + 180) % 360) - 180 + return round(lat, 5), round(lon, 5) + +rc_p: Any = None +def exec_remote_checker(lat, lon, duration): + global rc_p + # TODO: good enough for testing + remote_cmd = "export PYTHONPATH=/data/pythonpath:/data/pythonpath/pyextra && " + remote_cmd += "cd /data/openpilot && " + remote_cmd += f"timeout {duration} /usr/local/pyenv/shims/python tools/gpstest/remote_checker.py " + remote_cmd += f"{lat} {lon}" + + ssh_cmd = ['ssh', '-i', '/home/batman/openpilot/xx/phone/key/id_rsa', + 'comma@192.168.60.130'] + ssh_cmd += [remote_cmd] + + rc_p = sp.Popen(ssh_cmd, stdout=sp.PIPE) + rc_p.wait() + rc_output = rc_p.stdout.read() + print(f"Checker Result: {rc_output.strip().decode('utf-8')}") + + +def run_remote_checker(spoof_proc, lat, lon, duration) -> bool: + checker_thread = threading.Thread(target=exec_remote_checker, args=(lat, lon, duration)) + checker_thread.start() + + tcnt = 0 + while True: + if not checker_thread.is_alive(): + # assume this only happens when the signal got matched + return True + + # the spoofing process has a timeout, kill checker if reached + if not spoof_proc.is_alive(): + rc_p.kill() + # spoofing process died, assume timeout + print("Spoofing process timeout") + return False + + print(f"Time elapsed: {tcnt}[s]", end = "\r") + time.sleep(1) + tcnt += 1 + + +def main(): + continuous_mode = False + if len(sys.argv) == 2 and sys.argv[1] == '-c': + print("Continuous Mode!") + continuous_mode = True + + rinex_file = download_rinex() + + duration = 60*3 # max runtime in seconds + lat, lon = get_random_coords(47.2020, 15.7403) + + while True: + # spoof random location + spoof_proc = run_lime_gps(rinex_file, f"{lat},{lon},100", duration) + start_time = time.monotonic() + + # remote checker runs blocking + if not run_remote_checker(spoof_proc, lat, lon, duration): + # location could not be matched by ublox module + pass + + end_time = time.monotonic() + spoof_proc.terminate() + + # -1 to count process startup + print(f"Time to get Signal: {round(end_time - start_time - 1, 4)}") + + if continuous_mode: + lat, lon = get_continuous_coords(lat, lon) + else: + lat, lon = get_random_coords(lat, lon) + +if __name__ == "__main__": + main() diff --git a/tools/gpstest/gpstest.sh b/tools/gpstest/gpstest.sh deleted file mode 100755 index dfb71fe563..0000000000 --- a/tools/gpstest/gpstest.sh +++ /dev/null @@ -1,8 +0,0 @@ -#!/bin/bash - -LimeGPS_BIN=LimeGPS/LimeGPS -if test -f "$LimeGPS_BIN"; then - LD_PRELOAD=LimeSuite/builddir/src/libLimeSuite.so $LimeGPS_BIN $@ -else - echo "LimeGPS binary not found, run 'setup.sh' first" -fi diff --git a/tools/gpstest/patches/limeGPS/inc_ephem_array_size.patch b/tools/gpstest/patches/limeGPS/inc_ephem_array_size.patch new file mode 100644 index 0000000000..9a3525d346 --- /dev/null +++ b/tools/gpstest/patches/limeGPS/inc_ephem_array_size.patch @@ -0,0 +1,13 @@ +diff --git a/gpssim.h b/gpssim.h +index c30b227..2ae0802 100644 +--- a/gpssim.h ++++ b/gpssim.h +@@ -75,7 +75,7 @@ + #define SC08 (8) + #define SC16 (16) + +-#define EPHEM_ARRAY_SIZE (13) // for daily GPS broadcast ephemers file (brdc) ++#define EPHEM_ARRAY_SIZE (20) // for daily GPS broadcast ephemers file (brdc) + + /*! \brief Structure representing GPS time */ + typedef struct diff --git a/tools/gpstest/patches/limeGPS/makefile.patch b/tools/gpstest/patches/limeGPS/makefile.patch new file mode 100644 index 0000000000..f99ce551db --- /dev/null +++ b/tools/gpstest/patches/limeGPS/makefile.patch @@ -0,0 +1,11 @@ +diff --git a/makefile b/makefile +index 51bfabf..d0ea1eb 100644 +--- a/makefile ++++ b/makefile +@@ -1,5 +1,4 @@ + CC=gcc -O2 -Wall + + all: limegps.c gpssim.c +- $(CC) -o LimeGPS limegps.c gpssim.c -lm -lpthread -lLimeSuite +- ++ $(CC) -o LimeGPS limegps.c gpssim.c -lm -lpthread -lLimeSuite -I../LimeSuite/src -L../LimeSuite/builddir/src -Wl,-rpath="$(PWD)/../LimeSuite/builddir/src" diff --git a/tools/gpstest/patches/limeSuite/mcu_error.patch b/tools/gpstest/patches/limeSuite/mcu_error.patch new file mode 100644 index 0000000000..91790a4a2b --- /dev/null +++ b/tools/gpstest/patches/limeSuite/mcu_error.patch @@ -0,0 +1,13 @@ +diff --git a/src/lms7002m/LMS7002M_RxTxCalibrations.cpp b/src/lms7002m/LMS7002M_RxTxCalibrations.cpp +index 41a37044..ac29c6b6 100644 +--- a/src/lms7002m/LMS7002M_RxTxCalibrations.cpp ++++ b/src/lms7002m/LMS7002M_RxTxCalibrations.cpp +@@ -254,7 +254,7 @@ int LMS7002M::CalibrateTx(float_type bandwidth_Hz, bool useExtLoopback) + mcuControl->RunProcedure(useExtLoopback ? MCU_FUNCTION_CALIBRATE_TX_EXTLOOPB : MCU_FUNCTION_CALIBRATE_TX); + status = mcuControl->WaitForMCU(1000); + if(status != MCU_BD::MCU_NO_ERROR) +- return ReportError(EINVAL, "Tx Calibration: MCU error %i (%s)", status, MCU_BD::MCUStatusMessage(status)); ++ return -1; //ReportError(EINVAL, "Tx Calibration: MCU error %i (%s)", status, MCU_BD::MCUStatusMessage(status)); + } + + //sync registers to cache diff --git a/tools/gpstest/patches/limeSuite/reference_print.patch b/tools/gpstest/patches/limeSuite/reference_print.patch new file mode 100644 index 0000000000..5bd7cdf1ed --- /dev/null +++ b/tools/gpstest/patches/limeSuite/reference_print.patch @@ -0,0 +1,13 @@ +diff --git a/src/FPGA_common/FPGA_common.cpp b/src/FPGA_common/FPGA_common.cpp +index 4e81f33e..7381c475 100644 +--- a/src/FPGA_common/FPGA_common.cpp ++++ b/src/FPGA_common/FPGA_common.cpp +@@ -946,7 +946,7 @@ double FPGA::DetectRefClk(double fx3Clk) + + if (i == 0) + return -1; +- lime::info("Reference clock %1.2f MHz", clkTbl[i - 1] / 1e6); ++ //lime::info("Reference clock %1.2f MHz", clkTbl[i - 1] / 1e6); + return clkTbl[i - 1]; + } + diff --git a/tools/gpstest/remote_checker.py b/tools/gpstest/remote_checker.py new file mode 100644 index 0000000000..84f6c0c3d9 --- /dev/null +++ b/tools/gpstest/remote_checker.py @@ -0,0 +1,48 @@ +#!/usr/bin/env python3 +import sys +import time +from typing import List + +import cereal.messaging as messaging +from selfdrive.manager.process_config import managed_processes + +DELTA = 0.001 +# assume running openpilot for now +procs: List[str] = []#"ubloxd", "pigeond"] + + +def main(): + if len(sys.argv) < 3: + print("args: ") + return + + sol_lat = float(sys.argv[1]) + sol_lon = float(sys.argv[2]) + + for p in procs: + managed_processes[p].start() + time.sleep(0.5) # give time to startup + + gps_sock = messaging.sub_sock('gpsLocationExternal', timeout=0.1) + + # analyze until the location changed + while True: + events = messaging.drain_sock(gps_sock) + for e in events: + lat = e.gpsLocationExternal.latitude + lon = e.gpsLocationExternal.longitude + + if abs(lat - sol_lat) < DELTA and abs(lon - sol_lon) < DELTA: + print("MATCH") + return + + for p in procs: + if not managed_processes[p].proc.is_alive(): + print(f"ERROR: '{p}' died") + return + + +if __name__ == "__main__": + main() + for p in procs: + managed_processes[p].stop() diff --git a/tools/gpstest/run_static_gps_signal.py b/tools/gpstest/run_static_gps_signal.py new file mode 100755 index 0000000000..3787038f13 --- /dev/null +++ b/tools/gpstest/run_static_gps_signal.py @@ -0,0 +1,83 @@ +#!/usr/bin/env python3 +import os +import sys +import random +import datetime as dt +import subprocess as sp +from typing import Tuple + +from laika.downloader import download_nav +from laika.gps_time import GPSTime +from laika.helpers import ConstellationId + +cache_dir = '/tmp/gpstest/' + + +def download_rinex(): + # TODO: check if there is a better way to get the full brdc file for LimeGPS + gps_time = GPSTime.from_datetime(dt.datetime.utcnow()) + utc_time = dt.datetime.utcnow() - dt.timedelta(1) + gps_time = GPSTime.from_datetime(dt.datetime(utc_time.year, utc_time.month, utc_time.day)) + return download_nav(gps_time, cache_dir, ConstellationId.GPS) + + +def get_random_coords(lat, lon) -> Tuple[int, int]: + # jump around the world + # max values, lat: -90 to 90, lon: -180 to 180 + + lat_add = random.random()*20 + 10 + lon_add = random.random()*20 + 20 + + lat = ((lat + lat_add + 90) % 180) - 90 + lon = ((lon + lon_add + 180) % 360) - 180 + return round(lat, 5), round(lon, 5) + + +def check_availability() -> bool: + cmd = ["LimeSuite/builddir/LimeUtil/LimeUtil", "--find"] + output = sp.check_output(cmd) + + if output.strip() == b"": + return False + + print(f"Device: {output.strip().decode('utf-8')}") + return True + + +def main(): + if not os.path.exists('LimeGPS'): + print("LimeGPS not found run 'setup.sh' first") + return + + if not os.path.exists('LimeSuite'): + print("LimeSuite not found run 'setup.sh' first") + return + + if not check_availability(): + print("No limeSDR device found!") + return + + rinex_file = download_rinex() + lat, lon = get_random_coords(47.2020, 15.7403) + + if len(sys.argv) == 3: + lat = float(sys.argv[1]) + lon = float(sys.argv[2]) + + try: + print(f"starting LimeGPS, Location: {lat},{lon}") + cmd = ["LimeGPS/LimeGPS", "-e", rinex_file, "-l", f"{lat},{lon},100"] + sp.check_output(cmd, stderr=sp.PIPE) + except KeyboardInterrupt: + print("stopping LimeGPS") + except Exception as e: + out_stderr = e.stderr.decode('utf-8')# pylint:disable=no-member + if "Device is busy." in out_stderr: + print("GPS simulation is already running, Device is busy!") + return + + print(f"LimeGPS crashed: {str(e)}") + print(f"stderr:\n{e.stderr.decode('utf-8')}")# pylint:disable=no-member + +if __name__ == "__main__": + main() diff --git a/tools/gpstest/setup.sh b/tools/gpstest/setup.sh index c893f6aba8..ddf41dd260 100755 --- a/tools/gpstest/setup.sh +++ b/tools/gpstest/setup.sh @@ -9,8 +9,9 @@ if [ ! -d LimeSuite ]; then cd LimeSuite # checkout latest version which has firmware updates available git checkout v20.10.0 + git apply ../patches/limeSuite/* mkdir builddir && cd builddir - cmake .. + cmake -DCMAKE_BUILD_TYPE=Release .. make -j4 cd ../.. fi @@ -18,8 +19,7 @@ fi if [ ! -d LimeGPS ]; then git clone https://github.com/osqzss/LimeGPS.git cd LimeGPS - sed -i 's/LimeSuite/LimeSuite -I..\/LimeSuite\/src -L..\/LimeSuite\/builddir\/src/' makefile + git apply ../patches/limeGPS/* make cd .. fi - diff --git a/tools/gpstest/test_gps.py b/tools/gpstest/test_gps.py new file mode 100644 index 0000000000..f5e19372f7 --- /dev/null +++ b/tools/gpstest/test_gps.py @@ -0,0 +1,140 @@ +#!/usr/bin/env python3 +import time +import unittest +import struct +import numpy as np + +import cereal.messaging as messaging +import selfdrive.sensord.pigeond as pd +from system.hardware import TICI +from selfdrive.test.helpers import with_processes + + +def read_events(service, duration_sec): + service_sock = messaging.sub_sock(service, timeout=0.1) + start_time_sec = time.monotonic() + events = [] + while time.monotonic() - start_time_sec < duration_sec: + events += messaging.drain_sock(service_sock) + time.sleep(0.1) + + assert len(events) != 0, f"No '{service}'events collected!" + return events + + +def verify_ubloxgnss_data(socket: messaging.SubSocket): + start_time = 0 + end_time = 0 + events = messaging.drain_sock(socket) + assert len(events) != 0, "no ublxGnss measurements" + + for event in events: + if event.ubloxGnss.which() != "measurementReport": + continue + + if start_time == 0: + start_time = event.logMonoTime + + if event.ubloxGnss.measurementReport.numMeas != 0: + end_time = event.logMonoTime + break + + assert end_time != 0, "no ublox measurements received!" + + ttfm = (end_time - start_time)/1e9 + assert ttfm < 35, f"Time to first measurement > 35s, {ttfm}" + + # check for satellite count in measurements + sat_count = [] + end_id = events.index(event)# pylint:disable=undefined-loop-variable + for event in events[end_id:]: + if event.ubloxGnss.which() == "measurementReport": + sat_count.append(event.ubloxGnss.measurementReport.numMeas) + + num_sat = int(sum(sat_count)/len(sat_count)) + assert num_sat > 8, f"Not enough satellites {num_sat} (TestBox setup!)" + + +def verify_gps_location(socket: messaging.SubSocket): + buf_lon = [0]*10 + buf_lat = [0]*10 + buf_i = 0 + events = messaging.drain_sock(socket) + assert len(events) != 0, "no gpsLocationExternal measurements" + + start_time = events[0].logMonoTime + end_time = 0 + for event in events: + buf_lon[buf_i % 10] = event.gpsLocationExternal.longitude + buf_lat[buf_i % 10] = event.gpsLocationExternal.latitude + buf_i += 1 + + if buf_i < 9: + continue + + if any([lat == 0 or lon == 0 for lat,lon in zip(buf_lat, buf_lon)]): + continue + + if np.std(buf_lon) < 1e-5 and np.std(buf_lat) < 1e-5: + end_time = event.logMonoTime + break + + assert end_time != 0, "GPS location never converged!" + + ttfl = (end_time - start_time)/1e9 + assert ttfl < 40, f"Time to first location > 40s, {ttfl}" + + hacc = events[-1].gpsLocationExternal.accuracy + vacc = events[-1].gpsLocationExternal.verticalAccuracy + assert hacc < 15, f"Horizontal accuracy too high, {hacc}" + assert vacc < 43, f"Vertical accuracy too high, {vacc}" + + +def verify_time_to_first_fix(pigeon): + # get time to first fix from nav status message + nav_status = b"" + while True: + pigeon.send(b"\xb5\x62\x01\x03\x00\x00\x04\x0d") + nav_status = pigeon.receive() + if nav_status[:4] == b"\xb5\x62\x01\x03": + break + + values = struct.unpack(" 40s, {ttff}" + + +class TestGPS(unittest.TestCase): + @classmethod + def setUpClass(cls): + if not TICI: + raise unittest.SkipTest + + def tearDown(self): + pd.set_power(False) + + @with_processes(['ubloxd']) + def test_ublox_reset(self): + + pigeon, pm = pd.create_pigeon() + pd.init_baudrate(pigeon) + assert pigeon.reset_device(), "Could not reset device!" + + pd.initialize_pigeon(pigeon) + + ugs = messaging.sub_sock("ubloxGnss", timeout=0.1) + gle = messaging.sub_sock("gpsLocationExternal", timeout=0.1) + + # receive some messages (restart after cold start takes up to 30seconds) + pd.run_receiving(pigeon, pm, 40) + + verify_ubloxgnss_data(ugs) + verify_gps_location(gle) + + # skip for now, this might hang for a while + #verify_time_to_first_fix(pigeon) + + +if __name__ == "__main__": + unittest.main() \ No newline at end of file From f74fefaffad87471ba1d7fa351d7fd37b9505d4a Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 11 Oct 2022 18:59:16 -0700 Subject: [PATCH 015/101] =?UTF-8?q?Hyundai:=20remove=2090=C2=B0=20steering?= =?UTF-8?q?=20lockout=20(#24108)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * avoid 90 degree fault * use 50 frames * no panda mods * clean up * absolutely no faults. zero. zilch. nada * fix initial value and comments * try glitching at double rate instead of two in a row * bump panda * cut for two frames * clean up * bump panda * clean up * not today! * bump panda to master * prefix and simple lat_active * prefix --- panda | 2 +- selfdrive/car/hyundai/carcontroller.py | 28 ++++++++++++++++++++++---- selfdrive/car/hyundai/hyundaican.py | 3 ++- 3 files changed, 27 insertions(+), 6 deletions(-) diff --git a/panda b/panda index 1303af2db2..d68b1b0a98 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 1303af2db29a72eee180b10c6097fa5b19c29207 +Subproject commit d68b1b0a98d5cefad438180e3c2ffcdcbcffdd76 diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 4a1f7bcb51..2b0d6b9648 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -10,6 +10,12 @@ from selfdrive.car.hyundai.values import HyundaiFlags, Buttons, CarControllerPar VisualAlert = car.CarControl.HUDControl.VisualAlert LongCtrlState = car.CarControl.Actuators.LongControlState +# EPS faults if you apply torque while the steering angle is above 90 degrees for more than 1 second +# All slightly below EPS thresholds to avoid fault +MAX_ANGLE = 85 +MAX_ANGLE_FRAMES = 89 +MAX_ANGLE_CONSECUTIVE_FRAMES = 2 + def process_hud_alert(enabled, fingerprint, hud_control): sys_warning = (hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw)) @@ -40,6 +46,7 @@ class CarController: self.CP = CP self.params = CarControllerParams(CP) self.packer = CANPacker(dbc_name) + self.angle_limit_counter = 0 self.frame = 0 self.apply_steer_last = 0 @@ -107,10 +114,23 @@ class CarController: if self.frame % 100 == 0: can_sends.append([0x7D0, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", 0]) - can_sends.append(hyundaican.create_lkas11(self.packer, self.frame, self.car_fingerprint, apply_steer, CC.latActive, - CS.lkas11, sys_warning, sys_state, CC.enabled, - hud_control.leftLaneVisible, hud_control.rightLaneVisible, - left_lane_warning, right_lane_warning)) + # Count up to MAX_ANGLE_FRAMES, at which point we need to cut torque to avoid a steering fault + if CC.latActive and abs(CS.out.steeringAngleDeg) >= MAX_ANGLE: + self.angle_limit_counter += 1 + else: + self.angle_limit_counter = 0 + + # Cut steer actuation bit for two frames and hold torque with induced temporary fault + torque_fault = CC.latActive and self.angle_limit_counter > MAX_ANGLE_FRAMES + lat_active = CC.latActive and not torque_fault + + if self.angle_limit_counter >= MAX_ANGLE_FRAMES + MAX_ANGLE_CONSECUTIVE_FRAMES: + self.angle_limit_counter = 0 + + can_sends.append(hyundaican.create_lkas11(self.packer, self.frame, self.car_fingerprint, apply_steer, lat_active, + torque_fault, CS.lkas11, sys_warning, sys_state, CC.enabled, + hud_control.leftLaneVisible, hud_control.rightLaneVisible, + left_lane_warning, right_lane_warning)) if not self.CP.openpilotLongitudinalControl: if CC.cruiseControl.cancel: diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py index f4fe8f1126..dcb8430976 100644 --- a/selfdrive/car/hyundai/hyundaican.py +++ b/selfdrive/car/hyundai/hyundaican.py @@ -4,7 +4,7 @@ from selfdrive.car.hyundai.values import CAR, CHECKSUM, CAMERA_SCC_CAR hyundai_checksum = crcmod.mkCrcFun(0x11D, initCrc=0xFD, rev=False, xorOut=0xdf) def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req, - lkas11, sys_warning, sys_state, enabled, + torque_fault, lkas11, sys_warning, sys_state, enabled, left_lane, right_lane, left_lane_depart, right_lane_depart): values = lkas11 @@ -14,6 +14,7 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req, values["CF_Lkas_LdwsRHWarning"] = right_lane_depart values["CR_Lkas_StrToqReq"] = apply_steer values["CF_Lkas_ActToi"] = steer_req + values["CF_Lkas_ToiFlt"] = torque_fault # seems to allow actuation on CR_Lkas_StrToqReq values["CF_Lkas_MsgCount"] = frame % 0x10 if car_fingerprint in (CAR.SONATA, CAR.PALISADE, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV_2021, CAR.SANTA_FE, From 6dbfb8e49bde77a5ebddab2c8e084dfb596efd92 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 11 Oct 2022 21:27:09 -0700 Subject: [PATCH 016/101] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index b1003dd012..3eca747334 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit b1003dd0128a451439d4fe98d098d90e994f81ed +Subproject commit 3eca747334ca2138bf35d70399d58d0706a3cbd2 From 0f94d81b7adffa9da5c4632fb5979b27695bbb53 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 11 Oct 2022 22:33:37 -0700 Subject: [PATCH 017/101] GM camera ACC: reduce LKAS faults on startup (#26039) * GM camera ACC: no faults on start up 2.0 And by 2.0 I mean we don't need to wait for blocked msg support to be merged first to merge this without regressing accidental single blocked msg count handling. * Send the camera counter + 1 * Keep updating the first counter until we get a message on the bus * Only update right before sending so sent_lka_steering_cmd is updated first * Update ref_commit --- selfdrive/car/gm/carcontroller.py | 17 ++++++++++------- selfdrive/car/gm/carstate.py | 19 +++++++++++++++---- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 26 insertions(+), 12 deletions(-) diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index 977d20c5b3..7c883dacc0 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -21,7 +21,8 @@ class CarController: self.frame = 0 self.last_button_frame = 0 - self.lka_steering_cmd_counter_last = -1 + self.lka_steering_cmd_counter = 0 + self.sent_lka_steering_cmd = False self.lka_icon_status_last = (False, False) self.params = CarControllerParams() @@ -44,9 +45,14 @@ class CarController: # Steering (50Hz) # Avoid GM EPS faults when transmitting messages too close together: skip this transmit if we just received the # next Panda loopback confirmation in the current CS frame. - if CS.lka_steering_cmd_counter != self.lka_steering_cmd_counter_last: - self.lka_steering_cmd_counter_last = CS.lka_steering_cmd_counter + if CS.loopback_lka_steering_cmd_updated: + self.lka_steering_cmd_counter += 1 + self.sent_lka_steering_cmd = True elif (self.frame % self.params.STEER_STEP) == 0: + # Initialize ASCMLKASteeringCmd counter using the camera + if not self.sent_lka_steering_cmd and self.CP.networkLocation == NetworkLocation.fwdCamera: + self.lka_steering_cmd_counter = CS.camera_lka_steering_cmd_counter + 1 + if CC.latActive: new_steer = int(round(actuators.steer * self.params.STEER_MAX)) apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) @@ -54,10 +60,7 @@ class CarController: apply_steer = 0 self.apply_steer_last = apply_steer - # GM EPS faults on any gap in received message counters. To handle transient OP/Panda safety sync issues at the - # moment of disengaging, increment the counter based on the last message known to pass Panda safety checks. - idx = (CS.lka_steering_cmd_counter + 1) % 4 - + idx = self.lka_steering_cmd_counter % 4 can_sends.append(gmcan.create_steering_control(self.packer_pt, CanBus.POWERTRAIN, apply_steer, idx, CC.latActive)) if self.CP.openpilotLongitudinalControl: diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index f96a234dbd..6d1e2b9d44 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -15,7 +15,8 @@ class CarState(CarStateBase): super().__init__(CP) can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) self.shifter_values = can_define.dv["ECMPRDNL2"]["PRNDL2"] - self.lka_steering_cmd_counter = 0 + self.loopback_lka_steering_cmd_updated = False + self.camera_lka_steering_cmd_counter = 0 self.buttons_counter = 0 def update(self, pt_cp, cam_cp, loopback_cp): @@ -25,6 +26,11 @@ class CarState(CarStateBase): self.cruise_buttons = pt_cp.vl["ASCMSteeringButton"]["ACCButtons"] self.buttons_counter = pt_cp.vl["ASCMSteeringButton"]["RollingCounter"] + # Variables used for avoiding LKAS faults + self.loopback_lka_steering_cmd_updated = len(loopback_cp.vl_all["ASCMLKASteeringCmd"]) > 0 + if self.CP.networkLocation == NetworkLocation.fwdCamera: + self.camera_lka_steering_cmd_counter = cam_cp.vl["ASCMLKASteeringCmd"]["RollingCounter"] + ret.wheelSpeeds = self.get_wheel_speeds( pt_cp.vl["EBCMWheelSpdFront"]["FLWheelSpd"], pt_cp.vl["EBCMWheelSpdFront"]["FRWheelSpd"], @@ -59,7 +65,6 @@ class CarState(CarStateBase): ret.steeringTorque = pt_cp.vl["PSCMStatus"]["LKADriverAppldTrq"] ret.steeringTorqueEps = pt_cp.vl["PSCMStatus"]["LKATorqueDelivered"] ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD - self.lka_steering_cmd_counter = loopback_cp.vl["ASCMLKASteeringCmd"]["RollingCounter"] # 0 inactive, 1 active, 2 temporarily limited, 3 failed self.lkas_status = pt_cp.vl["PSCMStatus"]["LKATorqueDeliveredStatus"] @@ -94,8 +99,14 @@ class CarState(CarStateBase): signals = [] checks = [] if CP.networkLocation == NetworkLocation.fwdCamera: - signals.append(("ACCSpeedSetpoint", "ASCMActiveCruiseControlStatus")) - checks.append(("ASCMActiveCruiseControlStatus", 25)) + signals += [ + ("RollingCounter", "ASCMLKASteeringCmd"), + ("ACCSpeedSetpoint", "ASCMActiveCruiseControlStatus"), + ] + checks += [ + ("ASCMLKASteeringCmd", 10), + ("ASCMActiveCruiseControlStatus", 25), + ] return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus.CAMERA) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index db3684fb0b..6b64fcb5aa 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -02c6922762fef41c8188a5a4f1f3267b76651330 \ No newline at end of file +5fa6a3743f2678eef13267fb946d7a03f2af5824 From 5ad89425a7b4a888ae43228af92b8839f79ec9ec Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 11 Oct 2022 22:55:21 -0700 Subject: [PATCH 018/101] GM camera ACC: log stock aeb/fcw (#26017) * GM camera ACC: log aeb/fcw * order * fix stockAeb --- selfdrive/car/gm/carstate.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index 6d1e2b9d44..11c521e863 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -92,6 +92,9 @@ class CarState(CarStateBase): if self.CP.networkLocation == NetworkLocation.fwdCamera: ret.cruiseState.speed = cam_cp.vl["ASCMActiveCruiseControlStatus"]["ACCSpeedSetpoint"] * CV.KPH_TO_MS + ret.stockAeb = cam_cp.vl["AEBCmd"]["AEBCmdActive"] != 0 + ret.stockFcw = cam_cp.vl["ASCMActiveCruiseControlStatus"]["FCWAlert"] != 0 + return ret @staticmethod @@ -100,10 +103,13 @@ class CarState(CarStateBase): checks = [] if CP.networkLocation == NetworkLocation.fwdCamera: signals += [ + ("AEBCmdActive", "AEBCmd"), ("RollingCounter", "ASCMLKASteeringCmd"), + ("FCWAlert", "ASCMActiveCruiseControlStatus"), ("ACCSpeedSetpoint", "ASCMActiveCruiseControlStatus"), ] checks += [ + ("AEBCmd", 10), ("ASCMLKASteeringCmd", 10), ("ASCMActiveCruiseControlStatus", 25), ] From 967f0cc9f8afb17c049d893bedc7bd696404082b Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 12 Oct 2022 13:05:09 -0700 Subject: [PATCH 019/101] bump opendbc --- opendbc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc b/opendbc index c35e8139bf..04cc54d5e6 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit c35e8139bf9e9d87b9efb6764ab7e65983e8d33e +Subproject commit 04cc54d5e662aaf708f72cabb65507c7dbb5136d From aa3dc7acbe889b62576a2d1eb9c6b076b1cfa6cb Mon Sep 17 00:00:00 2001 From: Nelson Chen Date: Wed, 12 Oct 2022 13:31:08 -0700 Subject: [PATCH 020/101] RAV4 2022: Add missing engine FW (#26044) From 23e0360acaefab4d --- 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 137db5612b..819b85d759 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1363,6 +1363,7 @@ FW_VERSIONS = { ], (Ecu.engine, 0x700, None): [ b'\x01896634AA0000\x00\x00\x00\x00', + b'\x01896634AA0100\x00\x00\x00\x00', b'\x01896634AA1000\x00\x00\x00\x00', b'\x01896634A88000\x00\x00\x00\x00', b'\x01896634A89000\x00\x00\x00\x00', From 03a065160e176be451cce95073b71bbfce5b4d6a Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Wed, 12 Oct 2022 13:51:09 -0700 Subject: [PATCH 021/101] ci: only run one instance of each workflow (#26036) only allow one running workflow per event for each branch --- .github/workflows/selfdrive_tests.yaml | 5 +++++ .github/workflows/tools_tests.yaml | 5 +++++ 2 files changed, 10 insertions(+) diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index d4971a4339..9c38ba0cbc 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -1,10 +1,15 @@ name: selfdrive + on: push: branches-ignore: - 'testing-closet*' pull_request: +concurrency: + group: ${{ github.workflow }}-${{ github.ref }}-${{ github.event_name }} + cancel-in-progress: true + env: BASE_IMAGE: openpilot-base CL_BASE_IMAGE: openpilot-base-cl diff --git a/.github/workflows/tools_tests.yaml b/.github/workflows/tools_tests.yaml index 173e208384..c5afaad16c 100644 --- a/.github/workflows/tools_tests.yaml +++ b/.github/workflows/tools_tests.yaml @@ -1,8 +1,13 @@ name: tools + on: push: pull_request: +concurrency: + group: ${{ github.workflow }}-${{ github.ref }}-${{ github.event_name }} + cancel-in-progress: true + env: BASE_IMAGE: openpilot-base CL_BASE_IMAGE: openpilot-base-cl From 0fa1588f6c0bf9c9f1bebde91e02699506389ecd Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 13 Oct 2022 04:55:17 +0800 Subject: [PATCH 022/101] Cabana: stable initial release (#26004) * increase form size & fix wrong charts number * set max axisy to 1.0 if no value * show 'close' button in floating window * alwasy show scroll bar * complete the logs * more * increase size to 50 * keep logs for all messages * more * rename signal * better height * avoid flicker * dont call setupdatesenabled * filter dbc files bye typing * remove all charts if dbc file changed * fix wrong idx * bolder dbc filename * update chart if signal has been edited * new signals signalAdded,signalUpdated * split class Parser into CanMessages and DBCManager * cleanup * updateState after set message * cleanup * emit msgUpdated * clear history log if selected range changed * always update time * change title layout * show selected range hide title bar if no charts less space between title and chart * custome historylogmodel for extreme fast update * move historylog to seperate file * 2 decimal * cleanup cleanup * left click on the chart to set start time * todo * show tooltip for header item&cleanup binaryview add hline to signal form * better paint * cleanup signals/slots * better range if min==max * set historylog's minheight to 300 * 3x faster,sortable message list. * zero copy in queued connection * proxymodel * clear log if loop to the begin * simplify history log * remove icon * remove assets * hide linemarker on initialization * rubber width may less than 0 * dont zoom char if selected range is too small * cleanup messageslist * don't zoom chart if selected range less than 500ms * typo * check boundary * check msg_id * capital first letter * move history log out of scrollarea * Show only one form at a time * auto scroll to header d * reduce msg size entire row clickable rename filter_msgs --- tools/cabana/SConscript | 9 +- tools/cabana/cabana.cc | 6 +- tools/cabana/canmessages.cc | 123 ++++++++++++++++ tools/cabana/canmessages.h | 84 +++++++++++ tools/cabana/chartswidget.cc | 174 ++++++++++++++--------- tools/cabana/chartswidget.h | 25 +++- tools/cabana/dbcmanager.cc | 117 ++++++++++++++++ tools/cabana/dbcmanager.h | 51 +++++++ tools/cabana/detailwidget.cc | 224 ++++++++++++++---------------- tools/cabana/detailwidget.h | 53 ++++--- tools/cabana/historylog.cc | 91 ++++++++++++ tools/cabana/historylog.h | 37 +++++ tools/cabana/mainwin.cc | 7 +- tools/cabana/mainwin.h | 1 - tools/cabana/messageswidget.cc | 132 ++++++++++++------ tools/cabana/messageswidget.h | 38 +++-- tools/cabana/parser.cc | 181 ------------------------ tools/cabana/parser.h | 95 ------------- tools/cabana/signaledit.cc | 69 ++++----- tools/cabana/signaledit.h | 20 ++- tools/cabana/videowidget.cc | 115 ++++++--------- tools/cabana/videowidget.h | 16 +-- tools/replay/main.cc | 2 - tools/replay/replay.h | 2 + tools/replay/tests/test_replay.cc | 1 - 25 files changed, 999 insertions(+), 674 deletions(-) create mode 100644 tools/cabana/canmessages.cc create mode 100644 tools/cabana/canmessages.h create mode 100644 tools/cabana/dbcmanager.cc create mode 100644 tools/cabana/dbcmanager.h create mode 100644 tools/cabana/historylog.cc create mode 100644 tools/cabana/historylog.h delete mode 100644 tools/cabana/parser.cc delete mode 100644 tools/cabana/parser.h diff --git a/tools/cabana/SConscript b/tools/cabana/SConscript index c87e2cdd94..b94741ea9c 100644 --- a/tools/cabana/SConscript +++ b/tools/cabana/SConscript @@ -1,5 +1,4 @@ -import os -Import('env', 'qt_env', 'arch', 'common', 'messaging', 'visionipc', +Import('env', 'qt_env', 'arch', 'common', 'messaging', 'visionipc', 'replay_lib', 'cereal', 'transformations', 'widgets', 'opendbc') base_frameworks = qt_env['FRAMEWORKS'] @@ -13,8 +12,6 @@ else: qt_libs = ['qt_util', 'Qt5Charts'] + base_libs if arch in ['x86_64', 'Darwin'] and GetOption('extras'): - qt_env['CXXFLAGS'] += ["-Wno-deprecated-declarations"] - - Import('replay_lib') cabana_libs = [widgets, cereal, messaging, visionipc, replay_lib, opendbc,'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv'] + qt_libs - qt_env.Program('_cabana', ['cabana.cc', 'mainwin.cc', 'chartswidget.cc', 'videowidget.cc', 'signaledit.cc', 'parser.cc', 'messageswidget.cc', 'detailwidget.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks) + qt_env.Program('_cabana', ['cabana.cc', 'mainwin.cc', 'chartswidget.cc', 'historylog.cc', 'videowidget.cc', 'signaledit.cc', 'dbcmanager.cc', + 'canmessages.cc', 'messageswidget.cc', 'detailwidget.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks) diff --git a/tools/cabana/cabana.cc b/tools/cabana/cabana.cc index 20cd889023..88b175663f 100644 --- a/tools/cabana/cabana.cc +++ b/tools/cabana/cabana.cc @@ -1,14 +1,14 @@ #include #include +#include #include "selfdrive/ui/qt/util.h" #include "tools/cabana/mainwin.h" -const QString DEMO_ROUTE = "4cf7a6ad03080c90|2021-09-29--13-46-36"; - int main(int argc, char *argv[]) { initApp(argc, argv); QApplication app(argc, argv); + app.setStyle(QStyleFactory::create("Fusion")); QCommandLineParser cmd_parser; cmd_parser.addHelpOption(); @@ -22,7 +22,7 @@ int main(int argc, char *argv[]) { } const QString route = args.empty() ? DEMO_ROUTE : args.first(); - Parser p(&app); + CANMessages p(&app); if (!p.loadRoute(route, cmd_parser.value("data_dir"), true)) { return 0; } diff --git a/tools/cabana/canmessages.cc b/tools/cabana/canmessages.cc new file mode 100644 index 0000000000..a55a045981 --- /dev/null +++ b/tools/cabana/canmessages.cc @@ -0,0 +1,123 @@ +#include "tools/cabana/canmessages.h" + +#include + +Q_DECLARE_METATYPE(std::vector); + +CANMessages *can = nullptr; + +CANMessages::CANMessages(QObject *parent) : QObject(parent) { + can = this; + + qRegisterMetaType>(); + QObject::connect(this, &CANMessages::received, this, &CANMessages::process, Qt::QueuedConnection); +} + +CANMessages::~CANMessages() { + replay->stop(); +} + +static bool event_filter(const Event *e, void *opaque) { + CANMessages *c = (CANMessages *)opaque; + return c->eventFilter(e); +} + +bool CANMessages::loadRoute(const QString &route, const QString &data_dir, bool use_qcam) { + replay = new Replay(route, {"can", "roadEncodeIdx"}, {}, nullptr, use_qcam ? REPLAY_FLAG_QCAMERA : 0, data_dir, this); + replay->installEventFilter(event_filter, this); + QObject::connect(replay, &Replay::segmentsMerged, this, &CANMessages::segmentsMerged); + if (replay->load()) { + replay->start(); + return true; + } + return false; +} + +void CANMessages::process(QHash> *messages) { + for (auto it = messages->begin(); it != messages->end(); ++it) { + ++counters[it.key()]; + auto &msgs = can_msgs[it.key()]; + const auto &new_msgs = it.value(); + if (msgs.size() == CAN_MSG_LOG_SIZE || can_msgs[it.key()].size() == 0) { + msgs = std::move(new_msgs); + } else { + msgs.insert(msgs.begin(), std::make_move_iterator(new_msgs.begin()), std::make_move_iterator(new_msgs.end())); + while (msgs.size() >= CAN_MSG_LOG_SIZE) { + msgs.pop_back(); + } + } + } + delete messages; + + if (current_sec < begin_sec || current_sec > end_sec) { + // loop replay in selected range. + seekTo(begin_sec); + } else { + emit updated(); + } +} + +bool CANMessages::eventFilter(const Event *event) { + static double prev_update_sec = 0; + // drop packets when the GUI thread is calling seekTo. to make sure the current_sec is accurate. + if (!seeking && event->which == cereal::Event::Which::CAN) { + if (!received_msgs) { + received_msgs.reset(new QHash>); + received_msgs->reserve(1000); + } + + current_sec = (event->mono_time - replay->routeStartTime()) / (double)1e9; + auto can_events = event->event.getCan(); + for (const auto &c : can_events) { + QString id = QString("%1:%2").arg(c.getSrc()).arg(c.getAddress(), 1, 16); + auto &list = (*received_msgs)[id]; + while (list.size() >= CAN_MSG_LOG_SIZE) { + list.pop_back(); + } + CanData &data = list.emplace_front(); + data.ts = current_sec; + data.bus_time = c.getBusTime(); + data.dat.append((char *)c.getDat().begin(), c.getDat().size()); + } + + if (current_sec < prev_update_sec || (current_sec - prev_update_sec) > 1.0 / FPS) { + prev_update_sec = current_sec; + // use pointer to avoid data copy in queued connection. + emit received(received_msgs.release()); + } + } + return true; +} + +void CANMessages::seekTo(double ts) { + seeking = true; + replay->seekTo(ts, false); + seeking = false; +} + +void CANMessages::setRange(double min, double max) { + if (begin_sec != min || end_sec != max) { + begin_sec = min; + end_sec = max; + is_zoomed = begin_sec != event_begin_sec || end_sec != event_end_sec; + emit rangeChanged(min, max); + } +} + +void CANMessages::segmentsMerged() { + auto events = replay->events(); + if (!events || events->empty()) return; + + auto it = std::find_if(events->begin(), events->end(), [=](const Event *e) { return e->which == cereal::Event::Which::CAN; }); + event_begin_sec = it == events->end() ? 0 : ((*it)->mono_time - replay->routeStartTime()) / (double)1e9; + event_end_sec = double(events->back()->mono_time - replay->routeStartTime()) / 1e9; + if (!is_zoomed) { + begin_sec = event_begin_sec; + end_sec = event_end_sec; + } + emit eventsMerged(); +} + +void CANMessages::resetRange() { + setRange(event_begin_sec, event_end_sec); +} diff --git a/tools/cabana/canmessages.h b/tools/cabana/canmessages.h new file mode 100644 index 0000000000..a2af2a084c --- /dev/null +++ b/tools/cabana/canmessages.h @@ -0,0 +1,84 @@ +#pragma once + +#include +#include +#include + +#include + +#include "tools/replay/replay.h" + +const int FPS = 10; +const int CAN_MSG_LOG_SIZE = 100; + +struct CanData { + double ts; + uint16_t bus_time; + QByteArray dat; +}; + +class CANMessages : public QObject { + Q_OBJECT + +public: + CANMessages(QObject *parent); + ~CANMessages(); + bool loadRoute(const QString &route, const QString &data_dir, bool use_qcam); + void seekTo(double ts); + void resetRange(); + void setRange(double min, double max); + bool eventFilter(const Event *event); + + inline std::pair range() const { return {begin_sec, end_sec}; } + inline double totalSeconds() const { return replay->totalSeconds(); } + inline double routeStartTime() const { return replay->routeStartTime() / (double)1e9; } + inline double currentSec() const { return current_sec; } + inline bool isZoomed() const { return is_zoomed; } + inline const std::deque &messages(const QString &id) { return can_msgs[id]; } + inline const CanData &lastMessage(const QString &id) { return can_msgs[id].front(); } + + inline const std::vector *events() const { return replay->events(); } + inline void setSpeed(float speed) { replay->setSpeed(speed); } + inline bool isPaused() const { return replay->isPaused(); } + inline void pause(bool pause) { replay->pause(pause); } + inline const std::vector> getTimeline() { return replay->getTimeline(); } + +signals: + void eventsMerged(); + void rangeChanged(double min, double max); + void updated(); + void received(QHash> *); + +public: + QMap> can_msgs; + std::unique_ptr>> received_msgs = nullptr; + QHash counters; + +protected: + void process(QHash> *); + void segmentsMerged(); + + std::atomic current_sec = 0.; + std::atomic seeking = false; + double begin_sec = 0; + double end_sec = 0; + double event_begin_sec = 0; + double event_end_sec = 0; + bool is_zoomed = false; + Replay *replay = nullptr; +}; + +inline QString toHex(const QByteArray &dat) { + return dat.toHex(' ').toUpper(); +} +inline char toHex(uint value) { + return "0123456789ABCDEF"[value & 0xF]; +} + +inline const QString &getColor(int i) { + static const QString SIGNAL_COLORS[] = {"#9FE2BF", "#40E0D0", "#6495ED", "#CCCCFF", "#FF7F50", "#FFBF00"}; + return SIGNAL_COLORS[i % std::size(SIGNAL_COLORS)]; +} + +// A global pointer referring to the unique CANMessages object +extern CANMessages *can; diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index 5caa8d5a43..e8a27ae18c 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -7,25 +7,6 @@ #include #include -int64_t get_raw_value(uint8_t *data, size_t data_size, const Signal &sig) { - int64_t ret = 0; - - int i = sig.msb / 8; - int bits = sig.size; - while (i >= 0 && i < data_size && bits > 0) { - int lsb = (int)(sig.lsb / 8) == i ? sig.lsb : i * 8; - int msb = (int)(sig.msb / 8) == i ? sig.msb : (i + 1) * 8 - 1; - int size = msb - lsb + 1; - - uint64_t d = (data[i] >> (lsb - (i * 8))) & ((1ULL << size) - 1); - ret |= d << (bits - size); - - bits -= size; - i = sig.is_little_endian ? i - 1 : i + 1; - } - return ret; -} - // ChartsWidget ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) { @@ -35,18 +16,22 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) { // title bar title_bar = new QWidget(this); QHBoxLayout *title_layout = new QHBoxLayout(title_bar); + title_layout->setContentsMargins(0, 0, 0, 0); title_label = new QLabel(tr("Charts")); title_layout->addWidget(title_label); title_layout->addStretch(); + range_label = new QLabel(); + title_layout->addWidget(range_label); + reset_zoom_btn = new QPushButton("⟲", this); reset_zoom_btn->setVisible(false); reset_zoom_btn->setFixedSize(30, 30); reset_zoom_btn->setToolTip(tr("Reset zoom (drag on chart to zoom X-Axis)")); title_layout->addWidget(reset_zoom_btn); - remove_all_btn = new QPushButton(tr("✖")); + remove_all_btn = new QPushButton("✖", this); remove_all_btn->setVisible(false); remove_all_btn->setToolTip(tr("Remove all charts")); remove_all_btn->setFixedSize(30, 30); @@ -54,7 +39,6 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) { dock_btn = new QPushButton(); dock_btn->setFixedSize(30, 30); - updateDockButton(); title_layout->addWidget(dock_btn); main_layout->addWidget(title_bar, 0, Qt::AlignTop); @@ -74,53 +58,80 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) { main_layout->addWidget(charts_scroll); - QObject::connect(parser, &Parser::showPlot, this, &ChartsWidget::addChart); - QObject::connect(parser, &Parser::hidePlot, this, &ChartsWidget::removeChart); - QObject::connect(parser, &Parser::signalRemoved, this, &ChartsWidget::removeChart); - QObject::connect(reset_zoom_btn, &QPushButton::clicked, parser, &Parser::resetRange); + updateTitleBar(); + + QObject::connect(dbc(), &DBCManager::signalRemoved, this, &ChartsWidget::removeChart); + QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &ChartsWidget::removeAll); + QObject::connect(can, &CANMessages::rangeChanged, [this]() { updateTitleBar(); }); + QObject::connect(reset_zoom_btn, &QPushButton::clicked, can, &CANMessages::resetRange); QObject::connect(remove_all_btn, &QPushButton::clicked, this, &ChartsWidget::removeAll); - QObject::connect(dock_btn, &QPushButton::clicked, [=]() { + QObject::connect(dock_btn, &QPushButton::clicked, [this]() { emit dock(!docking); docking = !docking; - updateDockButton(); + updateTitleBar(); }); } -void ChartsWidget::updateDockButton() { +void ChartsWidget::updateTitleBar() { + if (!charts.size()) { + title_bar->setVisible(false); + return; + } + + title_label->setText(tr("Charts (%1)").arg(charts.size())); + + // show select range + if (can->isZoomed()) { + auto [min, max] = can->range(); + range_label->setText(tr("%1 - %2").arg(min, 0, 'f', 2).arg(max, 0, 'f', 2)); + range_label->setVisible(true); + reset_zoom_btn->setEnabled(true); + } else { + reset_zoom_btn->setEnabled(false); + range_label->setVisible(false); + } + dock_btn->setText(docking ? "⬈" : "⬋"); dock_btn->setToolTip(docking ? tr("Undock charts") : tr("Dock charts")); + remove_all_btn->setVisible(!charts.empty()); + reset_zoom_btn->setVisible(!charts.empty()); + title_bar->setVisible(true); } void ChartsWidget::addChart(const QString &id, const QString &sig_name) { - const QString char_name = id + sig_name; + const QString char_name = id + ":" + sig_name; if (charts.find(char_name) == charts.end()) { auto chart = new ChartWidget(id, sig_name, this); + QObject::connect(chart, &ChartWidget::remove, [=]() { + removeChart(id, sig_name); + }); charts_layout->insertWidget(0, chart); charts[char_name] = chart; } - remove_all_btn->setVisible(true); - reset_zoom_btn->setVisible(true); - title_label->setText(tr("Charts (%1)").arg(charts.size())); + updateTitleBar(); } void ChartsWidget::removeChart(const QString &id, const QString &sig_name) { - if (auto it = charts.find(id + sig_name); it != charts.end()) { + if (auto it = charts.find(id + ":" + sig_name); it != charts.end()) { it->second->deleteLater(); charts.erase(it); - if (charts.empty()) { - remove_all_btn->setVisible(false); - reset_zoom_btn->setVisible(false); - } } - title_label->setText(tr("Charts (%1)").arg(charts.size())); + updateTitleBar(); } void ChartsWidget::removeAll() { for (auto [_, chart] : charts) chart->deleteLater(); charts.clear(); - remove_all_btn->setVisible(false); - reset_zoom_btn->setVisible(false); + updateTitleBar(); +} + +bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) { + if (obj != this && event->type() == QEvent::Close) { + emit dock_btn->clicked(); + return true; + } + return false; } // ChartWidget @@ -138,16 +149,14 @@ ChartWidget::ChartWidget(const QString &id, const QString &sig_name, QWidget *pa header->setStyleSheet("background-color:white"); QHBoxLayout *header_layout = new QHBoxLayout(header); header_layout->setContentsMargins(11, 11, 11, 0); - QLabel *title = new QLabel(tr("%1 %2").arg(parser->getMsg(id)->name.c_str()).arg(id)); + QLabel *title = new QLabel(tr("%1 %2").arg(dbc()->msg(id)->name.c_str()).arg(id)); header_layout->addWidget(title); header_layout->addStretch(); QPushButton *remove_btn = new QPushButton("✖", this); remove_btn->setFixedSize(30, 30); remove_btn->setToolTip(tr("Remove chart")); - QObject::connect(remove_btn, &QPushButton::clicked, [=]() { - emit parser->hidePlot(id, sig_name); - }); + QObject::connect(remove_btn, &QPushButton::clicked, this, &ChartWidget::remove); header_layout->addWidget(remove_btn); chart_layout->addWidget(header); @@ -163,9 +172,8 @@ ChartWidget::ChartWidget(const QString &id, const QString &sig_name, QWidget *pa chart->setTitleFont(font); chart->setMargins({0, 0, 0, 0}); chart->layout()->setContentsMargins(0, 0, 0, 0); - QObject::connect(dynamic_cast(chart->axisX()), &QValueAxis::rangeChanged, parser, &Parser::setRange); - chart_view = new QChartView(chart); + chart_view = new ChartView(chart); chart_view->setFixedHeight(300); chart_view->setRenderHint(QPainter::Antialiasing); chart_view->setRubberBand(QChartView::HorizontalRubberBand); @@ -184,26 +192,28 @@ ChartWidget::ChartWidget(const QString &id, const QString &sig_name, QWidget *pa line_marker->raise(); setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Fixed); - QObject::connect(parser, &Parser::updated, this, &ChartWidget::updateState); - QObject::connect(parser, &Parser::rangeChanged, this, &ChartWidget::rangeChanged); - QObject::connect(parser, &Parser::eventsMerged, this, &ChartWidget::updateSeries); - + QObject::connect(can, &CANMessages::updated, this, &ChartWidget::updateState); + QObject::connect(can, &CANMessages::rangeChanged, this, &ChartWidget::rangeChanged); + QObject::connect(can, &CANMessages::eventsMerged, this, &ChartWidget::updateSeries); + QObject::connect(dynamic_cast(chart->axisX()), &QValueAxis::rangeChanged, can, &CANMessages::setRange); + QObject::connect(dbc(), &DBCManager::signalUpdated, [this](const QString &msg_id, const QString &sig_name) { + if (this->id == msg_id && this->sig_name == sig_name) + updateSeries(); + }); updateSeries(); } void ChartWidget::updateState() { auto chart = chart_view->chart(); auto axis_x = dynamic_cast(chart->axisX()); - int x = chart->plotArea().left() + chart->plotArea().width() * (parser->currentSec() - axis_x->min()) / (axis_x->max() - axis_x->min()); - if (line_marker_x != x) { - line_marker->setX(x); - line_marker_x = x; - } + + int x = chart->plotArea().left() + chart->plotArea().width() * (can->currentSec() - axis_x->min()) / (axis_x->max() - axis_x->min()); + line_marker->setX(x); } void ChartWidget::updateSeries() { - const Signal *sig = parser->getSig(id, sig_name); - auto events = parser->replay->events(); + const Signal *sig = dbc()->signal(id, sig_name); + auto events = can->events(); if (!sig || !events) return; auto l = id.split(':'); @@ -212,18 +222,14 @@ void ChartWidget::updateSeries() { vals.clear(); vals.reserve(3 * 60 * 100); - uint64_t route_start_time = parser->replay->routeStartTime(); + uint64_t route_start_time = can->routeStartTime(); for (auto &evt : *events) { if (evt->which == cereal::Event::Which::CAN) { for (auto c : evt->event.getCan()) { if (bus == c.getSrc() && address == c.getAddress()) { auto dat = c.getDat(); - int64_t val = get_raw_value((uint8_t *)dat.begin(), dat.size(), *sig); - if (sig->is_signed) { - val -= ((val >> (sig->size - 1)) & 0x1) ? (1ULL << sig->size) : 0; - } - double value = val * sig->factor + sig->offset; - double ts = (evt->mono_time - route_start_time) / (double)1e9; // seconds + double value = get_raw_value((uint8_t *)dat.begin(), dat.size(), *sig); + double ts = (evt->mono_time / (double)1e9) - route_start_time; // seconds vals.push_back({ts, value}); } } @@ -231,7 +237,7 @@ void ChartWidget::updateSeries() { } QLineSeries *series = (QLineSeries *)chart_view->chart()->series()[0]; series->replace(vals); - auto [begin, end] = parser->range(); + auto [begin, end] = can->range(); chart_view->chart()->axisX()->setRange(begin, end); updateAxisY(); } @@ -247,6 +253,7 @@ void ChartWidget::rangeChanged(qreal min, qreal max) { // auto zoom on yaxis void ChartWidget::updateAxisY() { const auto axis_x = dynamic_cast(chart_view->chart()->axisX()); + const auto axis_y = dynamic_cast(chart_view->chart()->axisY()); // vals is a sorted list auto begin = std::lower_bound(vals.begin(), vals.end(), axis_x->min(), [](auto &p, double x) { return p.x() < x; }); if (begin == vals.end()) @@ -254,14 +261,45 @@ void ChartWidget::updateAxisY() { auto end = std::upper_bound(vals.begin(), vals.end(), axis_x->max(), [](double x, auto &p) { return x < p.x(); }); const auto [min, max] = std::minmax_element(begin, end, [](auto &p1, auto &p2) { return p1.y() < p2.y(); }); - chart_view->chart()->axisY()->setRange(min->y(), max->y()); + if (min->y() == max->y()) { + if (max->y() < 0) { + axis_y->setRange(max->y(), 0); + } else { + axis_y->setRange(0, max->y() == 0 ? 1 : max->y()); + } + } else { + axis_y->setRange(min->y(), max->y()); + } } +// ChartView + +void ChartView::mouseReleaseEvent(QMouseEvent *event) { + auto rubber = findChild(); + if (event->button() == Qt::LeftButton && rubber && rubber->isVisible()) { + auto [begin, end] = can->range(); + if (rubber->width() <= 0) { + double seek_to = begin + ((event->pos().x() - chart()->plotArea().x()) / chart()->plotArea().width()) * (end - begin); + can->seekTo(seek_to); + } else if (((double)rubber->width() / chart()->plotArea().width()) * (end - begin) < 0.5) { + // don't zoom if selected range is less than 0.5s + rubber->hide(); + event->accept(); + return; + } + } + // TODO: right-click to reset zoom + QChartView::mouseReleaseEvent(event); +} + + // LineMarker void LineMarker::setX(double x) { - x_pos = x; - update(); + if (x != x_pos) { + x_pos = x; + update(); + } } void LineMarker::paintEvent(QPaintEvent *event) { diff --git a/tools/cabana/chartswidget.h b/tools/cabana/chartswidget.h index 81df2237bc..7dbf0f108b 100644 --- a/tools/cabana/chartswidget.h +++ b/tools/cabana/chartswidget.h @@ -9,7 +9,8 @@ #include #include -#include "tools/cabana/parser.h" +#include "tools/cabana/canmessages.h" +#include "tools/cabana/dbcmanager.h" using namespace QtCharts; @@ -22,7 +23,15 @@ public: private: void paintEvent(QPaintEvent *event) override; - double x_pos = 0.0; + double x_pos = -1; +}; + +class ChartView : public QChartView { + Q_OBJECT + +public: + ChartView(QChart *chart, QWidget *parent = nullptr) : QChartView(chart, parent) {} + void mouseReleaseEvent(QMouseEvent *event) override; }; class ChartWidget : public QWidget { @@ -32,6 +41,9 @@ public: ChartWidget(const QString &id, const QString &sig_name, QWidget *parent); inline QChart *chart() const { return chart_view->chart(); } +signals: + void remove(); + private: void updateState(); void addData(const CanData &can_data, const Signal &sig); @@ -41,9 +53,8 @@ private: QString id; QString sig_name; - QChartView *chart_view = nullptr; + ChartView *chart_view = nullptr; LineMarker *line_marker = nullptr; - double line_marker_x = 0.0; QList vals; }; @@ -54,7 +65,6 @@ public: ChartsWidget(QWidget *parent = nullptr); void addChart(const QString &id, const QString &sig_name); void removeChart(const QString &id, const QString &sig_name); - void removeAll(); inline bool hasChart(const QString &id, const QString &sig_name) { return charts.find(id + sig_name) != charts.end(); } @@ -64,10 +74,13 @@ signals: private: void updateState(); - void updateDockButton(); + void updateTitleBar(); + void removeAll(); + bool eventFilter(QObject *obj, QEvent *event); QWidget *title_bar; QLabel *title_label; + QLabel *range_label; bool docking = true; QPushButton *dock_btn; QPushButton *reset_zoom_btn; diff --git a/tools/cabana/dbcmanager.cc b/tools/cabana/dbcmanager.cc new file mode 100644 index 0000000000..1cb6da7fb5 --- /dev/null +++ b/tools/cabana/dbcmanager.cc @@ -0,0 +1,117 @@ +#include "tools/cabana/dbcmanager.h" + +#include + +DBCManager::DBCManager(QObject *parent) : QObject(parent) {} + +DBCManager::~DBCManager() {} + +void DBCManager::open(const QString &dbc_file_name) { + dbc_name = dbc_file_name; + dbc = const_cast(dbc_lookup(dbc_name.toStdString())); + msg_map.clear(); + for (auto &msg : dbc->msgs) { + msg_map[msg.address] = &msg; + } + emit DBCFileChanged(); +} + +void save(const QString &dbc_file_name) { + // TODO: save DBC to file +} + +void DBCManager::updateMsg(const QString &id, const QString &name, uint32_t size) { + auto m = const_cast(msg(id)); + if (m) { + m->name = name.toStdString(); + m->size = size; + } else { + uint32_t address = addressFromId(id); + dbc->msgs.push_back({.address = address, .name = name.toStdString(), .size = size}); + msg_map[address] = &dbc->msgs.back(); + } + emit msgUpdated(id); +} + +void DBCManager::addSignal(const QString &id, const Signal &sig) { + if (Msg *m = const_cast(msg(id))) { + m->sigs.push_back(sig); + emit signalAdded(id, QString::fromStdString(sig.name)); + } +} + +void DBCManager::updateSignal(const QString &id, const QString &sig_name, const Signal &sig) { + if (Signal *s = const_cast(signal(id, sig_name))) { + *s = sig; + emit signalUpdated(id, sig_name); + } +} + +void DBCManager::removeSignal(const QString &id, const QString &sig_name) { + if (Msg *m = const_cast(msg(id))) { + auto it = std::find_if(m->sigs.begin(), m->sigs.end(), [=](auto &sig) { return sig_name == sig.name.c_str(); }); + if (it != m->sigs.end()) { + m->sigs.erase(it); + emit signalRemoved(id, sig_name); + } + } +} + +const Signal *DBCManager::signal(const QString &id, const QString &sig_name) const { + if (auto m = msg(id)) { + auto it = std::find_if(m->sigs.begin(), m->sigs.end(), [&](auto &s) { return sig_name == s.name.c_str(); }); + if (it != m->sigs.end()) + return &(*it); + } + return nullptr; +} + +uint32_t DBCManager::addressFromId(const QString &id) { + return id.mid(id.indexOf(':') + 1).toUInt(nullptr, 16); +} + +DBCManager *dbc() { + static DBCManager dbc_manager(nullptr); + return &dbc_manager; +} + +// helper functions + +static QVector BIG_ENDIAN_START_BITS = []() { + QVector ret; + for (int i = 0; i < 64; i++) + for (int j = 7; j >= 0; j--) + ret.push_back(j + i * 8); + return ret; +}(); + +int bigEndianStartBitsIndex(int start_bit) { + return BIG_ENDIAN_START_BITS[start_bit]; +} + +int bigEndianBitIndex(int index) { + return BIG_ENDIAN_START_BITS.indexOf(index); +} + +double get_raw_value(uint8_t *data, size_t data_size, const Signal &sig) { + int64_t val = 0; + + int i = sig.msb / 8; + int bits = sig.size; + while (i >= 0 && i < data_size && bits > 0) { + int lsb = (int)(sig.lsb / 8) == i ? sig.lsb : i * 8; + int msb = (int)(sig.msb / 8) == i ? sig.msb : (i + 1) * 8 - 1; + int size = msb - lsb + 1; + + uint64_t d = (data[i] >> (lsb - (i * 8))) & ((1ULL << size) - 1); + val |= d << (bits - size); + + bits -= size; + i = sig.is_little_endian ? i - 1 : i + 1; + } + if (sig.is_signed) { + val -= ((val >> (sig.size - 1)) & 0x1) ? (1ULL << sig.size) : 0; + } + double value = val * sig.factor + sig.offset; + return value; +} diff --git a/tools/cabana/dbcmanager.h b/tools/cabana/dbcmanager.h new file mode 100644 index 0000000000..06c071be82 --- /dev/null +++ b/tools/cabana/dbcmanager.h @@ -0,0 +1,51 @@ +#pragma once + +#include + +#include "opendbc/can/common_dbc.h" + +class DBCManager : public QObject { + Q_OBJECT + +public: + DBCManager(QObject *parent); + ~DBCManager(); + + void open(const QString &dbc_file_name); + void save(const QString &dbc_file_name); + + const Signal *signal(const QString &id, const QString &sig_name) const; + void addSignal(const QString &id, const Signal &sig); + void updateSignal(const QString &id, const QString &sig_name, const Signal &sig); + void removeSignal(const QString &id, const QString &sig_name); + + static uint32_t addressFromId(const QString &id); + inline static std::vector allDBCNames() { return get_dbc_names(); } + inline QString name() const { return dbc_name; } + + void updateMsg(const QString &id, const QString &name, uint32_t size); + inline const Msg *msg(const QString &id) const { return msg(addressFromId(id)); } + inline const Msg *msg(uint32_t address) const { + auto it = msg_map.find(address); + return it != msg_map.end() ? it->second : nullptr; + } + +signals: + void signalAdded(const QString &id, const QString &sig_name); + void signalRemoved(const QString &id, const QString &sig_name); + void signalUpdated(const QString &id, const QString &sig_name); + void msgUpdated(const QString &id); + void DBCFileChanged(); + +private: + QString dbc_name; + DBC *dbc = nullptr; + std::unordered_map msg_map; +}; + +// TODO: Add helper function in dbc.h +double get_raw_value(uint8_t *data, size_t data_size, const Signal &sig); +int bigEndianStartBitsIndex(int start_bit); +int bigEndianBitIndex(int index); + +DBCManager *dbc(); diff --git a/tools/cabana/detailwidget.cc b/tools/cabana/detailwidget.cc index 1b6552804e..7c1847230b 100644 --- a/tools/cabana/detailwidget.cc +++ b/tools/cabana/detailwidget.cc @@ -1,39 +1,29 @@ #include "tools/cabana/detailwidget.h" -#include #include #include #include +#include #include #include -#include - -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/widgets/scrollview.h" - -inline const QString &getColor(int i) { - static const QString SIGNAL_COLORS[] = {"#9FE2BF", "#40E0D0", "#6495ED", "#CCCCFF", "#FF7F50", "#FFBF00"}; - return SIGNAL_COLORS[i % std::size(SIGNAL_COLORS)]; -} // DetailWidget DetailWidget::DetailWidget(QWidget *parent) : QWidget(parent) { QVBoxLayout *main_layout = new QVBoxLayout(this); - name_label = new QLabel(this); - name_label->setStyleSheet("font-weight:bold;"); - name_label->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred); - name_label->setAlignment(Qt::AlignCenter); - main_layout->addWidget(name_label); - // title QHBoxLayout *title_layout = new QHBoxLayout(); + title_layout->addWidget(new QLabel("time:")); time_label = new QLabel(this); title_layout->addWidget(time_label); + time_label->setStyleSheet("font-weight:bold"); + title_layout->addStretch(); + name_label = new QLabel(this); + name_label->setStyleSheet("font-weight:bold;"); + title_layout->addWidget(name_label); title_layout->addStretch(); - edit_btn = new QPushButton(tr("Edit"), this); edit_btn->setVisible(false); title_layout->addWidget(edit_btn); @@ -41,79 +31,104 @@ DetailWidget::DetailWidget(QWidget *parent) : QWidget(parent) { // binary view binary_view = new BinaryView(this); - main_layout->addWidget(binary_view); + main_layout->addWidget(binary_view, 0, Qt::AlignTop); + + // signal header + signals_header = new QWidget(this); + QHBoxLayout *signals_header_layout = new QHBoxLayout(signals_header); + signals_header_layout->addWidget(new QLabel(tr("Signals"))); + signals_header_layout->addStretch(); + QPushButton *add_sig_btn = new QPushButton(tr("Add signal"), this); + signals_header_layout->addWidget(add_sig_btn); + signals_header->setVisible(false); + main_layout->addWidget(signals_header); // scroll area - QHBoxLayout *signals_layout = new QHBoxLayout(); - signals_layout->addWidget(new QLabel(tr("Signals"))); - signals_layout->addStretch(); - add_sig_btn = new QPushButton(tr("Add signal"), this); - add_sig_btn->setVisible(false); - signals_layout->addWidget(add_sig_btn); - main_layout->addLayout(signals_layout); - + scroll = new ScrollArea(this); QWidget *container = new QWidget(this); + container->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Maximum); QVBoxLayout *container_layout = new QVBoxLayout(container); signal_edit_layout = new QVBoxLayout(); signal_edit_layout->setSpacing(2); container_layout->addLayout(signal_edit_layout); - history_log = new HistoryLog(this); - container_layout->addWidget(history_log); - - QScrollArea *scroll = new QScrollArea(this); scroll->setWidget(container); scroll->setWidgetResizable(true); - scroll->setFrameShape(QFrame::NoFrame); scroll->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); - scroll->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Expanding); - main_layout->addWidget(scroll); + history_log = new HistoryLog(this); + main_layout->addWidget(history_log); + QObject::connect(add_sig_btn, &QPushButton::clicked, this, &DetailWidget::addSignal); QObject::connect(edit_btn, &QPushButton::clicked, this, &DetailWidget::editMsg); - QObject::connect(parser, &Parser::updated, this, &DetailWidget::updateState); + QObject::connect(can, &CANMessages::updated, this, &DetailWidget::updateState); } -void DetailWidget::setMsg(const CanData *c) { - can_data = c; - clearLayout(signal_edit_layout); - edit_btn->setVisible(true); +void DetailWidget::setMessage(const QString &message_id) { + msg_id = message_id; + for (auto f : signal_forms) { + f->deleteLater(); + } + signal_forms.clear(); - if (auto msg = parser->getMsg(can_data->address)) { - name_label->setText(msg->name.c_str()); - add_sig_btn->setVisible(true); + if (auto msg = dbc()->msg(msg_id)) { for (int i = 0; i < msg->sigs.size(); ++i) { - signal_edit_layout->addWidget(new SignalEdit(can_data->id, msg->sigs[i], getColor(i))); + auto form = new SignalEdit(i, msg_id, msg->sigs[i], getColor(i)); + signal_edit_layout->addWidget(form); + QObject::connect(form, &SignalEdit::showChart, this, &DetailWidget::showChart); + QObject::connect(form, &SignalEdit::showFormClicked, this, &DetailWidget::showForm); + signal_forms.push_back(form); } + name_label->setText(msg->name.c_str()); + signals_header->setVisible(true); } else { name_label->setText(tr("untitled")); - add_sig_btn->setVisible(false); + signals_header->setVisible(false); } + edit_btn->setVisible(true); - binary_view->setMsg(can_data); - history_log->clear(); + binary_view->setMessage(msg_id); + history_log->setMessage(msg_id); } void DetailWidget::updateState() { - if (!can_data) return; + time_label->setText(QString::number(can->currentSec(), 'f', 3)); + if (msg_id.isEmpty()) return; - time_label->setText(QString("time: %1").arg(can_data->ts, 0, 'f', 3)); - binary_view->setData(can_data->dat); + binary_view->updateState(); history_log->updateState(); } void DetailWidget::editMsg() { - EditMessageDialog dlg(can_data->id, this); + EditMessageDialog dlg(msg_id, this); if (dlg.exec()) { - setMsg(can_data); + setMessage(msg_id); } } void DetailWidget::addSignal() { - AddSignalDialog dlg(can_data->id, this); + AddSignalDialog dlg(msg_id, this); if (dlg.exec()) { - setMsg(can_data); + setMessage(msg_id); + } +} + +void DetailWidget::showForm() { + SignalEdit *sender = qobject_cast(QObject::sender()); + if (sender->isFormVisible()) { + sender->setFormVisible(false); + } else { + for (auto f : signal_forms) { + f->setFormVisible(f == sender); + if (f == sender) { + // scroll to header + QTimer::singleShot(0, [=]() { + const QPoint p = f->mapTo(scroll, QPoint(0, 0)); + scroll->verticalScrollBar()->setValue(p.y() + scroll->verticalScrollBar()->value()); + }); + } + } } } @@ -121,6 +136,7 @@ void DetailWidget::addSignal() { BinaryView::BinaryView(QWidget *parent) { QVBoxLayout *main_layout = new QVBoxLayout(this); + main_layout->setContentsMargins(0, 0, 0, 0); table = new QTableWidget(this); table->horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); table->horizontalHeader()->hide(); @@ -131,9 +147,10 @@ BinaryView::BinaryView(QWidget *parent) { setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Fixed); } -void BinaryView::setMsg(const CanData *can_data) { - const Msg *msg = parser->getMsg(can_data->address); - int row_count = msg ? msg->size : can_data->dat.size(); +void BinaryView::setMessage(const QString &message_id) { + msg_id = message_id; + const Msg *msg = dbc()->msg(msg_id); + int row_count = msg ? msg->size : can->lastMessage(msg_id).dat.size(); table->setRowCount(row_count); table->setColumnCount(9); @@ -151,8 +168,8 @@ void BinaryView::setMsg(const CanData *can_data) { } } + // set background color if (msg) { - // set background color for (int i = 0; i < msg->sigs.size(); ++i) { const auto &sig = msg->sigs[i]; int start = sig.is_little_endian ? sig.start_bit : bigEndianBitIndex(sig.start_bit); @@ -162,80 +179,44 @@ void BinaryView::setMsg(const CanData *can_data) { } } - setFixedHeight(table->rowHeight(0) * table->rowCount() + 25); + table->setFixedHeight(table->rowHeight(0) * table->rowCount() + table->horizontalHeader()->height() + 2); + updateState(); } -void BinaryView::setData(const QByteArray &binary) { - std::string s; - for (int j = 0; j < binary.size(); ++j) { - s += std::bitset<8>(binary[j]).to_string(); - } +void BinaryView::updateState() { + if (msg_id.isEmpty()) return; + + const auto &binary = can->lastMessage(msg_id).dat; setUpdatesEnabled(false); char hex[3] = {'\0'}; for (int i = 0; i < binary.size(); ++i) { for (int j = 0; j < 8; ++j) { - table->item(i, j)->setText(QChar(s[i * 8 + j])); + table->item(i, j)->setText(QChar((binary[i] >> (7 - j)) & 1 ? '1' : '0')); } - sprintf(&hex[0], "%02X", (unsigned char)binary[i]); + hex[0] = toHex(binary[i] >> 4); + hex[1] = toHex(binary[i] & 0xf); table->item(i, 8)->setText(hex); } setUpdatesEnabled(true); } -// HistoryLog - -HistoryLog::HistoryLog(QWidget *parent) : QWidget(parent) { - QVBoxLayout *main_layout = new QVBoxLayout(this); - QLabel *title = new QLabel("TIME BYTES"); - main_layout->addWidget(title); - - QVBoxLayout *message_layout = new QVBoxLayout(); - for (int i = 0; i < std::size(labels); ++i) { - labels[i] = new QLabel(); - labels[i]->setVisible(false); - message_layout->addWidget(labels[i]); - } - main_layout->addLayout(message_layout); - main_layout->addStretch(); -} - -void HistoryLog::updateState() { - int i = 0; - for (; i < parser->history_log.size(); ++i) { - const auto &c = parser->history_log[i]; - auto label = labels[i]; - label->setVisible(true); - label->setText(QString("%1 %2").arg(c.ts, 0, 'f', 3).arg(toHex(c.dat))); - } - - for (; i < std::size(labels); ++i) { - labels[i]->setVisible(false); - } -} - -void HistoryLog::clear() { - setUpdatesEnabled(false); - for (auto l : labels) l->setVisible(false); - setUpdatesEnabled(true); -} - // EditMessageDialog -EditMessageDialog::EditMessageDialog(const QString &id, QWidget *parent) : id(id), QDialog(parent) { +EditMessageDialog::EditMessageDialog(const QString &msg_id, QWidget *parent) : msg_id(msg_id), QDialog(parent) { setWindowTitle(tr("Edit message")); QVBoxLayout *main_layout = new QVBoxLayout(this); QFormLayout *form_layout = new QFormLayout(); - form_layout->addRow("ID", new QLabel(id)); + form_layout->addRow("ID", new QLabel(msg_id)); - auto msg = const_cast(parser->getMsg(id)); + const auto msg = dbc()->msg(msg_id); name_edit = new QLineEdit(this); name_edit->setText(msg ? msg->name.c_str() : "untitled"); form_layout->addRow(tr("Name"), name_edit); size_spin = new QSpinBox(this); - size_spin->setValue(msg ? msg->size : parser->can_msgs[id].dat.size()); + size_spin->setValue(msg ? msg->size : can->lastMessage(msg_id).dat.size()); form_layout->addRow(tr("Size"), size_spin); main_layout->addLayout(form_layout); @@ -243,22 +224,33 @@ EditMessageDialog::EditMessageDialog(const QString &id, QWidget *parent) : id(id auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); main_layout->addWidget(buttonBox); + setFixedWidth(parent->width() * 0.9); + connect(buttonBox, &QDialogButtonBox::accepted, this, &EditMessageDialog::save); connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); } void EditMessageDialog::save() { - if (size_spin->value() <= 0 || name_edit->text().isEmpty()) return; + const QString name = name_edit->text(); + if (size_spin->value() <= 0 || name_edit->text().isEmpty() || name == tr("untitled")) + return; - if (auto msg = const_cast(parser->getMsg(id))) { - msg->name = name_edit->text().toStdString(); - msg->size = size_spin->value(); - } else { - Msg m = {}; - m.address = Parser::addressFromId(id); - m.name = name_edit->text().toStdString(); - m.size = size_spin->value(); - parser->addNewMsg(m); - } + dbc()->updateMsg(msg_id, name, size_spin->value()); QDialog::accept(); } + +// ScrollArea + +bool ScrollArea::eventFilter(QObject *obj, QEvent *ev) { + if (obj == widget() && ev->type() == QEvent::Resize) { + int height = widget()->height() + 4; + setMinimumHeight(height > 480 ? 480 : height); + setMaximumHeight(height); + } + return QScrollArea::eventFilter(obj, ev); +} + +void ScrollArea::setWidget(QWidget *w) { + QScrollArea::setWidget(w); + w->installEventFilter(this); +} diff --git a/tools/cabana/detailwidget.h b/tools/cabana/detailwidget.h index b2e7cbf3b7..99fe321012 100644 --- a/tools/cabana/detailwidget.h +++ b/tools/cabana/detailwidget.h @@ -3,35 +3,28 @@ #include #include #include +#include #include #include #include #include "opendbc/can/common.h" #include "opendbc/can/common_dbc.h" -#include "tools/cabana/parser.h" +#include "tools/cabana/canmessages.h" +#include "tools/cabana/dbcmanager.h" +#include "tools/cabana/historylog.h" #include "tools/cabana/signaledit.h" -class HistoryLog : public QWidget { - Q_OBJECT - -public: - HistoryLog(QWidget *parent); - void clear(); - void updateState(); - -private: - QLabel *labels[LOG_SIZE] = {}; -}; - class BinaryView : public QWidget { Q_OBJECT public: BinaryView(QWidget *parent); - void setMsg(const CanData *can_data); - void setData(const QByteArray &binary); + void setMessage(const QString &message_id); + void updateState(); +private: + QString msg_id; QTableWidget *table; }; @@ -39,14 +32,23 @@ class EditMessageDialog : public QDialog { Q_OBJECT public: - EditMessageDialog(const QString &id, QWidget *parent); + EditMessageDialog(const QString &msg_id, QWidget *parent); protected: void save(); + QString msg_id; QLineEdit *name_edit; QSpinBox *size_spin; - QString id; +}; + +class ScrollArea : public QScrollArea { + Q_OBJECT + +public: + ScrollArea(QWidget *parent) : QScrollArea(parent) {} + bool eventFilter(QObject *obj, QEvent *ev) override; + void setWidget(QWidget *w); }; class DetailWidget : public QWidget { @@ -54,17 +56,26 @@ class DetailWidget : public QWidget { public: DetailWidget(QWidget *parent); - void setMsg(const CanData *c); + void setMessage(const QString &message_id); + +signals: + void showChart(const QString &msg_id, const QString &sig_name); + +private slots: + void showForm(); private: - void updateState(); void addSignal(); void editMsg(); + void updateState(); - const CanData *can_data = nullptr; + QString msg_id; QLabel *name_label, *time_label; - QPushButton *edit_btn, *add_sig_btn; + QPushButton *edit_btn; QVBoxLayout *signal_edit_layout; + QWidget *signals_header; + QList signal_forms; HistoryLog *history_log; BinaryView *binary_view; + ScrollArea *scroll; }; diff --git a/tools/cabana/historylog.cc b/tools/cabana/historylog.cc new file mode 100644 index 0000000000..494e281cb1 --- /dev/null +++ b/tools/cabana/historylog.cc @@ -0,0 +1,91 @@ +#include "tools/cabana/historylog.h" + +#include +#include + +QVariant HistoryLogModel::data(const QModelIndex &index, int role) const { + if (role == Qt::DisplayRole) { + const auto &can_msgs = can->messages(msg_id); + if (index.row() < can_msgs.size()) { + const auto &can_data = can_msgs[index.row()]; + auto msg = dbc()->msg(msg_id); + if (msg && index.column() < msg->sigs.size()) { + return get_raw_value((uint8_t *)can_data.dat.begin(), can_data.dat.size(), msg->sigs[index.column()]); + } else { + return toHex(can_data.dat); + } + } + } + return {}; +} + +void HistoryLogModel::setMessage(const QString &message_id) { + beginResetModel(); + msg_id = message_id; + const auto msg = dbc()->msg(message_id); + column_count = msg && !msg->sigs.empty() ? msg->sigs.size() : 1; + row_count = 0; + endResetModel(); + + updateState(); +} + +QVariant HistoryLogModel::headerData(int section, Qt::Orientation orientation, int role) const { + if (orientation == Qt::Horizontal) { + auto msg = dbc()->msg(msg_id); + if (msg && section < msg->sigs.size()) { + if (role == Qt::BackgroundRole) { + return QBrush(QColor(getColor(section))); + } else if (role == Qt::DisplayRole || role == Qt::ToolTipRole) { + return QString::fromStdString(msg->sigs[section].name); + } + } + } else if (role == Qt::DisplayRole) { + const auto &can_msgs = can->messages(msg_id); + if (section < can_msgs.size()) { + return QString::number(can_msgs[section].ts, 'f', 2); + } + } + return {}; +} + +void HistoryLogModel::updateState() { + if (msg_id.isEmpty()) return; + + const auto &can_msgs = can->messages(msg_id); + int prev_row_count = row_count; + row_count = can_msgs.size(); + int delta = row_count - prev_row_count; + if (delta > 0) { + beginInsertRows({}, prev_row_count, row_count - 1); + endInsertRows(); + } else if (delta < 0) { + beginRemoveRows({}, row_count, prev_row_count - 1); + endRemoveRows(); + } + if (row_count > 0) { + emit dataChanged(index(0, 0), index(row_count - 1, column_count - 1)); + emit headerDataChanged(Qt::Vertical, 0, row_count - 1); + } +} + +HistoryLog::HistoryLog(QWidget *parent) : QWidget(parent) { + QVBoxLayout *main_layout = new QVBoxLayout(this); + main_layout->setContentsMargins(0, 0, 0, 0); + model = new HistoryLogModel(this); + table = new QTableView(this); + table->setModel(model); + table->horizontalHeader()->setStretchLastSection(true); + table->setEditTriggers(QAbstractItemView::NoEditTriggers); + table->setStyleSheet("QTableView::item { border:0px; padding-left:5px; padding-right:5px; }"); + table->verticalHeader()->setStyleSheet("QHeaderView::section {padding-left: 5px; padding-right: 5px;min-width:40px;}"); + main_layout->addWidget(table); +} + +void HistoryLog::setMessage(const QString &message_id) { + model->setMessage(message_id); +} + +void HistoryLog::updateState() { + model->updateState(); +} diff --git a/tools/cabana/historylog.h b/tools/cabana/historylog.h new file mode 100644 index 0000000000..f3a9046bfa --- /dev/null +++ b/tools/cabana/historylog.h @@ -0,0 +1,37 @@ +#pragma once + +#include + +#include "tools/cabana/canmessages.h" +#include "tools/cabana/dbcmanager.h" + +class HistoryLogModel : public QAbstractTableModel { +Q_OBJECT + +public: + HistoryLogModel(QObject *parent) : QAbstractTableModel(parent) {} + void setMessage(const QString &message_id); + void updateState(); + QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const override; + int columnCount(const QModelIndex &parent = QModelIndex()) const override { return column_count; } + QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const; + int rowCount(const QModelIndex &parent = QModelIndex()) const override { return row_count; } + +private: + QString msg_id; + int row_count = 0; + int column_count = 0; +}; + +class HistoryLog : public QWidget { + Q_OBJECT + +public: + HistoryLog(QWidget *parent); + void setMessage(const QString &message_id); + void updateState(); + +private: + QTableView *table; + HistoryLogModel *model; +}; diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc index 49e6cd2cca..6fa24ea21d 100644 --- a/tools/cabana/mainwin.cc +++ b/tools/cabana/mainwin.cc @@ -1,5 +1,6 @@ #include "tools/cabana/mainwin.h" +#include #include #include #include @@ -30,13 +31,15 @@ MainWindow::MainWindow() : QWidget() { h_layout->addWidget(right_container); - QObject::connect(messages_widget, &MessagesWidget::msgChanged, detail_widget, &DetailWidget::setMsg); + QObject::connect(messages_widget, &MessagesWidget::msgSelectionChanged, detail_widget, &DetailWidget::setMessage); + QObject::connect(detail_widget, &DetailWidget::showChart, charts_widget, &ChartsWidget::addChart); QObject::connect(charts_widget, &ChartsWidget::dock, this, &MainWindow::dockCharts); } void MainWindow::dockCharts(bool dock) { charts_widget->setUpdatesEnabled(false); if (dock && floating_window) { + floating_window->removeEventFilter(charts_widget); r_layout->addWidget(charts_widget); floating_window->deleteLater(); floating_window = nullptr; @@ -44,7 +47,7 @@ void MainWindow::dockCharts(bool dock) { floating_window = new QWidget(nullptr); floating_window->setLayout(new QVBoxLayout()); floating_window->layout()->addWidget(charts_widget); - floating_window->setWindowFlags(Qt::WindowTitleHint | Qt::WindowMaximizeButtonHint | Qt::WindowMinimizeButtonHint); + floating_window->installEventFilter(charts_widget); floating_window->setMinimumSize(QGuiApplication::primaryScreen()->size() / 2); floating_window->showMaximized(); } diff --git a/tools/cabana/mainwin.h b/tools/cabana/mainwin.h index bcd15e4d8e..b0d7c273da 100644 --- a/tools/cabana/mainwin.h +++ b/tools/cabana/mainwin.h @@ -3,7 +3,6 @@ #include "tools/cabana/chartswidget.h" #include "tools/cabana/detailwidget.h" #include "tools/cabana/messageswidget.h" -#include "tools/cabana/parser.h" #include "tools/cabana/videowidget.h" class MainWindow : public QWidget { diff --git a/tools/cabana/messageswidget.cc b/tools/cabana/messageswidget.cc index 7de3507b3d..eaf84fbace 100644 --- a/tools/cabana/messageswidget.cc +++ b/tools/cabana/messageswidget.cc @@ -1,19 +1,32 @@ #include "tools/cabana/messageswidget.h" #include +#include #include +#include #include +#include #include +#include "tools/cabana/dbcmanager.h" + MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) { QVBoxLayout *main_layout = new QVBoxLayout(this); + // DBC file selector QHBoxLayout *dbc_file_layout = new QHBoxLayout(); QComboBox *combo = new QComboBox(this); - auto dbc_names = get_dbc_names(); + auto dbc_names = dbc()->allDBCNames(); for (const auto &name : dbc_names) { combo->addItem(QString::fromStdString(name)); } + combo->setEditable(true); + combo->setCurrentText(QString()); + combo->setInsertPolicy(QComboBox::NoInsert); + combo->completer()->setCompletionMode(QCompleter::PopupCompletion); + QFont font; + font.setBold(true); + combo->lineEdit()->setFont(font); dbc_file_layout->addWidget(combo); dbc_file_layout->addStretch(); @@ -21,73 +34,104 @@ MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) { dbc_file_layout->addWidget(save_btn); main_layout->addLayout(dbc_file_layout); - filter = new QLineEdit(this); + // message filter + QLineEdit *filter = new QLineEdit(this); filter->setPlaceholderText(tr("filter messages")); main_layout->addWidget(filter); - table_widget = new QTableWidget(this); + // message table + table_widget = new QTableView(this); + model = new MessageListModel(this); + QSortFilterProxyModel *proxy_model = new QSortFilterProxyModel(this); + proxy_model->setSourceModel(model); + proxy_model->setFilterCaseSensitivity(Qt::CaseInsensitive); + proxy_model->setDynamicSortFilter(false); + table_widget->setModel(proxy_model); table_widget->setSelectionBehavior(QAbstractItemView::SelectRows); table_widget->setSelectionMode(QAbstractItemView::SingleSelection); table_widget->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Expanding); - table_widget->setColumnCount(4); + table_widget->setSortingEnabled(true); table_widget->setColumnWidth(0, 250); table_widget->setColumnWidth(1, 80); table_widget->setColumnWidth(2, 80); - table_widget->setHorizontalHeaderLabels({tr("Name"), tr("ID"), tr("Count"), tr("Bytes")}); table_widget->horizontalHeader()->setStretchLastSection(true); + table_widget->verticalHeader()->hide(); + table_widget->sortByColumn(0, Qt::AscendingOrder); main_layout->addWidget(table_widget); - QObject::connect(parser, &Parser::updated, this, &MessagesWidget::updateState); + // signals/slots + QObject::connect(filter, &QLineEdit::textChanged, proxy_model, &QSortFilterProxyModel::setFilterFixedString); + QObject::connect(can, &CANMessages::updated, model, &MessageListModel::updateState); + QObject::connect(combo, SIGNAL(activated(const QString &)), SLOT(dbcSelectionChanged(const QString &))); QObject::connect(save_btn, &QPushButton::clicked, [=]() { // TODO: save DBC to file }); - QObject::connect(combo, &QComboBox::currentTextChanged, [=](const QString &dbc) { - parser->openDBC(dbc); - }); - QObject::connect(table_widget, &QTableWidget::itemSelectionChanged, [=]() { - const CanData *c = &(parser->can_msgs[table_widget->selectedItems()[1]->text()]); - parser->setCurrentMsg(c->id); - emit msgChanged(c); + QObject::connect(table_widget->selectionModel(), &QItemSelectionModel::currentChanged, [=](const QModelIndex ¤t, const QModelIndex &previous) { + if (current.isValid()) { + emit msgSelectionChanged(table_widget->model()->data(current, Qt::UserRole).toString()); + } }); // For test purpose combo->setCurrentText("toyota_nodsu_pt_generated"); } -void MessagesWidget::updateState() { - auto getTableItem = [=](int row, int col) -> QTableWidgetItem * { - auto item = table_widget->item(row, col); - if (!item) { - item = new QTableWidgetItem(); - item->setFlags(item->flags() ^ Qt::ItemIsEditable); - table_widget->setItem(row, col, item); - } - return item; - }; +void MessagesWidget::dbcSelectionChanged(const QString &dbc_file) { + dbc()->open(dbc_file); + // update detailwidget + auto current = table_widget->selectionModel()->currentIndex(); + if (current.isValid()) { + emit msgSelectionChanged(table_widget->model()->data(current, Qt::UserRole).toString()); + } +} - table_widget->setRowCount(parser->can_msgs.size()); - int i = 0; - QString name, untitled = tr("untitled"); - const QString filter_str = filter->text(); - for (const auto &[_, c] : parser->can_msgs) { - if (auto msg = parser->getMsg(c.address)) { - name = msg->name.c_str(); - } else { - name = untitled; - } - if (!filter_str.isEmpty() && !name.contains(filter_str, Qt::CaseInsensitive)) { - table_widget->hideRow(i++); - continue; +// MessageListModel + +QVariant MessageListModel::headerData(int section, Qt::Orientation orientation, int role) const { + if (orientation == Qt::Horizontal && role == Qt::DisplayRole) + return (QString[]){"Name", "ID", "Count", "Bytes"}[section]; + else if (orientation == Qt::Vertical && role == Qt::DisplayRole) { + // return QString::number(section); + } + return {}; +} + +QVariant MessageListModel::data(const QModelIndex &index, int role) const { + if (role == Qt::DisplayRole) { + auto it = std::next(can->can_msgs.begin(), index.row()); + if (it != can->can_msgs.end() && !it.value().empty()) { + const auto &d = it.value().front(); + const QString &msg_id = it.key(); + switch (index.column()) { + case 0: { + auto msg = dbc()->msg(msg_id); + QString name = msg ? msg->name.c_str() : "untitled"; + return name; + } + case 1: return msg_id; + case 2: return can->counters[msg_id]; + case 3: return toHex(d.dat); + } } + } else if (role == Qt::UserRole) { + return std::next(can->can_msgs.begin(), index.row()).key(); + } + return {}; +} - getTableItem(i, 0)->setText(name); - getTableItem(i, 1)->setText(c.id); - getTableItem(i, 2)->setText(QString::number(parser->counters[c.id])); - getTableItem(i, 3)->setText(toHex(c.dat)); - table_widget->showRow(i); - i++; +void MessageListModel::updateState() { + int prev_row_count = row_count; + row_count = can->can_msgs.size(); + int delta = row_count - prev_row_count; + if (delta > 0) { + beginInsertRows({}, prev_row_count, row_count - 1); + endInsertRows(); + } else if (delta < 0) { + beginRemoveRows({}, row_count, prev_row_count - 1); + endRemoveRows(); } - if (table_widget->currentRow() == -1) { - table_widget->selectRow(0); + + if (row_count > 0) { + emit dataChanged(index(0, 0), index(row_count - 1, 3)); } } diff --git a/tools/cabana/messageswidget.h b/tools/cabana/messageswidget.h index 1dbb4a1af3..f6487ba2bd 100644 --- a/tools/cabana/messageswidget.h +++ b/tools/cabana/messageswidget.h @@ -1,24 +1,38 @@ #pragma once -#include -#include -#include +#include +#include -#include "tools/cabana/parser.h" +#include "tools/cabana/canmessages.h" + +class MessageListModel : public QAbstractTableModel { +Q_OBJECT + +public: + MessageListModel(QObject *parent) : QAbstractTableModel(parent) {} + QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const override; + int columnCount(const QModelIndex &parent = QModelIndex()) const override { return 4; } + QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const; + int rowCount(const QModelIndex &parent = QModelIndex()) const override { return row_count; } + void updateState(); + +private: + int row_count = 0; +}; class MessagesWidget : public QWidget { Q_OBJECT - public: +public: MessagesWidget(QWidget *parent); - public slots: - void updateState(); +public slots: + void dbcSelectionChanged(const QString &dbc_file); - signals: - void msgChanged(const CanData *id); +signals: + void msgSelectionChanged(const QString &message_id); - protected: - QLineEdit *filter; - QTableWidget *table_widget; +protected: + QTableView *table_widget; + MessageListModel *model; }; diff --git a/tools/cabana/parser.cc b/tools/cabana/parser.cc deleted file mode 100644 index f4bacbb86d..0000000000 --- a/tools/cabana/parser.cc +++ /dev/null @@ -1,181 +0,0 @@ -#include "tools/cabana/parser.h" - -#include - -#include "cereal/messaging/messaging.h" - -Parser *parser = nullptr; - -static bool event_filter(const Event *e, void *opaque) { - Parser *p = (Parser*)opaque; - return p->eventFilter(e); -} - -Parser::Parser(QObject *parent) : QObject(parent) { - parser = this; - - qRegisterMetaType>(); - QObject::connect(this, &Parser::received, this, &Parser::process, Qt::QueuedConnection); -} - -Parser::~Parser() { - replay->stop(); -} - -bool Parser::loadRoute(const QString &route, const QString &data_dir, bool use_qcam) { - replay = new Replay(route, {"can", "roadEncodeIdx"}, {}, nullptr, use_qcam ? REPLAY_FLAG_QCAMERA : 0, data_dir, this); - replay->installEventFilter(event_filter, this); - QObject::connect(replay, &Replay::segmentsMerged, this, &Parser::segmentsMerged); - if (replay->load()) { - replay->start(); - return true; - } - return false; -} - -void Parser::openDBC(const QString &name) { - dbc_name = name; - dbc = const_cast(dbc_lookup(name.toStdString())); - counters.clear(); - msg_map.clear(); - for (auto &msg : dbc->msgs) { - msg_map[msg.address] = &msg; - } -} - -void Parser::process(std::vector msgs) { - static double prev_update_ts = 0; - - for (const auto &can_data : msgs) { - can_msgs[can_data.id] = can_data; - ++counters[can_data.id]; - - if (can_data.id == current_msg_id) { - while (history_log.size() >= LOG_SIZE) { - history_log.pop_back(); - } - history_log.push_front(can_data); - } - } - double now = millis_since_boot(); - if ((now - prev_update_ts) > 1000.0 / FPS) { - prev_update_ts = now; - emit updated(); - } - - if (current_sec < begin_sec || current_sec > end_sec) { - // loop replay in selected range. - seekTo(begin_sec); - } -} - -bool Parser::eventFilter(const Event *event) { - // drop packets when the GUI thread is calling seekTo. to make sure the current_sec is accurate. - if (!seeking && event->which == cereal::Event::Which::CAN) { - current_sec = (event->mono_time - replay->routeStartTime()) / (double)1e9; - - auto can = event->event.getCan(); - msgs_buf.clear(); - msgs_buf.reserve(can.size()); - - for (const auto &c : can) { - CanData &data = msgs_buf.emplace_back(); - data.address = c.getAddress(); - data.bus_time = c.getBusTime(); - data.source = c.getSrc(); - data.dat.append((char *)c.getDat().begin(), c.getDat().size()); - data.id = QString("%1:%2").arg(data.source).arg(data.address, 1, 16); - data.ts = current_sec; - } - emit received(msgs_buf); - } - return true; -} - -void Parser::seekTo(double ts) { - seeking = true; - replay->seekTo(ts, false); - seeking = false; -} - -void Parser::addNewMsg(const Msg &msg) { - dbc->msgs.push_back(msg); - msg_map[dbc->msgs.back().address] = &dbc->msgs.back(); -} - -void Parser::removeSignal(const QString &id, const QString &sig_name) { - Msg *msg = const_cast(getMsg(id)); - if (!msg) return; - - auto it = std::find_if(msg->sigs.begin(), msg->sigs.end(), [=](auto &sig) { return sig_name == sig.name.c_str(); }); - if (it != msg->sigs.end()) { - msg->sigs.erase(it); - emit signalRemoved(id, sig_name); - } -} - -uint32_t Parser::addressFromId(const QString &id) { - return id.mid(id.indexOf(':') + 1).toUInt(nullptr, 16); -} - -const Signal *Parser::getSig(const QString &id, const QString &sig_name) { - if (auto msg = getMsg(id)) { - auto it = std::find_if(msg->sigs.begin(), msg->sigs.end(), [&](auto &s) { return sig_name == s.name.c_str(); }); - if (it != msg->sigs.end()) { - return &(*it); - } - } - return nullptr; -} - -void Parser::setRange(double min, double max) { - if (begin_sec != min || end_sec != max) { - begin_sec = min; - end_sec = max; - is_zoomed = begin_sec != event_begin_sec || end_sec != event_end_sec; - emit rangeChanged(min, max); - } -} - -void Parser::segmentsMerged() { - auto events = replay->events(); - if (!events || events->empty()) return; - - auto it = std::find_if(events->begin(), events->end(), [=](const Event *e) { return e->which == cereal::Event::Which::CAN; }); - event_begin_sec = it == events->end() ? 0 : ((*it)->mono_time - replay->routeStartTime()) / (double)1e9; - event_end_sec = double(events->back()->mono_time - replay->routeStartTime()) / 1e9; - if (!is_zoomed) { - begin_sec = event_begin_sec; - end_sec = event_end_sec; - } - emit eventsMerged(); -} - -void Parser::resetRange() { - setRange(event_begin_sec, event_end_sec); -} - -void Parser::setCurrentMsg(const QString &id) { - current_msg_id = id; - history_log.clear(); -} - -// helper functions - -static QVector BIG_ENDIAN_START_BITS = []() { - QVector ret; - for (int i = 0; i < 64; i++) { - for (int j = 7; j >= 0; j--) { - ret.push_back(j + i * 8); - } - } - return ret; -}(); - -int bigEndianStartBitsIndex(int start_bit) { - return BIG_ENDIAN_START_BITS[start_bit]; -} - -int bigEndianBitIndex(int index) { - return BIG_ENDIAN_START_BITS.indexOf(index); -} diff --git a/tools/cabana/parser.h b/tools/cabana/parser.h deleted file mode 100644 index 1632fcf6a6..0000000000 --- a/tools/cabana/parser.h +++ /dev/null @@ -1,95 +0,0 @@ -#pragma once - -#include -#include - -#include -#include -#include - -#include "opendbc/can/common.h" -#include "opendbc/can/common_dbc.h" -#include "tools/replay/replay.h" - -const int FPS = 20; -const static int LOG_SIZE = 25; - -struct CanData { - QString id; - double ts; - uint32_t address; - uint16_t bus_time; - uint8_t source; - QByteArray dat; -}; - -class Parser : public QObject { - Q_OBJECT - -public: - Parser(QObject *parent); - ~Parser(); - static uint32_t addressFromId(const QString &id); - bool eventFilter(const Event *event); - bool loadRoute(const QString &route, const QString &data_dir, bool use_qcam); - void openDBC(const QString &name); - void saveDBC(const QString &name) {} - void addNewMsg(const Msg &msg); - void removeSignal(const QString &id, const QString &sig_name); - void seekTo(double ts); - const Signal *getSig(const QString &id, const QString &sig_name); - void setRange(double min, double max); - void resetRange(); - void setCurrentMsg(const QString &id); - inline std::pair range() const { return {begin_sec, end_sec}; } - inline double currentSec() const { return current_sec; } - inline bool isZoomed() const { return is_zoomed; } - inline const Msg *getMsg(const QString &id) { return getMsg(addressFromId(id)); } - inline const Msg *getMsg(uint32_t address) { - auto it = msg_map.find(address); - return it != msg_map.end() ? it->second : nullptr; - } - -signals: - void showPlot(const QString &id, const QString &name); - void hidePlot(const QString &id, const QString &name); - void signalRemoved(const QString &id, const QString &sig_name); - void eventsMerged(); - void rangeChanged(double min, double max); - void received(std::vector can); - void updated(); - -public: - Replay *replay = nullptr; - QHash counters; - std::map can_msgs; - QList history_log; - -protected: - void process(std::vector can); - void segmentsMerged(); - - std::atomic current_sec = 0.; - std::atomic seeking = false; - QString dbc_name; - double begin_sec = 0; - double end_sec = 0; - double event_begin_sec = 0; - double event_end_sec = 0; - bool is_zoomed = false; - DBC *dbc = nullptr; - std::map msg_map; - QString current_msg_id; - std::vector msgs_buf; -}; - -Q_DECLARE_METATYPE(std::vector); - -// TODO: Add helper function in dbc.h -int bigEndianStartBitsIndex(int start_bit); -int bigEndianBitIndex(int index); -inline QString toHex(const QByteArray &dat) { - return dat.toHex(' ').toUpper(); -} - -extern Parser *parser; diff --git a/tools/cabana/signaledit.cc b/tools/cabana/signaledit.cc index c214adab09..3f48450195 100644 --- a/tools/cabana/signaledit.cc +++ b/tools/cabana/signaledit.cc @@ -3,13 +3,12 @@ #include #include #include -#include #include #include // SignalForm -SignalForm::SignalForm(const Signal &sig, QWidget *parent) : QWidget(parent) { +SignalForm::SignalForm(const Signal &sig, QWidget *parent) : start_bit(sig.start_bit), QWidget(parent) { QFormLayout *form_layout = new QFormLayout(this); name = new QLineEdit(sig.name.c_str()); @@ -33,7 +32,8 @@ SignalForm::SignalForm(const Signal &sig, QWidget *parent) : QWidget(parent) { sign->setCurrentIndex(sig.is_signed ? 0 : 1); form_layout->addRow(tr("sign"), sign); - factor = new QSpinBox(); + factor = new QDoubleSpinBox(); + factor->setDecimals(3); factor->setValue(sig.factor); form_layout->addRow(tr("Factor"), factor); @@ -46,9 +46,11 @@ SignalForm::SignalForm(const Signal &sig, QWidget *parent) : QWidget(parent) { form_layout->addRow(tr("Unit"), unit); comment = new QLineEdit(); form_layout->addRow(tr("Comment"), comment); - min_val = new QSpinBox(); + min_val = new QDoubleSpinBox(); + factor->setDecimals(3); form_layout->addRow(tr("Minimum value"), min_val); - max_val = new QSpinBox(); + max_val = new QDoubleSpinBox(); + factor->setDecimals(3); form_layout->addRow(tr("Maximum value"), max_val); val_desc = new QLineEdit(); form_layout->addRow(tr("Value descriptions"), val_desc); @@ -56,11 +58,11 @@ SignalForm::SignalForm(const Signal &sig, QWidget *parent) : QWidget(parent) { std::optional SignalForm::getSignal() { Signal sig = {}; + sig.start_bit = start_bit; sig.name = name->text().toStdString(); sig.size = size->text().toInt(); sig.offset = offset->text().toDouble(); sig.factor = factor->text().toDouble(); - sig.msb = msb->text().toInt(); sig.is_signed = sign->currentIndex() == 0; sig.is_little_endian = endianness->currentIndex() == 0; if (sig.is_little_endian) { @@ -75,30 +77,32 @@ std::optional SignalForm::getSignal() { // SignalEdit -SignalEdit::SignalEdit(const QString &id, const Signal &sig, const QString &color, QWidget *parent) : id(id), name_(sig.name.c_str()), QWidget(parent) { +SignalEdit::SignalEdit(int index, const QString &id, const Signal &sig, const QString &color, QWidget *parent) + : id(id), name_(sig.name.c_str()), QWidget(parent) { QVBoxLayout *main_layout = new QVBoxLayout(this); main_layout->setContentsMargins(0, 0, 0, 0); // title QHBoxLayout *title_layout = new QHBoxLayout(); - QLabel *icon = new QLabel(">"); + icon = new QLabel(">"); + icon->setFixedSize(15, 30); icon->setStyleSheet("font-weight:bold"); title_layout->addWidget(icon); title = new ElidedLabel(this); - title->setText(sig.name.c_str()); + title->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::MinimumExpanding); + title->setText(QString("%1. %2").arg(index + 1).arg(sig.name.c_str())); title->setStyleSheet(QString("font-weight:bold; color:%1").arg(color)); title_layout->addWidget(title); - title_layout->addStretch(); plot_btn = new QPushButton("📈"); plot_btn->setToolTip(tr("Show Plot")); plot_btn->setFixedSize(30, 30); - QObject::connect(plot_btn, &QPushButton::clicked, [=]() { emit parser->showPlot(id, name_); }); + QObject::connect(plot_btn, &QPushButton::clicked, [=]() { emit showChart(id, name_); }); title_layout->addWidget(plot_btn); main_layout->addLayout(title_layout); - edit_container = new QWidget(this); - QVBoxLayout *v_layout = new QVBoxLayout(edit_container); + form_container = new QWidget(this); + QVBoxLayout *v_layout = new QVBoxLayout(form_container); form = new SignalForm(sig, this); v_layout->addWidget(form); @@ -110,24 +114,27 @@ SignalEdit::SignalEdit(const QString &id, const Signal &sig, const QString &colo h->addWidget(save_btn); v_layout->addLayout(h); - edit_container->setVisible(false); - main_layout->addWidget(edit_container); + form_container->setVisible(false); + main_layout->addWidget(form_container); + + QFrame* hline = new QFrame(); + hline->setFrameShape(QFrame::HLine); + hline->setFrameShadow(QFrame::Sunken); + main_layout->addWidget(hline); QObject::connect(remove_btn, &QPushButton::clicked, this, &SignalEdit::remove); QObject::connect(save_btn, &QPushButton::clicked, this, &SignalEdit::save); - QObject::connect(title, &ElidedLabel::clicked, [=]() { - edit_container->isVisible() ? edit_container->hide() : edit_container->show(); - icon->setText(edit_container->isVisible() ? "▼" : ">"); - }); + QObject::connect(title, &ElidedLabel::clicked, this, &SignalEdit::showFormClicked); +} + +void SignalEdit::setFormVisible(bool visible) { + form_container->setVisible(visible); + icon->setText(visible ? "▼" : ">"); } void SignalEdit::save() { - if (auto sig = const_cast(parser->getSig(id, name_))) { - if (auto s = form->getSignal()) { - *sig = *s; - // TODO: reset the chart for sig - } - } + if (auto s = form->getSignal()) + dbc()->updateSignal(id, name_, *s); } void SignalEdit::remove() { @@ -137,7 +144,7 @@ void SignalEdit::remove() { msgbox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel); msgbox.setDefaultButton(QMessageBox::Cancel); if (msgbox.exec()) { - parser->removeSignal(id, name_); + dbc()->removeSignal(id, name_); deleteLater(); } } @@ -145,19 +152,19 @@ void SignalEdit::remove() { // AddSignalDialog AddSignalDialog::AddSignalDialog(const QString &id, QWidget *parent) : QDialog(parent) { - setWindowTitle(tr("Add signal to %1").arg(parser->getMsg(id)->name.c_str())); + setWindowTitle(tr("Add signal to %1").arg(dbc()->msg(id)->name.c_str())); QVBoxLayout *main_layout = new QVBoxLayout(this); Signal sig = {.name = "untitled"}; auto form = new SignalForm(sig, this); main_layout->addWidget(form); auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); main_layout->addWidget(buttonBox); + setFixedWidth(parent->width() * 0.9); + connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); connect(buttonBox, &QDialogButtonBox::accepted, [=]() { - if (auto msg = const_cast(parser->getMsg(id))) { - if (auto signal = form->getSignal()) { - msg->sigs.push_back(*signal); - } + if (auto signal = form->getSignal()) { + dbc()->addSignal(id, *signal); } QDialog::accept(); }); diff --git a/tools/cabana/signaledit.h b/tools/cabana/signaledit.h index b8140cc93b..00c13948b7 100644 --- a/tools/cabana/signaledit.h +++ b/tools/cabana/signaledit.h @@ -4,12 +4,15 @@ #include #include +#include #include #include #include #include "selfdrive/ui/qt/widgets/controls.h" -#include "tools/cabana/parser.h" + +#include "tools/cabana/canmessages.h" +#include "tools/cabana/dbcmanager.h" class SignalForm : public QWidget { Q_OBJECT @@ -19,17 +22,25 @@ public: std::optional getSignal(); QLineEdit *name, *unit, *comment, *val_desc; - QSpinBox *size, *msb, *lsb, *factor, *offset, *min_val, *max_val; + QSpinBox *size, *msb, *lsb, *offset; + QDoubleSpinBox *factor, *min_val, *max_val; QComboBox *sign, *endianness; + int start_bit = 0; }; class SignalEdit : public QWidget { Q_OBJECT public: - SignalEdit(const QString &id, const Signal &sig, const QString &color, QWidget *parent = nullptr); + SignalEdit(int index, const QString &id, const Signal &sig, const QString &color, QWidget *parent = nullptr); + void setFormVisible(bool show); + inline bool isFormVisible() const { return form_container->isVisible(); } void save(); +signals: + void showChart(const QString &msg_id, const QString &sig_name); + void showFormClicked(); + protected: void remove(); @@ -38,8 +49,9 @@ protected: QPushButton *plot_btn; ElidedLabel *title; SignalForm *form; - QWidget *edit_container; + QWidget *form_container; QPushButton *remove_btn; + QLabel *icon; }; class AddSignalDialog : public QDialog { diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc index 957747584c..193a6f8788 100644 --- a/tools/cabana/videowidget.cc +++ b/tools/cabana/videowidget.cc @@ -6,11 +6,10 @@ #include #include #include +#include #include #include -#include "tools/cabana/parser.h" - inline QString formatTime(int seconds) { return QDateTime::fromTime_t(seconds).toString(seconds > 60 * 60 ? "hh::mm::ss" : "mm::ss"); } @@ -25,18 +24,17 @@ VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) { // slider controls QHBoxLayout *slider_layout = new QHBoxLayout(); - time_label = new QLabel("00:00"); + QLabel *time_label = new QLabel("00:00"); slider_layout->addWidget(time_label); slider = new Slider(this); slider->setSingleStep(0); slider->setMinimum(0); - slider->setMaximum(parser->replay->totalSeconds() * 1000); + slider->setMaximum(can->totalSeconds() * 1000); slider_layout->addWidget(slider); - total_time_label = new QLabel(formatTime(parser->replay->totalSeconds())); - slider_layout->addWidget(total_time_label); - + end_time_label = new QLabel(formatTime(can->totalSeconds())); + slider_layout->addWidget(end_time_label); main_layout->addLayout(slider_layout); // btn controls @@ -50,51 +48,39 @@ VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) { for (float speed : {0.1, 0.5, 1., 2.}) { QPushButton *btn = new QPushButton(QString("%1x").arg(speed), this); btn->setCheckable(true); - QObject::connect(btn, &QPushButton::clicked, [=]() { parser->replay->setSpeed(speed); }); + QObject::connect(btn, &QPushButton::clicked, [=]() { can->setSpeed(speed); }); control_layout->addWidget(btn); group->addButton(btn); if (speed == 1.0) btn->setChecked(true); } - main_layout->addLayout(control_layout); - setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); - QObject::connect(parser, &Parser::rangeChanged, this, &VideoWidget::rangeChanged); - QObject::connect(parser, &Parser::updated, this, &VideoWidget::updateState); - QObject::connect(slider, &QSlider::sliderMoved, [=]() { time_label->setText(formatTime(slider->value() / 1000)); }); - QObject::connect(slider, &QSlider::sliderReleased, [this]() { setPosition(slider->value()); }); - QObject::connect(slider, &Slider::setPosition, this, &VideoWidget::setPosition); + setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); + QObject::connect(can, &CANMessages::rangeChanged, this, &VideoWidget::rangeChanged); + QObject::connect(can, &CANMessages::updated, this, &VideoWidget::updateState); + QObject::connect(slider, &QSlider::sliderReleased, [this]() { can->seekTo(slider->value() / 1000.0); }); + QObject::connect(slider, &QSlider::valueChanged, [=](int value) { time_label->setText(formatTime(value / 1000)); }); QObject::connect(play, &QPushButton::clicked, [=]() { - bool is_paused = parser->replay->isPaused(); + bool is_paused = can->isPaused(); play->setText(is_paused ? "⏸" : "▶"); - parser->replay->pause(!is_paused); + can->pause(!is_paused); }); } -void VideoWidget::setPosition(int value) { - time_label->setText(formatTime(value / 1000.0)); - parser->seekTo(value / 1000.0); -} - void VideoWidget::rangeChanged(double min, double max) { - if (!parser->isZoomed()) { + if (!can->isZoomed()) { min = 0; - max = parser->replay->totalSeconds(); + max = can->totalSeconds(); } - time_label->setText(formatTime(min)); - total_time_label->setText(formatTime(max)); + end_time_label->setText(formatTime(max)); slider->setMinimum(min * 1000); slider->setMaximum(max * 1000); - slider->setValue(parser->currentSec() * 1000); } void VideoWidget::updateState() { - if (!slider->isSliderDown()) { - double current_sec = parser->currentSec(); - time_label->setText(formatTime(current_sec)); - slider->setValue(current_sec * 1000); - } + if (!slider->isSliderDown()) + slider->setValue(can->currentSec() * 1000); } // Slider @@ -102,7 +88,7 @@ Slider::Slider(QWidget *parent) : QSlider(Qt::Horizontal, parent) { QTimer *timer = new QTimer(this); timer->setInterval(2000); timer->callOnTimeout([this]() { - timeline = parser->replay->getTimeline(); + timeline = can->getTimeline(); update(); }); timer->start(); @@ -110,7 +96,7 @@ Slider::Slider(QWidget *parent) : QSlider(Qt::Horizontal, parent) { void Slider::sliderChange(QAbstractSlider::SliderChange change) { if (change == QAbstractSlider::SliderValueChange) { - qreal x = width() * ((value() - minimum()) / double(maximum() - minimum())); + int x = width() * ((value() - minimum()) / double(maximum() - minimum())); if (x != slider_x) { slider_x = x; update(); @@ -121,45 +107,34 @@ void Slider::sliderChange(QAbstractSlider::SliderChange change) { } void Slider::paintEvent(QPaintEvent *ev) { - auto getPaintRange = [this](double begin, double end) -> std::pair { - double total_sec = maximum() - minimum(); - int start_pos = ((std::max((double)minimum(), (double)begin) - minimum()) / total_sec) * width(); - int end_pos = ((std::min((double)maximum(), (double)end) - minimum()) / total_sec) * width(); - return {start_pos, end_pos}; - }; + static const QColor colors[] = { + [(int)TimelineType::None] = QColor(111, 143, 175), + [(int)TimelineType::Engaged] = QColor(0, 163, 108), + [(int)TimelineType::UserFlag] = Qt::white, + [(int)TimelineType::AlertInfo] = Qt::green, + [(int)TimelineType::AlertWarning] = QColor(255, 195, 0), + [(int)TimelineType::AlertCritical] = QColor(199, 0, 57)}; QPainter p(this); - const int v_margin = 2; - p.fillRect(rect().adjusted(0, v_margin, 0, -v_margin), QColor(111, 143, 175)); - + QRect r = rect().adjusted(0, 4, 0, -4); + p.fillRect(r, colors[(int)TimelineType::None]); + double min = minimum() / 1000.0; + double max = maximum() / 1000.0; for (auto [begin, end, type] : timeline) { - begin *= 1000; - end *= 1000; - if (begin > maximum() || end < minimum()) continue; - - if (type == TimelineType::Engaged) { - auto [start_pos, end_pos] = getPaintRange(begin, end); - p.fillRect(QRect(start_pos, v_margin, end_pos - start_pos, height() - v_margin * 2), QColor(0, 163, 108)); - } + if (begin > max || end < min) + continue; + r.setLeft(((std::max(min, (double)begin) - min) / (max - min)) * width()); + r.setRight(((std::min(max, (double)end) - min) / (max - min)) * width()); + p.fillRect(r, colors[(int)type]); } - for (auto [begin, end, type] : timeline) { - begin *= 1000; - end *= 1000; - if (type == TimelineType::Engaged || begin > maximum() || end < minimum()) continue; - - auto [start_pos, end_pos] = getPaintRange(begin, end); - if (type == TimelineType::UserFlag) { - p.fillRect(QRect(start_pos, height() - v_margin - 3, end_pos - start_pos, 3), Qt::white); - } else { - QColor color(Qt::green); - if (type != TimelineType::AlertInfo) - color = type == TimelineType::AlertWarning ? QColor(255, 195, 0) : QColor(199, 0, 57); - - p.fillRect(QRect(start_pos, height() - v_margin - 3, end_pos - start_pos, 3), color); - } - } - p.setPen(QPen(QColor(88, 24, 69), 3)); - p.drawLine(QPoint{slider_x, 0}, QPoint{slider_x, height()}); + + QStyleOptionSlider opt; + opt.initFrom(this); + opt.minimum = minimum(); + opt.maximum = maximum(); + opt.subControls = QStyle::SC_SliderHandle; + opt.sliderPosition = value(); + style()->drawComplexControl(QStyle::CC_Slider, &opt, &p); } void Slider::mousePressEvent(QMouseEvent *e) { @@ -167,6 +142,6 @@ void Slider::mousePressEvent(QMouseEvent *e) { if (e->button() == Qt::LeftButton && !isSliderDown()) { int value = minimum() + ((maximum() - minimum()) * e->x()) / width(); setValue(value); - emit setPosition(value); + emit sliderReleased(); } } diff --git a/tools/cabana/videowidget.h b/tools/cabana/videowidget.h index 060565d322..e80e3b48f9 100644 --- a/tools/cabana/videowidget.h +++ b/tools/cabana/videowidget.h @@ -5,24 +5,19 @@ #include #include "selfdrive/ui/qt/widgets/cameraview.h" -#include "tools/replay/replay.h" +#include "tools/cabana/canmessages.h" class Slider : public QSlider { Q_OBJECT public: Slider(QWidget *parent); - void mousePressEvent(QMouseEvent* e) override; + void mousePressEvent(QMouseEvent *e) override; void sliderChange(QAbstractSlider::SliderChange change) override; - -signals: - void setPosition(int value); - -private: - void paintEvent(QPaintEvent *ev) override; - std::vector> timeline; + void paintEvent(QPaintEvent *ev) override; int slider_x = -1; + std::vector> timeline; }; class VideoWidget : public QWidget { @@ -34,9 +29,8 @@ public: protected: void rangeChanged(double min, double max); void updateState(); - void setPosition(int value); CameraViewWidget *cam_widget; - QLabel *time_label, *total_time_label; + QLabel *end_time_label; Slider *slider; }; diff --git a/tools/replay/main.cc b/tools/replay/main.cc index d3d6894877..40dace0c91 100644 --- a/tools/replay/main.cc +++ b/tools/replay/main.cc @@ -4,8 +4,6 @@ #include "tools/replay/consoleui.h" #include "tools/replay/replay.h" -const QString DEMO_ROUTE = "4cf7a6ad03080c90|2021-09-29--13-46-36"; - int main(int argc, char *argv[]) { QCoreApplication app(argc, argv); diff --git a/tools/replay/replay.h b/tools/replay/replay.h index 725bd1a27e..fbb36bd1ed 100644 --- a/tools/replay/replay.h +++ b/tools/replay/replay.h @@ -7,6 +7,8 @@ #include "tools/replay/camera.h" #include "tools/replay/route.h" +const QString DEMO_ROUTE = "4cf7a6ad03080c90|2021-09-29--13-46-36"; + // one segment uses about 100M of memory constexpr int FORWARD_SEGS = 5; diff --git a/tools/replay/tests/test_replay.cc b/tools/replay/tests/test_replay.cc index d6482c3ca2..5b61b6b6f2 100644 --- a/tools/replay/tests/test_replay.cc +++ b/tools/replay/tests/test_replay.cc @@ -9,7 +9,6 @@ #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"; const std::string TEST_RLOG_CHECKSUM = "5b966d4bb21a100a8c4e59195faeb741b975ccbe268211765efd1763d892bfb3"; From 47b19ff14891947bc5db02f3378b5eceba08ee85 Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Wed, 12 Oct 2022 16:59:39 -0400 Subject: [PATCH 023/101] VW PQ: Volkswagen Sharan Mk2 / SEAT Alhambra Mk2 (#25839) * initial Sharan support * placeholder torque data * oops * add route * min speeds and PQ default delay --- selfdrive/car/tests/routes.py | 1 + selfdrive/car/torque_data/override.yaml | 1 + selfdrive/car/volkswagen/interface.py | 7 +++++++ selfdrive/car/volkswagen/values.py | 19 ++++++++++++++++++- 4 files changed, 27 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 82c0614493..ac56cc106b 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -175,6 +175,7 @@ routes = [ CarTestRoute("4d134e099430fba2|2021-03-26--00-26-06", VOLKSWAGEN.PASSAT_MK8), CarTestRoute("3cfdec54aa035f3f|2022-07-19--23-45-10", VOLKSWAGEN.PASSAT_NMS), CarTestRoute("0cd0b7f7e31a3853|2021-11-03--19-30-22", VOLKSWAGEN.POLO_MK6), + CarTestRoute("064d1816e448f8eb|2022-09-29--15-32-34", VOLKSWAGEN.SHARAN_MK2), CarTestRoute("7d82b2f3a9115f1f|2021-10-21--15-39-42", VOLKSWAGEN.TAOS_MK1), CarTestRoute("2744c89a8dda9a51|2021-07-24--21-28-06", VOLKSWAGEN.TCROSS_MK1), CarTestRoute("2cef8a0b898f331a|2021-03-25--20-13-57", VOLKSWAGEN.TIGUAN_MK2), diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index b5d1a31193..889eeffb25 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -30,6 +30,7 @@ CHEVROLET BOLT EUV 2022: [2.0, 2.0, 0.05] CHEVROLET SILVERADO 1500 2020: [1.9, 1.9, 0.112] CHEVROLET EQUINOX 2019: [2.0, 2.0, 0.05] VOLKSWAGEN PASSAT NMS: [2.5, 2.5, 0.1] +VOLKSWAGEN SHARAN 2ND GEN: [2.5, 2.5, 0.1] HYUNDAI TUCSON HYBRID 4TH GEN: [2.5, 2.5, 0.0] # Dashcam or fallback configured as ideal car diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 821eef44c7..4724fe81bf 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -127,6 +127,13 @@ class CarInterface(CarInterfaceBase): ret.mass = 1230 + STD_CARGO_KG ret.wheelbase = 2.55 + elif candidate == CAR.SHARAN_MK2: + ret.mass = 1639 + STD_CARGO_KG + ret.wheelbase = 2.92 + ret.minEnableSpeed = 30 * CV.KPH_TO_MS + ret.minSteerSpeed = 50 * CV.KPH_TO_MS + ret.steerActuatorDelay = 0.2 + elif candidate == CAR.TAOS_MK1: ret.mass = 1498 + STD_CARGO_KG ret.wheelbase = 2.69 diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index bdd1b5089d..e0bcd02600 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -116,6 +116,7 @@ class CAR: PASSAT_MK8 = "VOLKSWAGEN PASSAT 8TH GEN" # Chassis 3G, Mk8 VW Passat and variants PASSAT_NMS = "VOLKSWAGEN PASSAT NMS" # Chassis A3, North America/China/Mideast NMS Passat, incl. facelift POLO_MK6 = "VOLKSWAGEN POLO 6TH GEN" # Chassis AW, Mk6 VW Polo + SHARAN_MK2 = "VOLKSWAGEN SHARAN 2ND GEN" # Chassis 7N, Mk2 Volkswagen Sharan and SEAT Alhambra TAOS_MK1 = "VOLKSWAGEN TAOS 1ST GEN" # Chassis B2, Mk1 VW Taos and Tharu TCROSS_MK1 = "VOLKSWAGEN T-CROSS 1ST GEN" # Chassis C1, Mk1 VW T-Cross SWB and LWB variants TIGUAN_MK2 = "VOLKSWAGEN TIGUAN 2ND GEN" # Chassis AD/BW, Mk2 VW Tiguan and variants @@ -135,7 +136,7 @@ class CAR: SKODA_OCTAVIA_MK3 = "SKODA OCTAVIA 3RD GEN" # Chassis NE, Mk3 Skoda Octavia and variants -PQ_CARS = {CAR.PASSAT_NMS} +PQ_CARS = {CAR.PASSAT_NMS, CAR.SHARAN_MK2} DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict("vw_mqb_2010", None)) @@ -206,6 +207,10 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = { VWCarInfo("Volkswagen Polo 2020-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), VWCarInfo("Volkswagen Polo GTI 2020-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), ], + CAR.SHARAN_MK2: [ + VWCarInfo("Volkswagen Sharan 2018-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), + VWCarInfo("SEAT Alhambra 2018-20", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), + ], CAR.TAOS_MK1: VWCarInfo("Volkswagen Taos 2022", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), CAR.TCROSS_MK1: VWCarInfo("Volkswagen T-Cross 2021", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), CAR.TIGUAN_MK2: VWCarInfo("Volkswagen Tiguan 2019-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), @@ -625,6 +630,18 @@ FW_VERSIONS = { b'\xf1\x872Q0907572R \xf1\x890372', ], }, + CAR.SHARAN_MK2: { + # TODO: Sharan Mk2 EPS and DQ250 auto trans both require KWP2000 support for fingerprinting + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906016HE\xf1\x894635', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x877N0959655D \xf1\x890016\xf1\x82\x0801100705----10--', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0153', + ], + }, CAR.TAOS_MK1: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8704E906027NJ\xf1\x891445', From ac88ad871a9fba9076eb4d02a57e34ad34839f59 Mon Sep 17 00:00:00 2001 From: Jason Shuler Date: Wed, 12 Oct 2022 17:02:01 -0400 Subject: [PATCH 024/101] GM: disable checks on loopback bus (#26015) * disabling checks on loopback bus * Apply suggestions from code review Co-authored-by: Shane Smiskol --- selfdrive/car/gm/carstate.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index 11c521e863..a5f89c58b0 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -177,9 +177,7 @@ class CarState(CarStateBase): ] checks = [ - ("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 + ("ASCMLKASteeringCmd", 0), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus.LOOPBACK) + return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus.LOOPBACK, enforce_checks=False) From 03f06b0e32c823df2321ca4e6b0077b5e112f734 Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Wed, 12 Oct 2022 14:03:44 -0700 Subject: [PATCH 025/101] ci: don't cancel concurrent workflows for master branch (#26047) don't cancel for master branch --- .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 9c38ba0cbc..ab70b8e7ef 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -8,7 +8,7 @@ on: concurrency: group: ${{ github.workflow }}-${{ github.ref }}-${{ github.event_name }} - cancel-in-progress: true + cancel-in-progress: ${{ github.ref != 'refs/heads/master' }} env: BASE_IMAGE: openpilot-base From 3c0904a18f4acb852193de9956965df2520104d1 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 12 Oct 2022 14:22:40 -0700 Subject: [PATCH 026/101] EV6 longitudinal (#26023) * ev6 long * update refs --- panda | 2 +- selfdrive/car/hyundai/carcontroller.py | 94 ++++++++++--------- selfdrive/car/hyundai/carstate.py | 40 +++++---- selfdrive/car/hyundai/hyundaicanfd.py | 109 +++++++++++++++++++++-- selfdrive/car/hyundai/interface.py | 66 ++++++++------ selfdrive/test/process_replay/ref_commit | 2 +- 6 files changed, 219 insertions(+), 94 deletions(-) diff --git a/panda b/panda index d68b1b0a98..ffb3109e28 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit d68b1b0a98d5cefad438180e3c2ffcdcbcffdd76 +Subproject commit ffb3109e28296cc86f1892c4e0690856e28fb35a diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 2b0d6b9648..bcbab2ab94 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -52,17 +52,15 @@ class CarController: self.apply_steer_last = 0 self.car_fingerprint = CP.carFingerprint self.last_button_frame = 0 - self.accel = 0 def update(self, CC, CS): actuators = CC.actuators hud_control = CC.hudControl - # Steering Torque - - # These cars have significantly more torque than most HKG. Limit to 70% of max. + # steering torque steer = actuators.steer if self.CP.carFingerprint in (CAR.KONA, CAR.KONA_EV, CAR.KONA_HEV, CAR.KONA_EV_2022): + # these cars have significantly more torque than most HKG; limit to 70% of max 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) @@ -72,48 +70,66 @@ class CarController: self.apply_steer_last = apply_steer + # accel + longitudinal + accel = clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) + stopping = actuators.longControlState == LongCtrlState.stopping + set_speed_in_units = hud_control.setSpeed * (CV.MS_TO_KPH if CS.is_metric else CV.MS_TO_MPH) + + # HUD messages sys_warning, sys_state, left_lane_warning, right_lane_warning = process_hud_alert(CC.enabled, self.car_fingerprint, hud_control) can_sends = [] + # *** common hyundai stuff *** + + # tester present - w/ no response (keeps relevant ECU disabled) + if self.frame % 100 == 0 and self.CP.openpilotLongitudinalControl: + addr, bus = 0x7d0, 0 + if self.CP.flags & HyundaiFlags.CANFD_HDA2.value: + addr, bus = 0x730, 5 + can_sends.append([addr, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", bus]) + + # CAN-FD platforms if self.CP.carFingerprint in CANFD_CAR: + hda2 = self.CP.flags & HyundaiFlags.CANFD_HDA2 + hda2_long = hda2 and self.CP.openpilotLongitudinalControl + # steering control - can_sends.append(hyundaicanfd.create_lkas(self.packer, self.CP, CC.enabled, CC.latActive, apply_steer)) + can_sends.extend(hyundaicanfd.create_steering_messages(self.packer, self.CP, CC.enabled, CC.latActive, apply_steer)) - # block LFA on HDA2 - if self.frame % 5 == 0 and (self.CP.flags & HyundaiFlags.CANFD_HDA2): + # disable LFA on HDA2 + if self.frame % 5 == 0 and hda2: can_sends.append(hyundaicanfd.create_cam_0x2a4(self.packer, CS.cam_0x2a4)) # LFA and HDA icons - if self.frame % 2 == 0 and not (self.CP.flags & HyundaiFlags.CANFD_HDA2): - can_sends.append(hyundaicanfd.create_lfahda_cluster(self.packer, CC.enabled)) + if self.frame % 5 == 0 and (not hda2 or hda2_long): + can_sends.append(hyundaicanfd.create_lfahda_cluster(self.packer, self.CP, CC.enabled)) - # button presses - if (self.frame - self.last_button_frame) * DT_CTRL > 0.25: - # cruise cancel - if CC.cruiseControl.cancel: - if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: - can_sends.append(hyundaicanfd.create_cruise_info(self.packer, CS.cruise_info_copy, True)) - self.last_button_frame = self.frame - else: - for _ in range(20): - can_sends.append(hyundaicanfd.create_buttons(self.packer, CS.buttons_counter+1, Buttons.CANCEL)) - self.last_button_frame = self.frame - - # cruise standstill resume - elif CC.cruiseControl.resume: - if not (self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS): - for _ in range(20): - can_sends.append(hyundaicanfd.create_buttons(self.packer, CS.buttons_counter+1, Buttons.RES_ACCEL)) - self.last_button_frame = self.frame - else: - - # tester present - w/ no response (keeps radar disabled) if self.CP.openpilotLongitudinalControl: - if self.frame % 100 == 0: - can_sends.append([0x7D0, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", 0]) - + can_sends.extend(hyundaicanfd.create_adrv_messages(self.packer, self.frame)) + if self.frame % 2 == 0: + can_sends.append(hyundaicanfd.create_acc_control(self.packer, self.CP, CC.enabled, accel, stopping, CC.cruiseControl.override, + set_speed_in_units)) + else: + # button presses + if (self.frame - self.last_button_frame) * DT_CTRL > 0.25: + # cruise cancel + if CC.cruiseControl.cancel: + if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: + self.last_button_frame = self.frame + else: + for _ in range(20): + can_sends.append(hyundaicanfd.create_buttons(self.packer, CS.buttons_counter+1, Buttons.CANCEL)) + self.last_button_frame = self.frame + + # cruise standstill resume + elif CC.cruiseControl.resume: + if not (self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS): + for _ in range(20): + can_sends.append(hyundaicanfd.create_buttons(self.packer, CS.buttons_counter+1, Buttons.RES_ACCEL)) + self.last_button_frame = self.frame + else: # Count up to MAX_ANGLE_FRAMES, at which point we need to cut torque to avoid a steering fault if CC.latActive and abs(CS.out.steeringAngleDeg) >= MAX_ANGLE: self.angle_limit_counter += 1 @@ -143,18 +159,10 @@ class CarController: self.last_button_frame = self.frame if self.frame % 2 == 0 and self.CP.openpilotLongitudinalControl: - accel = actuators.accel - - #TODO unclear if this is needed + # TODO: unclear if this is needed jerk = 3.0 if actuators.longControlState == LongCtrlState.pid else 1.0 - - accel = clip(accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) - - stopping = actuators.longControlState == LongCtrlState.stopping - set_speed_in_units = hud_control.setSpeed * (CV.MS_TO_MPH if CS.clu11["CF_Clu_SPEED_UNIT"] == 1 else CV.MS_TO_KPH) can_sends.extend(hyundaican.create_acc_commands(self.packer, CC.enabled, accel, jerk, int(self.frame / 2), hud_control.leadVisible, set_speed_in_units, stopping, CC.cruiseControl.override)) - self.accel = accel # 20 Hz LFA MFA message if self.frame % 5 == 0 and self.car_fingerprint in (CAR.SONATA, CAR.PALISADE, CAR.IONIQ, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV_2021, @@ -173,7 +181,7 @@ class CarController: new_actuators = actuators.copy() new_actuators.steer = apply_steer / self.params.STEER_MAX - new_actuators.accel = self.accel + new_actuators.accel = accel self.frame += 1 return new_actuators, can_sends diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 4d60afe1fd..4c2650c19f 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -30,6 +30,7 @@ class CarState(CarStateBase): else: # preferred and elect gear methods use same definition self.shifter_values = can_define.dv["LVR12"]["CF_Lvr_Gear"] + self.is_metric = False self.brake_error = False self.buttons_counter = 0 @@ -45,8 +46,8 @@ class CarState(CarStateBase): ret = car.CarState.new_message() cp_cruise = cp_cam if self.CP.carFingerprint in CAMERA_SCC_CAR else cp - is_metric = cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"] == 0 - speed_conv = CV.KPH_TO_MS if is_metric else CV.MPH_TO_MS + self.is_metric = cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"] == 0 + speed_conv = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS ret.doorOpen = any([cp.vl["CGW1"]["CF_Gway_DrvDrSw"], cp.vl["CGW1"]["CF_Gway_AstDrSw"], cp.vl["CGW2"]["CF_Gway_RLDrSw"], cp.vl["CGW2"]["CF_Gway_RRDrSw"]]) @@ -69,7 +70,7 @@ class CarState(CarStateBase): self.cluster_speed_counter = 0 # mimic how dash converts to imperial - if not is_metric: + if not self.is_metric: self.cluster_speed = math.floor(self.cluster_speed * CV.KPH_TO_MPH + CV.KPH_TO_MPH) ret.vEgoCluster = self.cluster_speed * speed_conv @@ -187,16 +188,19 @@ class CarState(CarStateBase): ret.cruiseState.available = True ret.cruiseState.enabled = cp.vl["SCC1"]["CRUISE_ACTIVE"] == 1 - cp_cruise_info = cp if self.CP.flags & HyundaiFlags.CANFD_HDA2 else cp_cam - speed_factor = CV.MPH_TO_MS if cp.vl["CLUSTER_INFO"]["DISTANCE_UNIT"] == 1 else CV.KPH_TO_MS - ret.cruiseState.speed = cp_cruise_info.vl["CRUISE_INFO"]["SET_SPEED"] * speed_factor - ret.cruiseState.standstill = cp_cruise_info.vl["CRUISE_INFO"]["CRUISE_STANDSTILL"] == 1 + self.is_metric = cp.vl["CLUSTER_INFO"]["DISTANCE_UNIT"] != 1 + if not self.CP.openpilotLongitudinalControl: + speed_factor = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS + cp_cruise_info = cp if self.CP.flags & HyundaiFlags.CANFD_HDA2 else cp_cam + ret.cruiseState.speed = cp_cruise_info.vl["CRUISE_INFO"]["SET_SPEED"] * speed_factor + ret.cruiseState.standstill = cp_cruise_info.vl["CRUISE_INFO"]["CRUISE_STANDSTILL"] == 1 cruise_btn_msg = "CRUISE_BUTTONS_ALT" if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else "CRUISE_BUTTONS" + self.prev_cruise_buttons = self.cruise_buttons[-1] self.cruise_buttons.extend(cp.vl_all[cruise_btn_msg]["CRUISE_BUTTONS"]) self.main_buttons.extend(cp.vl_all[cruise_btn_msg]["ADAPTIVE_CRUISE_MAIN_BTN"]) self.buttons_counter = cp.vl[cruise_btn_msg]["COUNTER"] - self.cruise_info_copy = copy.copy(cp_cruise_info.vl["CRUISE_INFO"]) + self.cruise_info_copy = {} if self.CP.flags & HyundaiFlags.CANFD_HDA2: self.cam_0x2a4 = copy.copy(cp_cam.vl["CAM_0x2a4"]) @@ -448,13 +452,18 @@ class CarState(CarStateBase): signals += [ ("ACCELERATOR_PEDAL", "ACCELERATOR"), ("GEAR", "ACCELERATOR"), - ("SET_SPEED", "CRUISE_INFO"), - ("CRUISE_STANDSTILL", "CRUISE_INFO"), ] checks += [ - ("CRUISE_INFO", 50), ("ACCELERATOR", 100), ] + if not CP.openpilotLongitudinalControl: + signals += [ + ("SET_SPEED", "CRUISE_INFO"), + ("CRUISE_STANDSTILL", "CRUISE_INFO"), + ] + checks += [ + ("CRUISE_INFO", 50), + ] else: signals += [ ("ACCELERATOR_PEDAL", "ACCELERATOR_ALT"), @@ -478,17 +487,14 @@ class CarState(CarStateBase): ("CRUISE_MAIN", "CRUISE_INFO"), ("CRUISE_STATUS", "CRUISE_INFO"), ("CRUISE_INACTIVE", "CRUISE_INFO"), - ("NEW_SIGNAL_2", "CRUISE_INFO"), + ("ZEROS_9", "CRUISE_INFO"), ("CRUISE_STANDSTILL", "CRUISE_INFO"), - ("NEW_SIGNAL_3", "CRUISE_INFO"), - ("BYTE11", "CRUISE_INFO"), + ("ZEROS_5", "CRUISE_INFO"), + ("DISTANCE_SETTING", "CRUISE_INFO"), ("SET_SPEED", "CRUISE_INFO"), ("NEW_SIGNAL_4", "CRUISE_INFO"), ] - signals += [(f"BYTE{i}", "CRUISE_INFO") for i in range(3, 7)] - signals += [(f"BYTE{i}", "CRUISE_INFO") for i in range(13, 31)] - checks = [ ("CRUISE_INFO", 50), ] diff --git a/selfdrive/car/hyundai/hyundaicanfd.py b/selfdrive/car/hyundai/hyundaicanfd.py index a53be7627d..9d4e4d4e0d 100644 --- a/selfdrive/car/hyundai/hyundaicanfd.py +++ b/selfdrive/car/hyundai/hyundaicanfd.py @@ -1,7 +1,17 @@ from selfdrive.car.hyundai.values import HyundaiFlags -def create_lkas(packer, CP, enabled, lat_active, apply_steer): +def get_e_can_bus(CP): + # On the CAN-FD platforms, the LKAS camera is on both A-CAN and E-CAN. HDA2 cars + # have a a different harness than the HDA1 and non-HDA variants in order to split + # a different bus, since the steering is done by different ECUs. + return 5 if CP.flags & HyundaiFlags.CANFD_HDA2 else 4 + + +def create_steering_messages(packer, CP, enabled, lat_active, apply_steer): + + ret = [] + values = { "LKA_MODE": 2, "LKA_ICON": 2 if enabled else 1, @@ -14,8 +24,14 @@ def create_lkas(packer, CP, enabled, lat_active, apply_steer): "NEW_SIGNAL_2": 0, } - msg = "LKAS" if CP.flags & HyundaiFlags.CANFD_HDA2 else "LFA" - return packer.make_can_msg(msg, 4, values) + if CP.flags & HyundaiFlags.CANFD_HDA2: + if CP.openpilotLongitudinalControl: + ret.append(packer.make_can_msg("LFA", 5, values)) + ret.append(packer.make_can_msg("LKAS", 4, values)) + else: + ret.append(packer.make_can_msg("LFA", 4, values)) + + return ret def create_cam_0x2a4(packer, camera_values): camera_values.update({ @@ -36,11 +52,92 @@ def create_cruise_info(packer, cruise_info_copy, cancel): if cancel: values["CRUISE_STATUS"] = 0 values["CRUISE_INACTIVE"] = 1 - return packer.make_can_msg("CRUISE_INFO", 4, values) + return packer.make_can_msg("CRUISE_INFO", 5, values) -def create_lfahda_cluster(packer, enabled): +def create_lfahda_cluster(packer, CP, enabled): values = { "HDA_ICON": 1 if enabled else 0, "LFA_ICON": 2 if enabled else 0, } - return packer.make_can_msg("LFAHDA_CLUSTER", 4, values) + return packer.make_can_msg("LFAHDA_CLUSTER", get_e_can_bus(CP), values) + + +def create_acc_control(packer, CP, enabled, accel, stopping, gas_override, set_speed): + cruise_status = 0 if not enabled else (4 if gas_override else 2) + if not enabled or gas_override: + accel = 0 + values = { + "CRUISE_STATUS": cruise_status, + "CRUISE_INACTIVE": 0 if enabled else 1, + "CRUISE_MAIN": 1, + "CRUISE_STANDSTILL": 0, + "STOP_REQ": 1 if stopping else 0, + "ACCEL_REQ": accel, + "ACCEL_REQ2": accel, + "SET_SPEED": set_speed, + "DISTANCE_SETTING": 4, + + "ACC_ObjDist": 1, + "ObjValid": 1, + "OBJ_STATUS": 2, + "SET_ME_2": 0x2, + "SET_ME_3": 0x3, + "SET_ME_TMP_64": 0x64, + + "NEW_SIGNAL_9": 2, + "NEW_SIGNAL_10": 4, + } + + return packer.make_can_msg("CRUISE_INFO", get_e_can_bus(CP), values) + + + +def create_adrv_messages(packer, frame): + # messages needed to car happy after disabling + # the ADAS Driving ECU to do longitudinal control + + ret = [] + + values = { + } + ret.append(packer.make_can_msg("ADRV_0x51", 4, values)) + + if frame % 2 == 0: + values = { + 'AEB_SETTING': 0x1, # show AEB disabled icon + 'SET_ME_2': 0x2, + 'SET_ME_FF': 0xff, + 'SET_ME_FC': 0xfc, + 'SET_ME_9': 0x9, + } + ret.append(packer.make_can_msg("ADRV_0x160", 5, values)) + + if frame % 5 == 0: + values = { + 'SET_ME_1C': 0x1c, + 'SET_ME_FF': 0xff, + 'SET_ME_TMP_F': 0xf, + 'SET_ME_TMP_F_2': 0xf, + } + ret.append(packer.make_can_msg("ADRV_0x1ea", 5, values)) + + values = { + 'SET_ME_E1': 0xe1, + 'SET_ME_3A': 0x3a, + } + ret.append(packer.make_can_msg("ADRV_0x200", 5, values)) + + if frame % 20 == 0: + values = { + 'SET_ME_15': 0x15, + } + ret.append(packer.make_can_msg("ADRV_0x345", 5, values)) + + if frame % 100 == 0: + values = { + 'SET_ME_22': 0x22, + 'SET_ME_41': 0x41, + } + ret.append(packer.make_can_msg("ADRV_0x1da", 5, values)) + + return ret diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 2d960ed17f..024d7498fa 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -27,31 +27,24 @@ class CarInterface(CarInterfaceBase): ret.carName = "hyundai" ret.radarOffCan = RADAR_START_ADDR not in fingerprint[1] or DBC[ret.carFingerprint]["radar"] is None - # WARNING: disabling radar also disables AEB (and we show the same warning on the instrument cluster as if you manually disabled AEB) - ret.experimentalLongitudinalAvailable = candidate not in (LEGACY_SAFETY_MODE_CAR | CAMERA_SCC_CAR | CANFD_CAR) - ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable - - ret.pcmCruise = not ret.openpilotLongitudinalControl - # 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 CANFD_CAR: + # detect HDA2 with LKAS message + if 0x50 in fingerprint[6]: + ret.flags |= HyundaiFlags.CANFD_HDA2.value + else: + # non-HDA2 + if 0x1cf not in fingerprint[4]: + ret.flags |= HyundaiFlags.CANFD_ALT_BUTTONS.value + ret.steerActuatorDelay = 0.1 # Default delay ret.steerLimitTimer = 0.4 tire_stiffness_factor = 1. - ret.stoppingControl = True - ret.startingState = True - ret.vEgoStarting = 0.1 - ret.startAccel = 2.0 - - ret.longitudinalTuning.kpV = [0.5] - ret.longitudinalTuning.kiV = [0.0] - - ret.longitudinalActuatorDelayLowerBound = 0.5 # s - ret.longitudinalActuatorDelayUpperBound = 0.5 # s 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 @@ -291,20 +284,38 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.01]] - # panda safety config + # *** longitudinal control *** + if candidate in CANFD_CAR: + ret.longitudinalTuning.kpV = [0.1] + ret.longitudinalTuning.kiV = [0.0] + ret.longitudinalActuatorDelayLowerBound = 0.15 + ret.longitudinalActuatorDelayUpperBound = 0.5 + ret.experimentalLongitudinalAvailable = bool(ret.flags & HyundaiFlags.CANFD_HDA2) + else: + ret.longitudinalTuning.kpV = [0.5] + ret.longitudinalTuning.kiV = [0.0] + ret.longitudinalActuatorDelayLowerBound = 0.5 + ret.longitudinalActuatorDelayUpperBound = 0.5 + ret.experimentalLongitudinalAvailable = candidate not in (LEGACY_SAFETY_MODE_CAR | CAMERA_SCC_CAR) + ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable + ret.pcmCruise = not ret.openpilotLongitudinalControl + + ret.stoppingControl = True + ret.startingState = True + ret.vEgoStarting = 0.1 + ret.startAccel = 2.0 + + # *** panda safety config *** if candidate in CANFD_CAR: ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.noOutput), get_safety_config(car.CarParams.SafetyModel.hyundaiCanfd)] - # detect HDA2 with LKAS message - if 0x50 in fingerprint[6]: - ret.flags |= HyundaiFlags.CANFD_HDA2.value + if ret.openpilotLongitudinalControl: + ret.safetyConfigs[1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_LONG + if ret.flags & HyundaiFlags.CANFD_HDA2: ret.safetyConfigs[1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_HDA2 - else: - # non-HDA2 - if 0x1cf not in fingerprint[4]: - ret.flags |= HyundaiFlags.CANFD_ALT_BUTTONS.value - ret.safetyConfigs[1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_ALT_BUTTONS + if ret.flags & HyundaiFlags.CANFD_ALT_BUTTONS: + ret.safetyConfigs[1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_ALT_BUTTONS else: ret.enableBsm = 0x58b in fingerprint[0] @@ -342,7 +353,10 @@ class CarInterface(CarInterfaceBase): @staticmethod def init(CP, logcan, sendcan): if CP.openpilotLongitudinalControl: - disable_ecu(logcan, sendcan, addr=0x7d0, com_cont_req=b'\x28\x83\x01') + addr, bus = 0x7d0, 0 + if CP.flags & HyundaiFlags.CANFD_HDA2.value: + addr, bus = 0x730, 5 + disable_ecu(logcan, sendcan, bus=bus, addr=addr, com_cont_req=b'\x28\x83\x01') def _update(self, c): ret = self.CS.update(self.cp, self.cp_cam) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 6b64fcb5aa..4577d3cddf 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -5fa6a3743f2678eef13267fb946d7a03f2af5824 +27022484e3f4c0265ee7243154659b2697de3af7 \ No newline at end of file From 80259f377f8b1aa3a337cccbc3b00bd41898cf44 Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Wed, 12 Oct 2022 14:23:12 -0700 Subject: [PATCH 027/101] Ford: cleanup and fix button press (#26033) * cleanup * use Veh_V_ActlBrk for vEgoRaw * remove unused CarState.yaw_data * less resume spam * set steering ramp rate * match DBC range * add LCA/TJA notes --- selfdrive/car/ford/carcontroller.py | 50 ++++++++++++++++------------- selfdrive/car/ford/carstate.py | 8 ++--- selfdrive/car/ford/fordcan.py | 29 ++++++++++------- selfdrive/car/ford/interface.py | 9 +++--- selfdrive/car/ford/values.py | 29 ++++++++--------- 5 files changed, 67 insertions(+), 58 deletions(-) diff --git a/selfdrive/car/ford/carcontroller.py b/selfdrive/car/ford/carcontroller.py index 592d8586ca..f18014601c 100644 --- a/selfdrive/car/ford/carcontroller.py +++ b/selfdrive/car/ford/carcontroller.py @@ -3,7 +3,7 @@ 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 selfdrive.car.ford.values import CANBUS, CarControllerParams VisualAlert = car.CarControl.HUDControl.VisualAlert @@ -16,9 +16,9 @@ def apply_ford_steer_angle_limits(apply_angle, apply_angle_last, vEgo): apply_angle = clip(apply_angle, (apply_angle_last - max_angle_diff), (apply_angle_last + max_angle_diff)) # absolute limit (LatCtlPath_An_Actl) - apply_path_angle = math.radians(apply_angle) / CarControllerParams.STEER_RATIO - apply_path_angle = clip(apply_path_angle, -0.4995, 0.5240) - apply_angle = math.degrees(apply_path_angle) * CarControllerParams.STEER_RATIO + apply_path_angle = math.radians(apply_angle) / CarControllerParams.LKAS_STEER_RATIO + apply_path_angle = clip(apply_path_angle, -0.5, 0.5235) + apply_angle = math.degrees(apply_path_angle) * CarControllerParams.LKAS_STEER_RATIO return apply_angle @@ -47,40 +47,46 @@ class CarController: ### acc buttons ### if CC.cruiseControl.cancel: can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, cancel=True)) - elif CC.cruiseControl.resume: + can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, cancel=True, bus=CANBUS.main)) + elif CC.cruiseControl.resume and (self.frame % CarControllerParams.BUTTONS_STEP) == 0: can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, resume=True)) - - # if stock lane centering is active or in standby, toggle it off + can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, resume=True, bus=CANBUS.main)) + # if stock lane centering isn't off, send a button press to toggle it off # the stock system checks for steering pressed, and eventually disengages cruise control - if (self.frame % 200) == 0 and CS.acc_tja_status_stock_values["Tja_D_Stat"] != 0: + elif CS.acc_tja_status_stock_values["Tja_D_Stat"] != 0 and (self.frame % CarControllerParams.ACC_UI_STEP) == 0: can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, tja_toggle=True)) ### lateral control ### if CC.latActive: + lca_rq = 1 apply_angle = apply_ford_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgo) else: - apply_angle = CS.out.steeringAngleDeg + lca_rq = 0 + apply_angle = 0. # send steering commands at 20Hz if (self.frame % CarControllerParams.LKAS_STEER_STEP) == 0: - lca_rq = 1 if CC.latActive else 0 - # use LatCtlPath_An_Actl to actuate steering - # path angle is the car wheel angle, not the steering wheel angle - path_angle = math.radians(apply_angle) / CarControllerParams.STEER_RATIO - - # ramp rate: 0=Slow, 1=Medium, 2=Fast, 3=Immediately - # TODO: try slower ramp speed when driver torque detected - ramp_type = 3 + path_angle = math.radians(apply_angle) / CarControllerParams.LKAS_STEER_RATIO + + # set slower ramp type when small steering angle change + # 0=Slow, 1=Medium, 2=Fast, 3=Immediately + steer_change = abs(CS.out.steeringAngleDeg - actuators.steeringAngleDeg) + if steer_change < 2.0: + ramp_type = 0 + elif steer_change < 4.0: + ramp_type = 1 + elif steer_change < 6.0: + ramp_type = 2 + else: + ramp_type = 3 precision = 1 # 0=Comfortable, 1=Precise (the stock system always uses comfortable) - offset_roll_compensation_curvature = clip(self.VM.calc_curvature(0, CS.out.vEgo, -CS.yaw_data["VehYaw_W_Actl"]), -0.02, 0.02094) - self.apply_angle_last = apply_angle - can_sends.append(fordcan.create_lka_command(self.packer, apply_angle, 0)) + can_sends.append(fordcan.create_lka_command(self.packer, 0, 0)) can_sends.append(fordcan.create_tja_command(self.packer, lca_rq, ramp_type, precision, - 0, path_angle, 0, offset_roll_compensation_curvature)) + 0, path_angle, 0, 0)) ### ui ### @@ -99,7 +105,7 @@ class CarController: self.steer_alert_last = steer_alert new_actuators = actuators.copy() - new_actuators.steeringAngleDeg = apply_angle + new_actuators.steeringAngleDeg = self.apply_angle_last self.frame += 1 return new_actuators, can_sends diff --git a/selfdrive/car/ford/carstate.py b/selfdrive/car/ford/carstate.py index a7ea19effc..2276b1208a 100644 --- a/selfdrive/car/ford/carstate.py +++ b/selfdrive/car/ford/carstate.py @@ -20,7 +20,7 @@ class CarState(CarStateBase): ret = car.CarState.new_message() # car speed - ret.vEgoRaw = cp.vl["EngVehicleSpThrottle2"]["Veh_V_ActlEng"] * CV.KPH_TO_MS + ret.vEgoRaw = cp.vl["BrakeSysFeatures"]["Veh_V_ActlBrk"] * CV.KPH_TO_MS ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) ret.yawRate = cp.vl["Yaw_Data_FD1"]["VehYaw_W_Actl"] ret.standstill = cp.vl["DesiredTorqBrk"]["VehStop_D_Stat"] == 1 @@ -85,8 +85,6 @@ class CarState(CarStateBase): # Stock values from IPMA so that we can retain some stock functionality self.acc_tja_status_stock_values = cp_cam.vl["ACCDATA_3"] self.lkas_status_stock_values = cp_cam.vl["IPMA_Data"] - # Use stock sensor values - self.yaw_data = cp.vl["Yaw_Data_FD1"] return ret @@ -94,7 +92,7 @@ class CarState(CarStateBase): def get_can_parser(CP): signals = [ # sig_name, sig_address - ("Veh_V_ActlEng", "EngVehicleSpThrottle2"), # ABS vehicle speed (kph) + ("Veh_V_ActlBrk", "BrakeSysFeatures"), # ABS vehicle speed (kph) ("VehYaw_W_Actl", "Yaw_Data_FD1"), # ABS vehicle yaw rate (rad/s) ("VehStop_D_Stat", "DesiredTorqBrk"), # ABS vehicle stopped ("PrkBrkStatus", "DesiredTorqBrk"), # ABS park brake status @@ -156,7 +154,7 @@ class CarState(CarStateBase): checks = [ # sig_address, frequency - ("EngVehicleSpThrottle2", 50), + ("BrakeSysFeatures", 50), ("Yaw_Data_FD1", 100), ("DesiredTorqBrk", 50), ("EngVehicleSpThrottle", 100), diff --git a/selfdrive/car/ford/fordcan.py b/selfdrive/car/ford/fordcan.py index b42561df21..373ce096c6 100644 --- a/selfdrive/car/ford/fordcan.py +++ b/selfdrive/car/ford/fordcan.py @@ -8,8 +8,7 @@ def create_lka_command(packer, angle_deg: float, curvature: float): """ Creates a CAN message for the Ford LKAS Command. - This command can apply "Lane Keeping Aid" manoeuvres, which are subject to the - PSCM lockout. + This command can apply "Lane Keeping Aid" manoeuvres, which are subject to the PSCM lockout. Frequency is 20Hz. """ @@ -30,12 +29,20 @@ def create_tja_command(packer, lca_rq: int, ramp_type: int, precision: int, path """ Creates a CAN message for the Ford TJA/LCA Command. - This command can apply "Lane Centering" manoeuvres: continuous lane centering - for traffic jam assist and highway driving. It is not subject to the PSCM - lockout. + This command can apply "Lane Centering" manoeuvres: continuous lane centering for traffic jam + assist and highway driving. It is not subject to the PSCM lockout. - The PSCM should be configured to accept TJA/LCA commands before these - commands will be processed. This can be done using tools such as Forscan. + Ford lane centering command uses a third order polynomial to describe the road centerline. The + polynomial is defined by the following coefficients: + c0: lateral offset between the vehicle and the centerline + c1: heading angle between the vehicle and the centerline + c2: curvature of the centerline + c3: rate of change of curvature of the centerline + As the PSCM combines this information with other sensor data, such as the vehicle's yaw rate and + speed, the steering angle cannot be easily controlled. + + The PSCM should be configured to accept TJA/LCA commands before these commands will be processed. + This can be done using tools such as Forscan. Frequency is 20Hz. """ @@ -47,7 +54,7 @@ def create_tja_command(packer, lca_rq: int, ramp_type: int, precision: int, path "LatCtlRampType_D_Rq": ramp_type, # Ramp speed: 0=Slow, 1=Medium, 2=Fast, 3=Immediate [0|3] "LatCtlPrecision_D_Rq": precision, # Precision: 0=Comfortable, 1=Precise, 2/3=NotUsed [0|3] "LatCtlPathOffst_L_Actl": path_offset, # Path offset [-5.12|5.11] meter - "LatCtlPath_An_Actl": path_angle, # Path angle [-0.4995|0.5240] radians + "LatCtlPath_An_Actl": path_angle, # Path angle [-0.5|0.5235] radians "LatCtlCurv_NoRate_Actl": curvature_rate, # Curvature rate [-0.001024|0.00102375] 1/meter^2 "LatCtlCurv_No_Actl": curvature, # Curvature [-0.02|0.02094] 1/meter } @@ -108,8 +115,8 @@ def create_lkas_ui_command(packer, main_on: bool, enabled: bool, steer_alert: bo def create_acc_ui_command(packer, main_on: bool, enabled: bool, hud_control, stock_values: dict): """ - Creates a CAN message for the Ford IPC adaptive cruise, forward collision - warning and traffic jam assist status. + Creates a CAN message for the Ford IPC adaptive cruise, forward collision warning and traffic jam + assist status. Stock functionality is maintained by passing through unmodified signals. @@ -141,7 +148,7 @@ def create_acc_ui_command(packer, main_on: bool, enabled: bool, hud_control, sto return packer.make_can_msg("ACCDATA_3", CANBUS.main, values) -def create_button_command(packer, stock_values: dict, cancel = False, resume = False, tja_toggle = False, bus = CANBUS.camera): +def create_button_command(packer, stock_values: dict, cancel = False, resume = False, tja_toggle = False, bus: int = CANBUS.camera): """ Creates a CAN message for the Ford SCCM buttons/switches. diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py index 7d4c9eb94c..4943db076f 100644 --- a/selfdrive/car/ford/interface.py +++ b/selfdrive/car/ford/interface.py @@ -5,8 +5,7 @@ from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, from selfdrive.car.ford.values import CAR, Ecu, TransmissionType, GearShifter from selfdrive.car.interfaces import CarInterfaceBase - -EventName = car.CarEvent.EventName +CarParams = car.CarParams class CarInterface(CarInterfaceBase): @@ -19,10 +18,10 @@ class CarInterface(CarInterfaceBase): ret.carName = "ford" ret.dashcamOnly = True - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.ford)] + ret.safetyConfigs = [get_safety_config(CarParams.SafetyModel.ford)] # Angle-based steering - ret.steerControlType = car.CarParams.SteerControlType.angle + ret.steerControlType = CarParams.SteerControlType.angle ret.steerActuatorDelay = 0.4 ret.steerLimitTimer = 1.0 tire_stiffness_factor = 1.0 @@ -43,7 +42,7 @@ class CarInterface(CarInterfaceBase): ret.mass = 1350 + STD_CARGO_KG else: - raise ValueError(f"Unsupported car: ${candidate}") + raise ValueError(f"Unsupported car: {candidate}") # Auto Transmission: 0x732 ECU or Gear_Shift_by_Wire_FD1 found_ecus = [fw.ecu for fw in car_fw] diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index 5820b5c9fd..7b3140fbbf 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -1,4 +1,4 @@ -from collections import namedtuple +from collections import defaultdict, namedtuple from dataclasses import dataclass from enum import Enum from typing import Dict, List, Union @@ -22,19 +22,17 @@ class CarControllerParams: LKAS_UI_STEP = 100 # Message: ACCDATA_3 ACC_UI_STEP = 5 + # Message: Steering_Data_FD1, but send twice as fast + BUTTONS_STEP = 10 / 2 - STEER_RATIO = 2.75 - STEER_DRIVER_ALLOWANCE = 0.8 + LKAS_STEER_RATIO = 2.75 # Approximate ratio between LatCtlPath_An_Actl and steering angle in radians + # TODO: remove this once we understand how the EPS calculates the steering angle better + STEER_DRIVER_ALLOWANCE = 0.8 # Driver intervention threshold in Nm RATE_LIMIT_UP = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., .8, .15]) RATE_LIMIT_DOWN = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., 3.5, 0.4]) -class RADAR: - DELPHI_ESR = 'ford_fusion_2018_adas' - DELPHI_MRR = 'FORD_CADS' - - class CANBUS: main = 0 radar = 1 @@ -47,6 +45,14 @@ class CAR: FOCUS_MK4 = "FORD FOCUS 4TH GEN" +class RADAR: + DELPHI_ESR = 'ford_fusion_2018_adas' + DELPHI_MRR = 'FORD_CADS' + + +DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict("ford_lincoln_base_pt", RADAR.DELPHI_MRR)) + + @dataclass class FordCarInfo(CarInfo): package: str = "Co-Pilot360 Assist+" @@ -143,10 +149,3 @@ FW_VERSIONS = { ], }, } - - -DBC = { - CAR.ESCAPE_MK4: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR), - CAR.EXPLORER_MK6: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR), - CAR.FOCUS_MK4: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR), -} From 23e78da6a49b8aa43c7d60226aa466a8599be700 Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Wed, 12 Oct 2022 14:34:43 -0700 Subject: [PATCH 028/101] ci: fix tools workflow --- .github/workflows/tools_tests.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/tools_tests.yaml b/.github/workflows/tools_tests.yaml index c5afaad16c..71f6ed50bc 100644 --- a/.github/workflows/tools_tests.yaml +++ b/.github/workflows/tools_tests.yaml @@ -6,7 +6,7 @@ on: concurrency: group: ${{ github.workflow }}-${{ github.ref }}-${{ github.event_name }} - cancel-in-progress: true + cancel-in-progress: ${{ github.ref != 'refs/heads/master' }} env: BASE_IMAGE: openpilot-base From 077f0e0a4433e07330e2c1e22bc1774da1d964fc Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Wed, 12 Oct 2022 15:11:03 -0700 Subject: [PATCH 029/101] ci: disable concurrency for master branch (#26052) disable concurrency for master branch --- .github/workflows/selfdrive_tests.yaml | 4 ++-- .github/workflows/tools_tests.yaml | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index ab70b8e7ef..cd34c6d27c 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -7,8 +7,8 @@ on: pull_request: concurrency: - group: ${{ github.workflow }}-${{ github.ref }}-${{ github.event_name }} - cancel-in-progress: ${{ github.ref != 'refs/heads/master' }} + group: ${{ github.workflow }}-${{ github.ref != 'refs/heads/master' && github.ref || github.run_id }}-${{ github.event_name }} + cancel-in-progress: true env: BASE_IMAGE: openpilot-base diff --git a/.github/workflows/tools_tests.yaml b/.github/workflows/tools_tests.yaml index 71f6ed50bc..9dc5c05837 100644 --- a/.github/workflows/tools_tests.yaml +++ b/.github/workflows/tools_tests.yaml @@ -5,8 +5,8 @@ on: pull_request: concurrency: - group: ${{ github.workflow }}-${{ github.ref }}-${{ github.event_name }} - cancel-in-progress: ${{ github.ref != 'refs/heads/master' }} + group: ${{ github.workflow }}-${{ github.ref != 'refs/heads/master' && github.ref || github.run_id }}-${{ github.event_name }} + cancel-in-progress: true env: BASE_IMAGE: openpilot-base From 8b5ebbddf684bc7566ae41447face9f2ab053d40 Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Wed, 12 Oct 2022 15:14:02 -0700 Subject: [PATCH 030/101] build extras together (#26051) * build extras together * don't check here either --- SConstruct | 9 +++++---- tools/cabana/SConscript | 7 +++---- tools/replay/SConscript | 17 ++++++++--------- 3 files changed, 16 insertions(+), 17 deletions(-) diff --git a/SConstruct b/SConstruct index e015218f2a..23ab37dc1e 100644 --- a/SConstruct +++ b/SConstruct @@ -431,11 +431,12 @@ SConscript(['selfdrive/sensord/SConscript']) SConscript(['selfdrive/ui/SConscript']) SConscript(['selfdrive/navd/SConscript']) -SConscript(['tools/replay/SConscript']) +if arch in ['x86_64', 'Darwin'] or GetOption('extras'): + SConscript(['tools/replay/SConscript']) -opendbc = abspath([File('opendbc/can/libdbc.so')]) -Export('opendbc') -SConscript(['tools/cabana/SConscript']) + opendbc = abspath([File('opendbc/can/libdbc.so')]) + Export('opendbc') + SConscript(['tools/cabana/SConscript']) if GetOption('test'): SConscript('panda/tests/safety/SConscript') diff --git a/tools/cabana/SConscript b/tools/cabana/SConscript index b94741ea9c..8dbd4f1d1c 100644 --- a/tools/cabana/SConscript +++ b/tools/cabana/SConscript @@ -11,7 +11,6 @@ else: base_libs.append('OpenCL') qt_libs = ['qt_util', 'Qt5Charts'] + base_libs -if arch in ['x86_64', 'Darwin'] and GetOption('extras'): - cabana_libs = [widgets, cereal, messaging, visionipc, replay_lib, opendbc,'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv'] + qt_libs - qt_env.Program('_cabana', ['cabana.cc', 'mainwin.cc', 'chartswidget.cc', 'historylog.cc', 'videowidget.cc', 'signaledit.cc', 'dbcmanager.cc', - 'canmessages.cc', 'messageswidget.cc', 'detailwidget.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks) +cabana_libs = [widgets, cereal, messaging, visionipc, replay_lib, opendbc,'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv'] + qt_libs +qt_env.Program('_cabana', ['cabana.cc', 'mainwin.cc', 'chartswidget.cc', 'historylog.cc', 'videowidget.cc', 'signaledit.cc', 'dbcmanager.cc', + 'canmessages.cc', 'messageswidget.cc', 'detailwidget.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks) diff --git a/tools/replay/SConscript b/tools/replay/SConscript index 9985375688..4ddeb662e0 100644 --- a/tools/replay/SConscript +++ b/tools/replay/SConscript @@ -12,15 +12,14 @@ else: base_libs.append('OpenCL') qt_libs = ['qt_util'] + base_libs -if arch in ['x86_64', 'Darwin'] or GetOption('extras'): - qt_env['CXXFLAGS'] += ["-Wno-deprecated-declarations"] +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_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, FRAMEWORKS=base_frameworks) - Export('replay_lib') - replay_libs = [replay_lib, 'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv', 'ncurses'] + qt_libs - qt_env.Program("replay", ["main.cc"], LIBS=replay_libs, FRAMEWORKS=base_frameworks) +replay_lib = qt_env.Library("qt_replay", replay_lib_src, LIBS=qt_libs, FRAMEWORKS=base_frameworks) +Export('replay_lib') +replay_libs = [replay_lib, 'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv', 'ncurses'] + qt_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]) +if GetOption('test'): + qt_env.Program('tests/test_replay', ['tests/test_runner.cc', 'tests/test_replay.cc'], LIBS=[replay_libs]) From 549452f84d0f06a92d5c03b710a300acefe8673d Mon Sep 17 00:00:00 2001 From: Kurt Nistelberger Date: Wed, 12 Oct 2022 15:14:45 -0700 Subject: [PATCH 031/101] rawgpsd: log + skip unknown responses (#26043) * skip DIAG_EVENT_REPORT_F events * . Co-authored-by: Kurt Nistelberger --- selfdrive/sensord/rawgps/rawgpsd.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/sensord/rawgps/rawgpsd.py b/selfdrive/sensord/rawgps/rawgpsd.py index 95f8dab1c2..c823ede076 100755 --- a/selfdrive/sensord/rawgps/rawgpsd.py +++ b/selfdrive/sensord/rawgps/rawgpsd.py @@ -180,7 +180,8 @@ def main() -> NoReturn: while 1: opcode, payload = diag.recv() if opcode != DIAG_LOG_F: - cloudlog.exception(f"Unhandled opcode: {opcode}") + cloudlog.error(f"Unhandled opcode: {opcode}") + continue assert opcode == DIAG_LOG_F (pending_msgs, log_outer_length), inner_log_packet = unpack_from(' Date: Wed, 12 Oct 2022 15:40:19 -0700 Subject: [PATCH 032/101] add CAN-FD non-ISO mode support (#25947) CAN FD non-ISO support Co-authored-by: Adeeb Shihadeh --- panda | 2 +- selfdrive/boardd/boardd.cc | 1 + selfdrive/boardd/panda.cc | 4 ++++ selfdrive/boardd/panda.h | 1 + 4 files changed, 7 insertions(+), 1 deletion(-) diff --git a/panda b/panda index ffb3109e28..2f3e2825e5 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit ffb3109e28296cc86f1892c4e0690856e28fb35a +Subproject commit 2f3e2825e5ecc8074b4ee9cb9a70df635d09fd10 diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 3e39985c29..77e86f9458 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -407,6 +407,7 @@ std::optional send_panda_states(PubMaster *pm, const std::vector cs[j].setCanDataSpeed(can_health.can_data_speed); cs[j].setCanfdEnabled(can_health.canfd_enabled); cs[j].setBrsEnabled(can_health.brs_enabled); + cs[j].setCanfdNonIso(can_health.canfd_non_iso); } // Convert faults bitset to capnp list diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index 7ddf15f9ce..0b8630b0c0 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -360,6 +360,10 @@ void Panda::set_data_speed_kbps(uint16_t bus, uint16_t speed) { usb_write(0xf9, bus, (speed * 10)); } +void Panda::set_canfd_non_iso(uint16_t bus, bool non_iso) { + usb_write(0xfc, bus, non_iso); +} + static uint8_t len_to_dlc(uint8_t len) { if (len <= 8) { return len; diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h index a4afbdac1a..c7a0e7a6c1 100644 --- a/selfdrive/boardd/panda.h +++ b/selfdrive/boardd/panda.h @@ -91,6 +91,7 @@ class Panda { void send_heartbeat(bool engaged); void set_can_speed_kbps(uint16_t bus, uint16_t speed); void set_data_speed_kbps(uint16_t bus, uint16_t speed); + void set_canfd_non_iso(uint16_t bus, bool non_iso); void can_send(capnp::List::Reader can_data_list); bool can_receive(std::vector& out_vec); From 135270f65cbde80c06aee1773b9ca802bd32f419 Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Wed, 12 Oct 2022 19:27:23 -0400 Subject: [PATCH 033/101] Allow car port to define enable buttons (#25793) * Allow car port to define enable buttons * simplify * oops --- selfdrive/car/__init__.py | 15 +-------------- selfdrive/car/interfaces.py | 14 +++++++++++--- selfdrive/car/volkswagen/interface.py | 4 +++- 3 files changed, 15 insertions(+), 18 deletions(-) diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py index 8ff39ceaeb..491c551b1b 100644 --- a/selfdrive/car/__init__.py +++ b/selfdrive/car/__init__.py @@ -3,7 +3,7 @@ import capnp from cereal import car from common.numpy_fast import clip -from typing import Dict, List +from typing import Dict # kg of standard extra cargo to count for drive, gas, etc... STD_CARGO_KG = 136. @@ -32,19 +32,6 @@ def create_button_event(cur_but: int, prev_but: int, buttons_dict: Dict[int, cap return be -def create_button_enable_events(buttonEvents: capnp.lib.capnp._DynamicListBuilder, pcm_cruise: bool = False) -> List[int]: - events = [] - for b in buttonEvents: - # do enable on both accel and decel buttons - if not pcm_cruise: - if b.type in (ButtonType.accelCruise, ButtonType.decelCruise) and not b.pressed: - events.append(EventName.buttonEnable) - # do disable on button down - if b.type == ButtonType.cancel and b.pressed: - events.append(EventName.buttonCancel) - return events - - def gen_empty_fingerprint(): return {i: {} for i in range(0, 8)} diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index a789fc6cad..4647a04244 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -10,11 +10,12 @@ from common.conversions import Conversions as CV from common.kalman.simple_kalman import KF1D from common.numpy_fast import interp from common.realtime import DT_CTRL -from selfdrive.car import apply_hysteresis, create_button_enable_events, gen_empty_fingerprint +from selfdrive.car import apply_hysteresis, gen_empty_fingerprint from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX, apply_deadzone from selfdrive.controls.lib.events import Events from selfdrive.controls.lib.vehicle_model import VehicleModel +ButtonType = car.CarState.ButtonEvent.Type GearShifter = car.CarState.GearShifter EventName = car.CarEvent.EventName TorqueFromLateralAccelCallbackType = Callable[[float, car.CarParams.LateralTorqueTuning, float, float, bool], float] @@ -210,7 +211,8 @@ class CarInterfaceBase(ABC): def apply(self, c: car.CarControl) -> Tuple[car.CarControl.Actuators, List[bytes]]: pass - def create_common_events(self, cs_out, extra_gears=None, pcm_enable=True, allow_enable=True): + def create_common_events(self, cs_out, extra_gears=None, pcm_enable=True, allow_enable=True, + enable_buttons=(ButtonType.accelCruise, ButtonType.decelCruise)): events = Events() if cs_out.doorOpen: @@ -244,7 +246,13 @@ class CarInterfaceBase(ABC): events.add(EventName.steerOverride) # Handle button presses - events.events.extend(create_button_enable_events(cs_out.buttonEvents, pcm_cruise=self.CP.pcmCruise)) + for b in cs_out.buttonEvents: + # Enable OP long on falling edge of enable buttons (defaults to accelCruise and decelCruise, overridable per-port) + if not self.CP.pcmCruise and (b.type in enable_buttons and not b.pressed): + events.add(EventName.buttonEnable) + # Disable on rising edge of cancel for both stock and OP long + if b.type == ButtonType.cancel and b.pressed: + events.add(EventName.buttonCancel) # Handle permanent and temporary steering faults self.steering_unpressed = 0 if cs_out.steeringPressed else self.steering_unpressed + 1 diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 4724fe81bf..870f3ab163 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -6,6 +6,7 @@ from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, from selfdrive.car.interfaces import CarInterfaceBase from selfdrive.car.volkswagen.values import CAR, PQ_CARS, CANBUS, NetworkLocation, TransmissionType, GearShifter +ButtonType = car.CarState.ButtonEvent.Type EventName = car.CarEvent.EventName @@ -218,7 +219,8 @@ class CarInterface(CarInterfaceBase): ret = self.CS.update(self.cp, self.cp_cam, self.cp_ext, self.CP.transmissionType) events = self.create_common_events(ret, extra_gears=[GearShifter.eco, GearShifter.sport, GearShifter.manumatic], - pcm_enable=not self.CS.CP.openpilotLongitudinalControl) + pcm_enable=not self.CS.CP.openpilotLongitudinalControl, + enable_buttons=(ButtonType.setCruise, ButtonType.resumeCruise)) # Low speed steer alert hysteresis logic if self.CP.minSteerSpeed > 0. and ret.vEgo < (self.CP.minSteerSpeed + 1.): From b65fad9e8f232167bcc0fc9139bd632c573abb60 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 13 Oct 2022 08:04:53 +0800 Subject: [PATCH 034/101] cabana: keep scrollarea frame (#26056) add frame back --- tools/cabana/chartswidget.cc | 1 - 1 file changed, 1 deletion(-) diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index e8a27ae18c..2fc3fecb2a 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -53,7 +53,6 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) { QScrollArea *charts_scroll = new QScrollArea(this); charts_scroll->setWidgetResizable(true); charts_scroll->setWidget(charts_container); - charts_scroll->setFrameShape(QFrame::NoFrame); charts_scroll->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); main_layout->addWidget(charts_scroll); From bb61081b70e787d3defe18c74720eb4d5dbb3114 Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Wed, 12 Oct 2022 20:46:26 -0400 Subject: [PATCH 035/101] VW MQB: DBC updates and cleanup (#26053) * VW MQB: DBC updates and cleanup * bump opendbc after merge --- opendbc | 2 +- selfdrive/car/volkswagen/carcontroller.py | 2 +- selfdrive/car/volkswagen/carstate.py | 9 +++++---- selfdrive/car/volkswagen/pqcan.py | 2 +- selfdrive/car/volkswagen/values.py | 1 + 5 files changed, 9 insertions(+), 7 deletions(-) diff --git a/opendbc b/opendbc index 04cc54d5e6..dde0ff6f44 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 04cc54d5e662aaf708f72cabb65507c7dbb5136d +Subproject commit dde0ff6f4456c167df204bf5ac1e3f2979c844c9 diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py index 816933f2f0..fff5548671 100644 --- a/selfdrive/car/volkswagen/carcontroller.py +++ b/selfdrive/car/volkswagen/carcontroller.py @@ -76,7 +76,7 @@ class CarController: stopping = actuators.longControlState == LongCtrlState.stopping starting = actuators.longControlState == LongCtrlState.starting can_sends.extend(self.CCS.create_acc_accel_control(self.packer_pt, CANBUS.pt, CS.acc_type, CC.longActive, accel, - acc_control, stopping, starting, CS.out.cruiseState.standstill)) + acc_control, stopping, starting, CS.esp_hold_confirmation)) # **** HUD Controls ***************************************************** # diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py index 3e99ca8252..5dc4543c0d 100644 --- a/selfdrive/car/volkswagen/carstate.py +++ b/selfdrive/car/volkswagen/carstate.py @@ -110,20 +110,21 @@ class CarState(CarStateBase): ret.cruiseState.available = True ret.cruiseState.enabled = False elif pt_cp.vl["TSK_06"]["TSK_Status"] in (3, 4, 5): - # ACC okay and enabled, currently regulating speed (3) or driver accel override (4) or overrun coast-down (5) + # ACC okay and enabled, currently regulating speed (3) or driver accel override (4) or brake only (5) ret.cruiseState.available = True ret.cruiseState.enabled = True else: # 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"]) + self.esp_hold_confirmation = bool(pt_cp.vl["ESP_21"]["ESP_Haltebestaetigung"]) + ret.cruiseState.standstill = self.CP.pcmCruise and self.esp_hold_confirmation 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 # radar sends a set-speed of ~90.69 m/s / 203mph. if self.CP.pcmCruise: - ret.cruiseState.speed = ext_cp.vl["ACC_02"]["ACC_Wunschgeschw"] * CV.KPH_TO_MS + ret.cruiseState.speed = ext_cp.vl["ACC_02"]["ACC_Wunschgeschw_02"] * CV.KPH_TO_MS if ret.cruiseState.speed > 90: ret.cruiseState.speed = 0 @@ -478,7 +479,7 @@ class CarState(CarStateBase): class MqbExtraSignals: # Additional signal and message lists for optional or bus-portable controllers fwd_radar_signals = [ - ("ACC_Wunschgeschw", "ACC_02"), # ACC set speed + ("ACC_Wunschgeschw_02", "ACC_02"), # ACC set speed ("AWV2_Freigabe", "ACC_10"), # FCW brake jerk release ("ANB_Teilbremsung_Freigabe", "ACC_10"), # AEB partial braking release ("ANB_Zielbremsung_Freigabe", "ACC_10"), # AEB target braking release diff --git a/selfdrive/car/volkswagen/pqcan.py b/selfdrive/car/volkswagen/pqcan.py index 30f3fcf62d..0bcbf6abb3 100644 --- a/selfdrive/car/volkswagen/pqcan.py +++ b/selfdrive/car/volkswagen/pqcan.py @@ -59,7 +59,7 @@ def acc_hud_status_value(main_switch_on, acc_faulted, long_active): return hud_status -def create_acc_accel_control(packer, bus, acc_type, enabled, accel, acc_control, stopping, starting, standstill): +def create_acc_accel_control(packer, bus, acc_type, enabled, accel, acc_control, stopping, starting, esp_hold): commands = [] values = { diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index e0bcd02600..8c679c7406 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -241,6 +241,7 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = { ], } + # All supported cars should return FW from the engine, srs, eps, and fwdRadar. Cars # with a manual trans won't return transmission firmware, but all other cars will. # From b3324418034fcf09123b614ee2429a4e5bc9d7a5 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Wed, 12 Oct 2022 17:47:30 -0700 Subject: [PATCH 036/101] locationd: Fix GPS sensor times with fixed offsets (#25920) * Rewind to qcom time * Fix test * Typo * init unix_time fix * add gps sensor_time_offsets * remove all clocks code and add todo * :emove clocks in unit test * update refs * update refs Co-authored-by: nuwandavek --- selfdrive/locationd/locationd.cc | 28 +++++++++++++--------- selfdrive/locationd/locationd.h | 2 +- selfdrive/locationd/models/live_kf.cc | 2 +- selfdrive/locationd/test/test_locationd.py | 1 + selfdrive/test/process_replay/ref_commit | 2 +- 5 files changed, 21 insertions(+), 14 deletions(-) diff --git a/selfdrive/locationd/locationd.cc b/selfdrive/locationd/locationd.cc index 9608f4003b..e156af5d64 100755 --- a/selfdrive/locationd/locationd.cc +++ b/selfdrive/locationd/locationd.cc @@ -20,6 +20,11 @@ const double VALID_POS_STD = 50.0; // m const double MAX_RESET_TRACKER = 5.0; const double SANE_GPS_UNCERTAINTY = 1500.0; // m +// TODO: GPS sensor time offsets are empirically calculated +// They should be replaced with synced time from a real clock +const double GPS_LOCATION_SENSOR_TIME_OFFSET = 0.630; // s +const double GPS_LOCATION_EXTERNAL_SENSOR_TIME_OFFSET = 0.095; // s + static VectorXd floatlist2vector(const capnp::List::Reader& floatlist) { VectorXd res(floatlist.size()); for (int i = 0; i < floatlist.size(); i++) { @@ -257,7 +262,7 @@ void Localizer::input_fake_gps_observations(double current_time) { this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R }); } -void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::Reader& log) { +void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::Reader& log, const double sensor_time_offset) { // ignore the message if the fix is invalid bool gps_invalid_flag = (log.getFlags() % 2 == 0); bool gps_unreasonable = (Vector2d(log.getAccuracy(), log.getVerticalAccuracy()).norm() >= SANE_GPS_UNCERTAINTY); @@ -265,13 +270,15 @@ void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::R bool gps_lat_lng_alt_insane = ((std::abs(log.getLatitude()) > 90) || (std::abs(log.getLongitude()) > 180) || (std::abs(log.getAltitude()) > ALTITUDE_SANITY_CHECK)); bool gps_vel_insane = (floatlist2vector(log.getVNED()).norm() > TRANS_SANITY_CHECK); - if (gps_invalid_flag || gps_unreasonable || gps_accuracy_insane || gps_lat_lng_alt_insane || gps_vel_insane){ + if (gps_invalid_flag || gps_unreasonable || gps_accuracy_insane || gps_lat_lng_alt_insane || gps_vel_insane) { this->determine_gps_mode(current_time); return; } + + double sensor_time = current_time - sensor_time_offset; // Process message - this->last_gps_fix = current_time; + this->last_gps_fix = sensor_time; this->gps_mode = true; Geodetic geodetic = { log.getLatitude(), log.getLongitude(), log.getAltitude() }; this->converter = std::make_unique(geodetic); @@ -300,14 +307,14 @@ void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::R if (ecef_vel.norm() > 5.0 && orientation_error.norm() > 1.0) { LOGE("Locationd vs ubloxLocation orientation difference too large, kalman reset"); this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R); - this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_ORIENTATION_FROM_GPS, { initial_pose_ecef_quat }); + this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_ORIENTATION_FROM_GPS, { initial_pose_ecef_quat }); } else if (gps_est_error > 100.0) { LOGE("Locationd vs ubloxLocation position difference too large, kalman reset"); this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R); } - this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_POS, { ecef_pos }, { ecef_pos_R }); - this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R }); + this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_POS, { ecef_pos }, { ecef_pos_R }); + this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R }); } void Localizer::handle_car_state(double current_time, const cereal::CarState::Reader& log) { @@ -443,9 +450,9 @@ void Localizer::handle_msg(const cereal::Event::Reader& log) { } else if (log.isGyroscope()) { this->handle_sensor(t, log.getGyroscope()); } else if (log.isGpsLocation()) { - this->handle_gps(t, log.getGpsLocation()); + this->handle_gps(t, log.getGpsLocation(), GPS_LOCATION_SENSOR_TIME_OFFSET); } else if (log.isGpsLocationExternal()) { - this->handle_gps(t, log.getGpsLocationExternal()); + this->handle_gps(t, log.getGpsLocationExternal(), GPS_LOCATION_EXTERNAL_SENSOR_TIME_OFFSET); } else if (log.isCarState()) { this->handle_car_state(t, log.getCarState()); } else if (log.isCameraOdometry()) { @@ -497,9 +504,8 @@ int Localizer::locationd_thread() { } else { gps_location_socket = "gpsLocation"; } - const std::initializer_list service_list = {gps_location_socket, - "cameraOdometry", "liveCalibration", "carState", "carParams", - "accelerometer", "gyroscope"}; + const std::initializer_list service_list = {gps_location_socket, "cameraOdometry", "liveCalibration", + "carState", "carParams", "accelerometer", "gyroscope"}; PubMaster pm({"liveLocationKalman"}); // TODO: remove carParams once we're always sending at 100Hz diff --git a/selfdrive/locationd/locationd.h b/selfdrive/locationd/locationd.h index b17ab04b23..280296b06c 100755 --- a/selfdrive/locationd/locationd.h +++ b/selfdrive/locationd/locationd.h @@ -46,7 +46,7 @@ public: void handle_msg_bytes(const char *data, const size_t size); void handle_msg(const cereal::Event::Reader& log); void handle_sensor(double current_time, const cereal::SensorEventData::Reader& log); - void handle_gps(double current_time, const cereal::GpsLocationData::Reader& log); + void handle_gps(double current_time, const cereal::GpsLocationData::Reader& log, const double sensor_time_offset); void handle_car_state(double current_time, const cereal::CarState::Reader& log); void handle_cam_odo(double current_time, const cereal::CameraOdometry::Reader& log); void handle_live_calib(double current_time, const cereal::LiveCalibrationData::Reader& log); diff --git a/selfdrive/locationd/models/live_kf.cc b/selfdrive/locationd/models/live_kf.cc index 5ff0f26995..f8c03365e1 100755 --- a/selfdrive/locationd/models/live_kf.cc +++ b/selfdrive/locationd/models/live_kf.cc @@ -44,7 +44,7 @@ LiveKalman::LiveKalman() { // init filter this->filter = std::make_shared(this->name, get_mapmat(this->Q), get_mapvec(this->initial_x), get_mapmat(initial_P), this->dim_state, this->dim_state_err, 0, 0, 0, std::vector(), - std::vector{3}, std::vector(), 0.2); + std::vector{3}, std::vector(), 0.8); } void LiveKalman::init_state(VectorXd& state, VectorXd& covs_diag, double filter_time) { diff --git a/selfdrive/locationd/test/test_locationd.py b/selfdrive/locationd/test/test_locationd.py index e32861cfae..7569530211 100755 --- a/selfdrive/locationd/test/test_locationd.py +++ b/selfdrive/locationd/test/test_locationd.py @@ -53,6 +53,7 @@ class TestLocationdProc(unittest.TestCase): msg.gpsLocationExternal.vNED = [0.0, 0.0, 0.0] msg.gpsLocationExternal.latitude = self.lat msg.gpsLocationExternal.longitude = self.lon + msg.gpsLocationExternal.unixTimestampMillis = t * 1e6 msg.gpsLocationExternal.altitude = self.alt elif name == 'cameraOdometry': msg.cameraOdometry.rot = [0.0, 0.0, 0.0] diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 4577d3cddf..e01fe2ac3c 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -27022484e3f4c0265ee7243154659b2697de3af7 \ No newline at end of file +14bc91c326f75ce48337720668a1744184c46994 \ No newline at end of file From 8809116a2674be71de45996b9f88bda46468694b Mon Sep 17 00:00:00 2001 From: Kurt Nistelberger Date: Wed, 12 Oct 2022 18:55:35 -0700 Subject: [PATCH 037/101] remove null effect assert --- selfdrive/sensord/rawgps/rawgpsd.py | 1 - 1 file changed, 1 deletion(-) diff --git a/selfdrive/sensord/rawgps/rawgpsd.py b/selfdrive/sensord/rawgps/rawgpsd.py index c823ede076..5a6827a759 100755 --- a/selfdrive/sensord/rawgps/rawgpsd.py +++ b/selfdrive/sensord/rawgps/rawgpsd.py @@ -182,7 +182,6 @@ def main() -> NoReturn: if opcode != DIAG_LOG_F: cloudlog.error(f"Unhandled opcode: {opcode}") continue - assert opcode == DIAG_LOG_F (pending_msgs, log_outer_length), inner_log_packet = unpack_from(' 0: From b31932382d574b4db3c2b9b280d5410823adad1c Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 13 Oct 2022 10:31:26 +0800 Subject: [PATCH 038/101] cabana: increase replay's segment cache limit & add setting dialog (#26019) * increase replay's segment cache limit * todo * add settings dialog blank line typo --- tools/cabana/.gitignore | 1 + tools/cabana/canmessages.cc | 36 ++++++++++++++++++++++--- tools/cabana/canmessages.h | 19 +++++++++++-- tools/cabana/mainwin.cc | 54 +++++++++++++++++++++++++++++++++++++ tools/cabana/mainwin.h | 12 +++++++++ tools/replay/replay.cc | 4 +-- tools/replay/replay.h | 5 +++- 7 files changed, 122 insertions(+), 9 deletions(-) diff --git a/tools/cabana/.gitignore b/tools/cabana/.gitignore index 0c21d5530d..88ffab2717 100644 --- a/tools/cabana/.gitignore +++ b/tools/cabana/.gitignore @@ -2,3 +2,4 @@ moc_* *.moc _cabana +settings diff --git a/tools/cabana/canmessages.cc b/tools/cabana/canmessages.cc index a55a045981..b717424ece 100644 --- a/tools/cabana/canmessages.cc +++ b/tools/cabana/canmessages.cc @@ -1,9 +1,11 @@ #include "tools/cabana/canmessages.h" #include +#include Q_DECLARE_METATYPE(std::vector); +Settings settings; CANMessages *can = nullptr; CANMessages::CANMessages(QObject *parent) : QObject(parent) { @@ -11,6 +13,7 @@ CANMessages::CANMessages(QObject *parent) : QObject(parent) { qRegisterMetaType>(); QObject::connect(this, &CANMessages::received, this, &CANMessages::process, Qt::QueuedConnection); + QObject::connect(&settings, &Settings::changed, this, &CANMessages::settingChanged); } CANMessages::~CANMessages() { @@ -24,6 +27,7 @@ static bool event_filter(const Event *e, void *opaque) { bool CANMessages::loadRoute(const QString &route, const QString &data_dir, bool use_qcam) { replay = new Replay(route, {"can", "roadEncodeIdx"}, {}, nullptr, use_qcam ? REPLAY_FLAG_QCAMERA : 0, data_dir, this); + replay->setSegmentCacheLimit(settings.cached_segment_limit); replay->installEventFilter(event_filter, this); QObject::connect(replay, &Replay::segmentsMerged, this, &CANMessages::segmentsMerged); if (replay->load()) { @@ -38,11 +42,11 @@ void CANMessages::process(QHash> *messages) { ++counters[it.key()]; auto &msgs = can_msgs[it.key()]; const auto &new_msgs = it.value(); - if (msgs.size() == CAN_MSG_LOG_SIZE || can_msgs[it.key()].size() == 0) { + if (new_msgs.size() == settings.can_msg_log_size || msgs.empty()) { msgs = std::move(new_msgs); } else { msgs.insert(msgs.begin(), std::make_move_iterator(new_msgs.begin()), std::make_move_iterator(new_msgs.end())); - while (msgs.size() >= CAN_MSG_LOG_SIZE) { + while (msgs.size() >= settings.can_msg_log_size) { msgs.pop_back(); } } @@ -71,7 +75,7 @@ bool CANMessages::eventFilter(const Event *event) { for (const auto &c : can_events) { QString id = QString("%1:%2").arg(c.getSrc()).arg(c.getAddress(), 1, 16); auto &list = (*received_msgs)[id]; - while (list.size() >= CAN_MSG_LOG_SIZE) { + while (list.size() >= settings.can_msg_log_size) { list.pop_back(); } CanData &data = list.emplace_front(); @@ -80,7 +84,7 @@ bool CANMessages::eventFilter(const Event *event) { data.dat.append((char *)c.getDat().begin(), c.getDat().size()); } - if (current_sec < prev_update_sec || (current_sec - prev_update_sec) > 1.0 / FPS) { + if (current_sec < prev_update_sec || (current_sec - prev_update_sec) > 1.0 / settings.fps) { prev_update_sec = current_sec; // use pointer to avoid data copy in queued connection. emit received(received_msgs.release()); @@ -121,3 +125,27 @@ void CANMessages::segmentsMerged() { void CANMessages::resetRange() { setRange(event_begin_sec, event_end_sec); } + +void CANMessages::settingChanged() { + replay->setSegmentCacheLimit(settings.cached_segment_limit); +} + +// Settings + +Settings::Settings() { + load(); +} + +void Settings::save() { + QSettings s("settings", QSettings::IniFormat); + s.setValue("fps", fps); + s.setValue("log_size", can_msg_log_size); + s.setValue("cached_segment", cached_segment_limit); +} + +void Settings::load() { + QSettings s("settings", QSettings::IniFormat); + fps = s.value("fps", 10).toInt(); + can_msg_log_size = s.value("log_size", 100).toInt(); + cached_segment_limit = s.value("cached_segment", 3.).toInt(); +} diff --git a/tools/cabana/canmessages.h b/tools/cabana/canmessages.h index a2af2a084c..3d33f801a7 100644 --- a/tools/cabana/canmessages.h +++ b/tools/cabana/canmessages.h @@ -8,8 +8,21 @@ #include "tools/replay/replay.h" -const int FPS = 10; -const int CAN_MSG_LOG_SIZE = 100; +class Settings : public QObject { + Q_OBJECT + +public: + Settings(); + void save(); + void load(); + + int fps = 10; + int can_msg_log_size = 100; + int cached_segment_limit = 3; + +signals: + void changed(); +}; struct CanData { double ts; @@ -57,6 +70,7 @@ public: protected: void process(QHash> *); void segmentsMerged(); + void settingChanged(); std::atomic current_sec = 0.; std::atomic seeking = false; @@ -82,3 +96,4 @@ inline const QString &getColor(int i) { // A global pointer referring to the unique CANMessages object extern CANMessages *can; +extern Settings settings; diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc index 6fa24ea21d..c9d9c85141 100644 --- a/tools/cabana/mainwin.cc +++ b/tools/cabana/mainwin.cc @@ -1,7 +1,9 @@ #include "tools/cabana/mainwin.h" #include +#include #include +#include #include #include @@ -23,6 +25,9 @@ MainWindow::MainWindow() : QWidget() { right_container->setFixedWidth(640); r_layout = new QVBoxLayout(right_container); + QPushButton *settings_btn = new QPushButton("Settings"); + r_layout->addWidget(settings_btn, 0, Qt::AlignRight); + video_widget = new VideoWidget(this); r_layout->addWidget(video_widget, 0, Qt::AlignTop); @@ -34,6 +39,7 @@ MainWindow::MainWindow() : QWidget() { QObject::connect(messages_widget, &MessagesWidget::msgSelectionChanged, detail_widget, &DetailWidget::setMessage); QObject::connect(detail_widget, &DetailWidget::showChart, charts_widget, &ChartsWidget::addChart); QObject::connect(charts_widget, &ChartsWidget::dock, this, &MainWindow::dockCharts); + QObject::connect(settings_btn, &QPushButton::clicked, this, &MainWindow::setOption); } void MainWindow::dockCharts(bool dock) { @@ -59,3 +65,51 @@ void MainWindow::closeEvent(QCloseEvent *event) { floating_window->deleteLater(); QWidget::closeEvent(event); } + +void MainWindow::setOption() { + SettingsDlg dlg(this); + dlg.exec(); +} + +// SettingsDlg + +SettingsDlg::SettingsDlg(QWidget *parent) : QDialog(parent) { + setWindowTitle(tr("Settings")); + QVBoxLayout *main_layout = new QVBoxLayout(this); + QFormLayout *form_layout = new QFormLayout(); + + fps = new QSpinBox(this); + fps->setRange(10, 100); + fps->setSingleStep(10); + fps->setValue(settings.fps); + form_layout->addRow("FPS", fps); + + log_size = new QSpinBox(this); + log_size->setRange(50, 500); + log_size->setSingleStep(10); + log_size->setValue(settings.can_msg_log_size); + form_layout->addRow(tr("Log size"), log_size); + + cached_segment = new QSpinBox(this); + cached_segment->setRange(3, 60); + cached_segment->setSingleStep(1); + cached_segment->setValue(settings.cached_segment_limit); + form_layout->addRow(tr("Cached segments limit"), cached_segment); + + main_layout->addLayout(form_layout); + + auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); + main_layout->addWidget(buttonBox); + + setFixedWidth(360); + connect(buttonBox, &QDialogButtonBox::accepted, this, &SettingsDlg::save); + connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); +} + +void SettingsDlg::save() { + settings.fps = fps->value(); + settings.can_msg_log_size = log_size->value(); + settings.cached_segment_limit = cached_segment->value(); + settings.save(); + accept(); +} diff --git a/tools/cabana/mainwin.h b/tools/cabana/mainwin.h index b0d7c273da..14c4b1dfa9 100644 --- a/tools/cabana/mainwin.h +++ b/tools/cabana/mainwin.h @@ -14,6 +14,7 @@ public: protected: void closeEvent(QCloseEvent *event) override; + void setOption(); VideoWidget *video_widget; MessagesWidget *messages_widget; @@ -22,3 +23,14 @@ protected: QWidget *floating_window = nullptr; QVBoxLayout *r_layout; }; + +class SettingsDlg : public QDialog { + Q_OBJECT + +public: + SettingsDlg(QWidget *parent); + void save(); + QSpinBox *fps; + QSpinBox *log_size ; + QSpinBox *cached_segment; +}; diff --git a/tools/replay/replay.cc b/tools/replay/replay.cc index 80e58b47a3..1337a4ef2c 100644 --- a/tools/replay/replay.cc +++ b/tools/replay/replay.cc @@ -211,7 +211,7 @@ void Replay::queueSegment() { SegmentMap::iterator cur, end; cur = end = segments_.lower_bound(std::min(current_segment_.load(), segments_.rbegin()->first)); - for (int i = 0; end != segments_.end() && i <= FORWARD_SEGS; ++i) { + for (int i = 0; end != segments_.end() && i <= segment_cache_limit + FORWARD_FETCH_SEGS; ++i) { ++end; } // load one segment at a time @@ -250,7 +250,7 @@ void Replay::mergeSegments(const SegmentMap::iterator &begin, const SegmentMap:: // merge 3 segments in sequence. std::vector segments_need_merge; size_t new_events_size = 0; - for (auto it = begin; it != end && it->second && it->second->isLoaded() && segments_need_merge.size() < 3; ++it) { + for (auto it = begin; it != end && it->second && it->second->isLoaded() && segments_need_merge.size() < segment_cache_limit; ++it) { segments_need_merge.push_back(it->first); new_events_size += it->second->log->events.size(); } diff --git a/tools/replay/replay.h b/tools/replay/replay.h index fbb36bd1ed..88c285125a 100644 --- a/tools/replay/replay.h +++ b/tools/replay/replay.h @@ -10,7 +10,7 @@ const QString DEMO_ROUTE = "4cf7a6ad03080c90|2021-09-29--13-46-36"; // one segment uses about 100M of memory -constexpr int FORWARD_SEGS = 5; +constexpr int FORWARD_FETCH_SEGS = 3; enum REPLAY_FLAGS { REPLAY_FLAG_NONE = 0x0000, @@ -57,6 +57,8 @@ public: filter_opaque = opaque; event_filter = filter; } + inline int segmentCacheLimit() const { return segment_cache_limit; } + inline void setSegmentCacheLimit(int n) { segment_cache_limit = std::max(3, n); } inline bool hasFlag(REPLAY_FLAGS flag) const { return flags_ & flag; } inline void addFlag(REPLAY_FLAGS flag) { flags_ |= flag; } inline void removeFlag(REPLAY_FLAGS flag) { flags_ &= ~flag; } @@ -131,4 +133,5 @@ protected: float speed_ = 1.0; replayEventFilter event_filter = nullptr; void *filter_opaque = nullptr; + int segment_cache_limit = 3; }; From 1d8fc4d21caf55368209b7bbafa34327962a6a97 Mon Sep 17 00:00:00 2001 From: jp-solutionz <47436082+jp-solutionz@users.noreply.github.com> Date: Thu, 13 Oct 2022 16:48:22 +1300 Subject: [PATCH 039/101] joystickd: add controller mapping (#25986) * Correct default controller mapping. Current config maps steering to right trigger (ABS_RZ) when using a default xinput controller: https://inputs.readthedocs.io/en/latest/user/hardwaresupport.html This results in default full left steering angle (1) requiring right trigger to return to centre (0) or right (-1). It appears the intended mapping for steering is right thumbstick (ABS_RX). Cancel button is also non-existent on default xinput controller. May be X button (BTN_NORTH) or Right Trigger (ABS_RZ). Tested on Xbox One Controller via USB Cable, Logitech F710 and GameSir T4 Pro. * Update joystickd.py Fixed comment * gamepad configuration * gamepad arg Co-authored-by: Cameron Clough --- tools/joystick/joystickd.py | 26 +++++++++++++++++--------- 1 file changed, 17 insertions(+), 9 deletions(-) diff --git a/tools/joystick/joystickd.py b/tools/joystick/joystickd.py index 8374cf8a74..b31dab83fe 100755 --- a/tools/joystick/joystickd.py +++ b/tools/joystick/joystickd.py @@ -38,13 +38,20 @@ class Keyboard: class Joystick: - def __init__(self): + def __init__(self, gamepad=False): # TODO: find a way to get this from API, perhaps "inputs" doesn't support it - self.min_axis_value = {'ABS_Y': 0., 'ABS_RZ': 0.} - self.max_axis_value = {'ABS_Y': 255., 'ABS_RZ': 255.} - self.cancel_button = 'BTN_TRIGGER' - self.axes_values = {'ABS_Y': 0., 'ABS_RZ': 0.} # gb, steer - self.axes_order = ['ABS_Y', 'ABS_RZ'] + if gamepad: + self.cancel_button = 'BTN_NORTH' # (BTN_NORTH=X, ABS_RZ=Right Trigger) + accel_axis = 'ABS_Y' + steer_axis = 'ABS_RX' + else: + self.cancel_button = 'BTN_TRIGGER' + accel_axis = 'ABS_Y' + steer_axis = 'ABS_RZ' + self.min_axis_value = {accel_axis: 0., steer_axis: 0.} + self.max_axis_value = {accel_axis: 255., steer_axis: 255.} + self.axes_values = {accel_axis: 0., steer_axis: 0.} + self.axes_order = [accel_axis, steer_axis] self.cancel = False def update(self): @@ -80,9 +87,8 @@ def send_thread(joystick): requests.get("http://"+os.environ["WEB"]+":5000/control/%f/%f" % tuple([joystick.axes_values[a] for a in joystick.axes_order][::-1]), timeout=None) rk.keep_time() -def joystick_thread(use_keyboard): +def joystick_thread(joystick): Params().put_bool('JoystickDebugMode', True) - joystick = Keyboard() if use_keyboard else Joystick() threading.Thread(target=send_thread, args=(joystick,), daemon=True).start() while True: joystick.update() @@ -92,6 +98,7 @@ if __name__ == '__main__': 'openpilot must be offroad before starting joysticked.', formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument('--keyboard', action='store_true', help='Use your keyboard instead of a joystick') + parser.add_argument('--gamepad', action='store_true', help='Use gamepad configuration instead of joystick') args = parser.parse_args() if not Params().get_bool("IsOffroad") and "ZMQ" not in os.environ and "WEB" not in os.environ: @@ -108,4 +115,5 @@ if __name__ == '__main__': else: print('Using joystick, make sure to run cereal/messaging/bridge on your device if running over the network!') - joystick_thread(args.keyboard) + joystick = Keyboard() if args.keyboard else Joystick(args.gamepad) + joystick_thread(joystick) From c782380fc1cfcbc7b521f14db37a360aef6b53ec Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 12 Oct 2022 21:54:08 -0700 Subject: [PATCH 040/101] Hyundai: share panda flags with CAN-FD platform (#26058) * Hyundai: share panda flags with CAN-FD platform * move that * only set bit * bump panda * panda master * regen + update refs for new param --- panda | 2 +- selfdrive/car/hyundai/interface.py | 19 +++++++------------ selfdrive/car/hyundai/values.py | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/test/process_replay/regen.py | 4 +++- .../test/process_replay/test_processes.py | 2 +- 6 files changed, 14 insertions(+), 17 deletions(-) diff --git a/panda b/panda index 2f3e2825e5..622ce923e9 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 2f3e2825e5ecc8074b4ee9cb9a70df635d09fd10 +Subproject commit 622ce923e901c634aab4c29be68638e38b0fcc16 diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 024d7498fa..13e93c7d06 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -310,8 +310,6 @@ class CarInterface(CarInterfaceBase): ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.noOutput), get_safety_config(car.CarParams.SafetyModel.hyundaiCanfd)] - if ret.openpilotLongitudinalControl: - ret.safetyConfigs[1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_LONG if ret.flags & HyundaiFlags.CANFD_HDA2: ret.safetyConfigs[1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_HDA2 if ret.flags & HyundaiFlags.CANFD_ALT_BUTTONS: @@ -325,18 +323,16 @@ class CarInterface(CarInterfaceBase): else: ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hyundai, 0)] - # set appropriate safety param for gas signal - if candidate in HYBRID_CAR: - ret.safetyConfigs[0].safetyParam = 2 - elif candidate in EV_CAR: - ret.safetyConfigs[0].safetyParam = 1 - - if ret.openpilotLongitudinalControl: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HYUNDAI_LONG - if candidate in CAMERA_SCC_CAR: ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HYUNDAI_CAMERA_SCC + if ret.openpilotLongitudinalControl: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_LONG + if candidate in HYBRID_CAR: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_HYBRID_GAS + elif candidate in EV_CAR: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_EV_GAS + ret.centerToFront = ret.wheelbase * 0.4 # TODO: get actual value, for now starting with reasonable value for @@ -347,7 +343,6 @@ class CarInterface(CarInterfaceBase): # mass and CG position, so all cars will have approximately similar dyn behaviors ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, tire_stiffness_factor=tire_stiffness_factor) - return ret @staticmethod diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 68a16b096e..ecda51816d 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1383,7 +1383,7 @@ CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.TUCSON_HYBRID_4TH_GEN} CAMERA_SCC_CAR = {CAR.KONA_EV_2022, } HYBRID_CAR = {CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019} # these cars use a different gas signal -EV_CAR = {CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_NIRO_EV, CAR.KONA_EV_2022} +EV_CAR = {CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_NIRO_EV, CAR.KONA_EV_2022, CAR.KIA_EV6, CAR.IONIQ_5} # these cars require a special panda safety mode due to missing counters and checksums in the messages LEGACY_SAFETY_MODE_CAR = {CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_LF, CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.VELOSTER, CAR.KIA_STINGER, CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.KIA_CEED, CAR.ELANTRA, CAR.IONIQ_HEV_2022} diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index e01fe2ac3c..6a8f5a273c 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -14bc91c326f75ce48337720668a1744184c46994 \ No newline at end of file +1e4bb3f620bddbe6ead966d6f2dd7db3fd730308 \ No newline at end of file diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py index eee3745f8e..2653a0126a 100755 --- a/selfdrive/test/process_replay/regen.py +++ b/selfdrive/test/process_replay/regen.py @@ -30,10 +30,11 @@ def replay_panda_states(s, msgs): rk = Ratekeeper(service_list[s].frequency, print_delay_threshold=None) smsgs = [m for m in msgs if m.which() in ['pandaStates', 'pandaStateDEPRECATED']] - # TODO: new safety params from flags, remove after getting new routes for Toyota + # TODO: safety param migration should be handled automatically safety_param_migration = { "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, + "KIA EV6 2022": Panda.FLAG_HYUNDAI_EV_GAS | Panda.FLAG_HYUNDAI_CANFD_HDA2, } # Migrate safety param base on carState @@ -56,6 +57,7 @@ def replay_panda_states(s, msgs): pm.send(s, new_m) else: new_m = m.as_builder() + new_m.pandaStates[-1].safetyParam = safety_param new_m.logMonoTime = int(sec_since_boot() * 1e9) pm.send(s, new_m) diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 38ed0e07ad..683387dce8 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -40,7 +40,7 @@ source_segments = [ segments = [ ("BODY", "regenFA002A80700|2022-09-27--15-37-02--0"), ("HYUNDAI", "regenBE53A59065B|2022-09-27--16-52-03--0"), - ("HYUNDAI2", "regen11AA43BCA5F|2022-09-27--15-39-54--0"), + ("HYUNDAI2", "regenFA8B5CA9840|2022-10-12--21-47-06--0"), ("TOYOTA", "regen929C5790007|2022-09-27--16-27-47--0"), ("TOYOTA2", "regenEA3950D7F22|2022-09-27--15-43-24--0"), ("TOYOTA3", "regen89026F6BD8D|2022-09-27--15-45-37--0"), From 4ee0b8196f85b29b735c3319924f3c40cebc86e5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 12 Oct 2022 21:54:53 -0700 Subject: [PATCH 041/101] Hyundai: fix alt CAN-FD cancel (#26057) --- selfdrive/car/hyundai/carcontroller.py | 1 + selfdrive/car/hyundai/carstate.py | 4 +++- selfdrive/car/hyundai/hyundaicanfd.py | 11 ++++++----- 3 files changed, 10 insertions(+), 6 deletions(-) diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index bcbab2ab94..a5d995df25 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -117,6 +117,7 @@ class CarController: # cruise cancel if CC.cruiseControl.cancel: if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: + can_sends.append(hyundaicanfd.create_acc_cancel(self.packer, self.CP, CS.cruise_info)) self.last_button_frame = self.frame else: for _ in range(20): diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 4c2650c19f..3752fdebef 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -34,6 +34,8 @@ class CarState(CarStateBase): self.brake_error = False self.buttons_counter = 0 + self.cruise_info = {} + # On some cars, CLU15->CF_Clu_VehicleSpeed can oscillate faster than the dash updates. Sample at 5 Hz self.cluster_speed = 0 self.cluster_speed_counter = CLUSTER_SAMPLE_RATE @@ -194,13 +196,13 @@ class CarState(CarStateBase): cp_cruise_info = cp if self.CP.flags & HyundaiFlags.CANFD_HDA2 else cp_cam ret.cruiseState.speed = cp_cruise_info.vl["CRUISE_INFO"]["SET_SPEED"] * speed_factor ret.cruiseState.standstill = cp_cruise_info.vl["CRUISE_INFO"]["CRUISE_STANDSTILL"] == 1 + self.cruise_info = copy.copy(cp_cruise_info.vl["CRUISE_INFO"]) cruise_btn_msg = "CRUISE_BUTTONS_ALT" if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else "CRUISE_BUTTONS" self.prev_cruise_buttons = self.cruise_buttons[-1] self.cruise_buttons.extend(cp.vl_all[cruise_btn_msg]["CRUISE_BUTTONS"]) self.main_buttons.extend(cp.vl_all[cruise_btn_msg]["ADAPTIVE_CRUISE_MAIN_BTN"]) self.buttons_counter = cp.vl[cruise_btn_msg]["COUNTER"] - self.cruise_info_copy = {} if self.CP.flags & HyundaiFlags.CANFD_HDA2: self.cam_0x2a4 = copy.copy(cp_cam.vl["CAM_0x2a4"]) diff --git a/selfdrive/car/hyundai/hyundaicanfd.py b/selfdrive/car/hyundai/hyundaicanfd.py index 9d4e4d4e0d..f2cbafdcf0 100644 --- a/selfdrive/car/hyundai/hyundaicanfd.py +++ b/selfdrive/car/hyundai/hyundaicanfd.py @@ -47,12 +47,13 @@ def create_buttons(packer, cnt, btn): } return packer.make_can_msg("CRUISE_BUTTONS", 5, values) -def create_cruise_info(packer, cruise_info_copy, cancel): +def create_acc_cancel(packer, CP, cruise_info_copy): values = cruise_info_copy - if cancel: - values["CRUISE_STATUS"] = 0 - values["CRUISE_INACTIVE"] = 1 - return packer.make_can_msg("CRUISE_INFO", 5, values) + values.update({ + "CRUISE_STATUS": 0, + "CRUISE_INACTIVE": 1, + }) + return packer.make_can_msg("CRUISE_INFO", get_e_can_bus(CP), values) def create_lfahda_cluster(packer, CP, enabled): values = { From 82bd082dcd3e9f38a0f7a766242b6979a611a567 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 12 Oct 2022 22:12:24 -0700 Subject: [PATCH 042/101] Hyundai: split alt gas pressed signals by EV and ICE (#26061) --- panda | 2 +- selfdrive/car/hyundai/carstate.py | 22 +++++++++++----------- 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/panda b/panda index 622ce923e9..de380961fc 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 622ce923e901c634aab4c29be68638e38b0fcc16 +Subproject commit de380961fcfece68137ea0c4f5dc07f2763a4aaf diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 3752fdebef..948634e974 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -154,7 +154,7 @@ class CarState(CarStateBase): def update_canfd(self, cp, cp_cam): ret = car.CarState.new_message() - if self.CP.flags & HyundaiFlags.CANFD_HDA2: + if self.CP.carFingerprint in EV_CAR: ret.gas = cp.vl["ACCELERATOR"]["ACCELERATOR_PEDAL"] / 255. else: ret.gas = cp.vl["ACCELERATOR_ALT"]["ACCELERATOR_PEDAL"] / 1023. @@ -450,22 +450,22 @@ class CarState(CarStateBase): ("DOORS_SEATBELTS", 4), ] - if CP.flags & HyundaiFlags.CANFD_HDA2: + if CP.flags & HyundaiFlags.CANFD_HDA2 and not CP.openpilotLongitudinalControl: + signals += [ + ("SET_SPEED", "CRUISE_INFO"), + ("CRUISE_STANDSTILL", "CRUISE_INFO"), + ] + checks += [ + ("CRUISE_INFO", 50), + ] + + if CP.carFingerprint in EV_CAR: signals += [ ("ACCELERATOR_PEDAL", "ACCELERATOR"), - ("GEAR", "ACCELERATOR"), ] checks += [ ("ACCELERATOR", 100), ] - if not CP.openpilotLongitudinalControl: - signals += [ - ("SET_SPEED", "CRUISE_INFO"), - ("CRUISE_STANDSTILL", "CRUISE_INFO"), - ] - checks += [ - ("CRUISE_INFO", 50), - ] else: signals += [ ("ACCELERATOR_PEDAL", "ACCELERATOR_ALT"), From 6a602ed41dd0b3712c2440b768220b18b1fcfd10 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 12 Oct 2022 22:12:52 -0700 Subject: [PATCH 043/101] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index de380961fc..c39528d299 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit de380961fcfece68137ea0c4f5dc07f2763a4aaf +Subproject commit c39528d299aae6a1ebbdbccddeae55bc76a534e3 From 7f3c070061da864bd18820ba5589e4ee7fbae0db Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Wed, 12 Oct 2022 22:28:07 -0700 Subject: [PATCH 044/101] Hyundai: add missing Elantra Hybrid 2023 FW versions (#26055) * add Hyundai Elantra HEV 2023 fw 8dcf421697cd2cb0|2022-10-12--16-12-21--0 VIN: KMHLN4AJ5PU042417 * add 2023 to docs * delete * fix fingerprint Co-authored-by: Shane Smiskol --- docs/CARS.md | 2 +- selfdrive/car/hyundai/values.py | 15 +++++++++------ 2 files changed, 10 insertions(+), 7 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 82ef37ae8d..f5cc5acaeb 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -55,7 +55,7 @@ A supported vehicle is one that just works when you install a comma three. All s |Honda|Ridgeline 2017-22|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| |Hyundai|Elantra 2017-19|Smart Cruise Control (SCC)|Stock|19 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| |Hyundai|Elantra 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| -|Hyundai|Elantra Hybrid 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| +|Hyundai|Elantra Hybrid 2021-23|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| |Hyundai|Genesis 2015-16|Smart Cruise Control (SCC)|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai J| |Hyundai|Ioniq 5 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai Q| |Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index ecda51816d..1a8fb14eec 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -109,7 +109,7 @@ class HyundaiCarInfo(CarInfo): CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { CAR.ELANTRA: HyundaiCarInfo("Hyundai Elantra 2017-19", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_b), CAR.ELANTRA_2021: HyundaiCarInfo("Hyundai Elantra 2021-22", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k), - CAR.ELANTRA_HEV_2021: HyundaiCarInfo("Hyundai Elantra Hybrid 2021-22", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k), + CAR.ELANTRA_HEV_2021: HyundaiCarInfo("Hyundai Elantra Hybrid 2021-23", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k), CAR.ELANTRA_GT_I30: [ HyundaiCarInfo("Hyundai Elantra GT 2017-19", harness=Harness.hyundai_e), HyundaiCarInfo("Hyundai i30 2019", harness=Harness.hyundai_e), @@ -1218,26 +1218,29 @@ FW_VERSIONS = { ], }, CAR.ELANTRA_HEV_2021: { - (Ecu.fwdCamera, 0x7c4, None) : [ + (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.05 99210-AA000 210930', b'\xf1\000CN7HMFC AT USA LHD 1.00 1.03 99210-AA000 200819', + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.07 99210-AA000 220426', ], - (Ecu.fwdRadar, 0x7d0, None) : [ + (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\000CNhe SCC FHCUP 1.00 1.01 99110-BY000 ', b'\xf1\x8799110BY000\xf1\x00CNhe SCC FHCUP 1.00 1.01 99110-BY000 ', ], - (Ecu.eps, 0x7d4, None) :[ + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CN7 MDPS C 1.00 1.03 56310BY0500 4CNHC103', b'\xf1\x8756310/BY050\xf1\x00CN7 MDPS C 1.00 1.03 56310/BY050 4CNHC103', b'\xf1\x8756310/BY050\xf1\000CN7 MDPS C 1.00 1.02 56310/BY050 4CNHC102', ], - (Ecu.transmission, 0x7e1, None) :[ + (Ecu.transmission, 0x7e1, None): [ b'\xf1\0006U3L0_C2\000\0006U3K3051\000\000HCN0G16NS0\xb9?A\xaa', b'\xf1\0006U3L0_C2\000\0006U3K3051\000\000HCN0G16NS0\000\000\000\000', b'\xf1\x816U3K3051\000\000\xf1\0006U3L0_C2\000\0006U3K3051\000\000HCN0G16NS0\xb9?A\xaa', b'\xf1\x816U3K3051\x00\x00\xf1\x006U3L0_C2\x00\x006U3K3051\x00\x00HCN0G16NS0\x00\x00\x00\x00', ], - (Ecu.engine, 0x7e0, None) : [ + (Ecu.engine, 0x7e0, None): [ b'\xf1\x816H6G5051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x816H6G6051\x00\x00\x00\x00\x00\x00\x00\x00', ] }, CAR.KONA_HEV: { From bf5f9adcc853c9fef6bdcfed027a588aa1940384 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 12 Oct 2022 22:34:40 -0700 Subject: [PATCH 045/101] boardd: don't multiplex OBD port on external pandas (#26062) don't multiplex on ext pandas --- selfdrive/boardd/boardd.cc | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 77e86f9458..2d613b68ce 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -113,8 +113,9 @@ bool safety_setter_thread(std::vector pandas) { } // set to ELM327 for fingerprinting - for (Panda *panda : pandas) { - panda->set_safety_model(cereal::CarParams::SafetyModel::ELM327); + for (int i = 0; i < pandas.size(); i++) { + const uint16_t safety_param = (i > 0) ? 1U : 0U; + pandas[i]->set_safety_model(cereal::CarParams::SafetyModel::ELM327, safety_param); } Params p = Params(); From 649eaf273ff245dbf8279d86d4acb9ea36a9d5d2 Mon Sep 17 00:00:00 2001 From: hoomoose <94947902+hoomoose@users.noreply.github.com> Date: Thu, 13 Oct 2022 10:34:59 -0600 Subject: [PATCH 046/101] Hyundai: support HDA1 EV6 and Ioniq 5 (#25723) it's hda1 time Co-authored-by: Adeeb Shihadeh --- selfdrive/car/hyundai/values.py | 10 ++++++++-- selfdrive/car/tests/routes.py | 3 ++- 2 files changed, 10 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 1a8fb14eec..2d5e6792ee 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -141,7 +141,10 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { ], CAR.VELOSTER: HyundaiCarInfo("Hyundai Veloster 2019-20", min_enable_speed=5. * CV.MPH_TO_MS, harness=Harness.hyundai_e), CAR.SONATA_HYBRID: HyundaiCarInfo("Hyundai Sonata Hybrid 2020-22", "All", harness=Harness.hyundai_a), - CAR.IONIQ_5: HyundaiCarInfo("Hyundai Ioniq 5 2022", "Highway Driving Assist II", harness=Harness.hyundai_q), + CAR.IONIQ_5: [ + HyundaiCarInfo("Hyundai Ioniq 5 2022 (without HDA II)" , "Highway Driving Assist", harness=Harness.hyundai_k), + HyundaiCarInfo("Hyundai Ioniq 5 2022 (with HDA II)", "Highway Driving Assist II", harness=Harness.hyundai_q), + ], CAR.TUCSON_HYBRID_4TH_GEN: HyundaiCarInfo("Hyundai Tucson Hybrid 2022", "All", harness=Harness.hyundai_n), # Kia @@ -171,7 +174,10 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { ], 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", "Highway Driving Assist II", harness=Harness.hyundai_p), + CAR.KIA_EV6: [ + HyundaiCarInfo("Kia EV6 2022 (without HDA II)", "Highway Driving Assist", harness=Harness.hyundai_l), + HyundaiCarInfo("Kia EV6 2022 (with HDA II)", "Highway Driving Assist II", harness=Harness.hyundai_p) + ], # Genesis CAR.GENESIS_G70: HyundaiCarInfo("Genesis G70 2018-19", "All", harness=Harness.hyundai_f), diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index ac56cc106b..85787ae88d 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -110,7 +110,8 @@ routes = [ CarTestRoute("49f3c13141b6bc87|2021-07-28--08-05-13", HYUNDAI.KONA_HEV), CarTestRoute("5dddcbca6eb66c62|2020-07-26--13-24-19", HYUNDAI.KIA_STINGER), CarTestRoute("d624b3d19adce635|2020-08-01--14-59-12", HYUNDAI.VELOSTER), - CarTestRoute("d824e27e8c60172c|2022-05-19--16-15-28", HYUNDAI.KIA_EV6), + CarTestRoute("d824e27e8c60172c|2022-05-19--16-15-28", HYUNDAI.KIA_EV6), # HDA2 + CarTestRoute("68d6a96e703c00c9|2022-09-10--16-09-39", HYUNDAI.KIA_EV6), # HDA1 CarTestRoute("007d5e4ad9f86d13|2021-09-30--15-09-23", HYUNDAI.KIA_K5_2021), CarTestRoute("50c6c9b85fd1ff03|2020-10-26--17-56-06", HYUNDAI.KIA_NIRO_EV), CarTestRoute("173219cf50acdd7b|2021-07-05--10-27-41", HYUNDAI.KIA_NIRO_PHEV), From 40dc05db6db4b5944b9fc43b506148a1c854d423 Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Thu, 13 Oct 2022 10:40:46 -0700 Subject: [PATCH 047/101] update car compatibility docs changes from 649eaf2 --- docs/CARS.md | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index f5cc5acaeb..77d6b890db 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -4,7 +4,7 @@ A supported vehicle is one that just works when you install a comma three. All supported cars provide a better experience than any stock system. -# 206 Supported Cars +# 208 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Harness| |---|---|---|:---:|:---:|:---:|:---:|:---:|:---:| @@ -57,7 +57,8 @@ A supported vehicle is one that just works when you install a comma three. All s |Hyundai|Elantra 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| |Hyundai|Elantra Hybrid 2021-23|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| |Hyundai|Genesis 2015-16|Smart Cruise Control (SCC)|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai J| -|Hyundai|Ioniq 5 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai Q| +|Hyundai|Ioniq 5 2022 (with HDA II)|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai Q| +|Hyundai|Ioniq 5 2022 (without HDA II)|Highway Driving Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| |Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |Hyundai|Ioniq Electric 2020|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| @@ -83,7 +84,8 @@ A supported vehicle is one that just works when you install a comma three. All s |Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Kia|Ceed 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| -|Kia|EV6 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P| +|Kia|EV6 2022 (with HDA II)|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P| +|Kia|EV6 2022 (without HDA II)|Highway Driving Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| |Kia|Forte 2019-21|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| |Kia|K5 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| |Kia|Niro EV 2019|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| From 41f520c2540a869b6904fd8aa0eb494513b38042 Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Thu, 13 Oct 2022 11:43:20 -0700 Subject: [PATCH 048/101] don't build cabana unless extras (#26072) don't build cabana on device this caused CI to fail for xx since qt libs aren't installed in CI docker --- SConstruct | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/SConstruct b/SConstruct index 23ab37dc1e..b87327aa20 100644 --- a/SConstruct +++ b/SConstruct @@ -434,9 +434,10 @@ SConscript(['selfdrive/navd/SConscript']) if arch in ['x86_64', 'Darwin'] or GetOption('extras'): SConscript(['tools/replay/SConscript']) - opendbc = abspath([File('opendbc/can/libdbc.so')]) - Export('opendbc') - SConscript(['tools/cabana/SConscript']) + if arch in ['x86_64', 'Darwin'] and GetOption('extras'): + opendbc = abspath([File('opendbc/can/libdbc.so')]) + Export('opendbc') + SConscript(['tools/cabana/SConscript']) if GetOption('test'): SConscript('panda/tests/safety/SConscript') From 2082248b73afedbcddd9f5a83ab4974811454f2a Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Thu, 13 Oct 2022 12:48:24 -0700 Subject: [PATCH 049/101] Revert "don't build cabana unless extras (#26072)" This reverts commit 41f520c2540a869b6904fd8aa0eb494513b38042. --- SConstruct | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/SConstruct b/SConstruct index b87327aa20..23ab37dc1e 100644 --- a/SConstruct +++ b/SConstruct @@ -434,10 +434,9 @@ SConscript(['selfdrive/navd/SConscript']) if arch in ['x86_64', 'Darwin'] or GetOption('extras'): SConscript(['tools/replay/SConscript']) - if arch in ['x86_64', 'Darwin'] and GetOption('extras'): - opendbc = abspath([File('opendbc/can/libdbc.so')]) - Export('opendbc') - SConscript(['tools/cabana/SConscript']) + opendbc = abspath([File('opendbc/can/libdbc.so')]) + Export('opendbc') + SConscript(['tools/cabana/SConscript']) if GetOption('test'): SConscript('panda/tests/safety/SConscript') From 5f7d9a519e98b446b14866a8920dd0493b4dce26 Mon Sep 17 00:00:00 2001 From: Vivek Aithal Date: Thu, 13 Oct 2022 13:21:35 -0700 Subject: [PATCH 050/101] regen: Refactor log migrate functions to avoid needing azure keys (#26049) * refactor migrate fns to avoid needing to use azure keys on import * move azure key init behind a function * resolve comments --- selfdrive/test/process_replay/regen.py | 3 ++- selfdrive/test/update_ci_routes.py | 20 +++++++++++++------- 2 files changed, 15 insertions(+), 8 deletions(-) diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py index 2653a0126a..c9f9c6c362 100755 --- a/selfdrive/test/process_replay/regen.py +++ b/selfdrive/test/process_replay/regen.py @@ -224,13 +224,14 @@ def migrate_sensorEvents(lr, old_logtime=False): m_dat.sensor = evt.sensor m_dat.type = evt.type m_dat.source = evt.source + if old_logtime: + m_dat.timestamp = evt.timestamp setattr(m_dat, evt.which(), getattr(evt, evt.which())) all_msgs.append(m.as_reader()) return all_msgs - def regen_segment(lr, frs=None, outdir=FAKEDATA, disable_tqdm=False): lr = migrate_carparams(list(lr)) lr = migrate_sensorEvents(list(lr)) diff --git a/selfdrive/test/update_ci_routes.py b/selfdrive/test/update_ci_routes.py index a1e8c35f6b..201ffb745a 100755 --- a/selfdrive/test/update_ci_routes.py +++ b/selfdrive/test/update_ci_routes.py @@ -14,11 +14,16 @@ SOURCES = [ (_DATA_ACCOUNT_CI, "commadataci"), ] -DEST_KEY = azureutil.get_user_token(_DATA_ACCOUNT_CI, "openpilotci") -SOURCE_KEYS = [azureutil.get_user_token(account, bucket) for account, bucket in SOURCES] -SERVICE = BlockBlobService(_DATA_ACCOUNT_CI, sas_token=DEST_KEY) + +def get_azure_keys(): + dest_key = azureutil.get_user_token(_DATA_ACCOUNT_CI, "openpilotci") + source_keys = [azureutil.get_user_token(account, bucket) for account, bucket in SOURCES] + service = BlockBlobService(_DATA_ACCOUNT_CI, sas_token=dest_key) + return dest_key, source_keys, service + def upload_route(path, exclude_patterns=None): + dest_key, _, _ = get_azure_keys() if exclude_patterns is None: exclude_patterns = ['*/dcamera.hevc'] @@ -29,27 +34,28 @@ def upload_route(path, exclude_patterns=None): "azcopy", "copy", f"{path}/*", - f"https://{_DATA_ACCOUNT_CI}.blob.core.windows.net/openpilotci/{destpath}?{DEST_KEY}", + f"https://{_DATA_ACCOUNT_CI}.blob.core.windows.net/openpilotci/{destpath}?{dest_key}", "--recursive=false", "--overwrite=false", ] + [f"--exclude-pattern={p}" for p in exclude_patterns] subprocess.check_call(cmd) def sync_to_ci_public(route): + dest_key, source_keys, service = get_azure_keys() key_prefix = route.replace('|', '/') dongle_id = key_prefix.split('/')[0] - if next(azureutil.list_all_blobs(SERVICE, "openpilotci", prefix=key_prefix), None) is not None: + if next(azureutil.list_all_blobs(service, "openpilotci", prefix=key_prefix), None) is not None: return True print(f"Uploading {route}") - for (source_account, source_bucket), source_key in zip(SOURCES, SOURCE_KEYS): + for (source_account, source_bucket), source_key in zip(SOURCES, source_keys): print(f"Trying {source_account}/{source_bucket}") cmd = [ "azcopy", "copy", f"https://{source_account}.blob.core.windows.net/{source_bucket}/{key_prefix}?{source_key}", - f"https://{_DATA_ACCOUNT_CI}.blob.core.windows.net/openpilotci/{dongle_id}?{DEST_KEY}", + f"https://{_DATA_ACCOUNT_CI}.blob.core.windows.net/openpilotci/{dongle_id}?{dest_key}", "--recursive=true", "--overwrite=false", "--exclude-pattern=*/dcamera.hevc", From cc6dd18cf0115458f28135b10e3d935ee4119e04 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 14 Oct 2022 04:24:55 +0800 Subject: [PATCH 051/101] Cabana: display the (x,y) values while MouseMove on the chart (#26064) --- tools/cabana/chartswidget.cc | 122 ++++++++++++++++++++++------------- tools/cabana/chartswidget.h | 41 ++++++------ 2 files changed, 96 insertions(+), 67 deletions(-) diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index 2fc3fecb2a..e704dea95a 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -3,7 +3,6 @@ #include #include #include -#include #include #include @@ -136,8 +135,7 @@ bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) { // ChartWidget ChartWidget::ChartWidget(const QString &id, const QString &sig_name, QWidget *parent) : id(id), sig_name(sig_name), QWidget(parent) { - QStackedLayout *stacked = new QStackedLayout(this); - stacked->setStackingMode(QStackedLayout::StackAll); + QVBoxLayout *main_layout = new QVBoxLayout(this); QWidget *chart_widget = new QWidget(this); QVBoxLayout *chart_layout = new QVBoxLayout(chart_widget); @@ -159,9 +157,23 @@ ChartWidget::ChartWidget(const QString &id, const QString &sig_name, QWidget *pa header_layout->addWidget(remove_btn); chart_layout->addWidget(header); + chart_view = new ChartView(id, sig_name, this); + chart_view->setFixedHeight(300); + chart_layout->addWidget(chart_view); + chart_layout->addStretch(); + + main_layout->addWidget(chart_widget); + + setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Fixed); +} + +// ChartView + +ChartView::ChartView(const QString &id, const QString &sig_name, QWidget *parent) + : id(id), sig_name(sig_name), QChartView(nullptr, parent) { QLineSeries *series = new QLineSeries(); series->setUseOpenGL(true); - auto chart = new QChart(); + QChart *chart = new QChart(); chart->setTitle(sig_name); chart->addSeries(series); chart->createDefaultAxes(); @@ -172,28 +184,26 @@ ChartWidget::ChartWidget(const QString &id, const QString &sig_name, QWidget *pa chart->setMargins({0, 0, 0, 0}); chart->layout()->setContentsMargins(0, 0, 0, 0); - chart_view = new ChartView(chart); - chart_view->setFixedHeight(300); - chart_view->setRenderHint(QPainter::Antialiasing); - chart_view->setRubberBand(QChartView::HorizontalRubberBand); - if (auto rubber = chart_view->findChild()) { + track_line = new QGraphicsLineItem(chart); + track_line->setPen(QPen(Qt::gray, 1, Qt::DashLine)); + value_text = new QGraphicsSimpleTextItem(chart); + value_text->setBrush(Qt::gray); + line_marker = new QGraphicsLineItem(chart); + line_marker->setPen(QPen(Qt::black, 2)); + + setChart(chart); + + setRenderHint(QPainter::Antialiasing); + setRubberBand(QChartView::HorizontalRubberBand); + if (auto rubber = findChild()) { QPalette pal; pal.setBrush(QPalette::Base, QColor(0, 0, 0, 80)); rubber->setPalette(pal); } - chart_layout->addWidget(chart_view); - chart_layout->addStretch(); - stacked->addWidget(chart_widget); - line_marker = new LineMarker(this); - stacked->addWidget(line_marker); - line_marker->setAttribute(Qt::WA_TransparentForMouseEvents, true); - line_marker->raise(); - - setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Fixed); - QObject::connect(can, &CANMessages::updated, this, &ChartWidget::updateState); - QObject::connect(can, &CANMessages::rangeChanged, this, &ChartWidget::rangeChanged); - QObject::connect(can, &CANMessages::eventsMerged, this, &ChartWidget::updateSeries); + QObject::connect(can, &CANMessages::updated, this, &ChartView::updateState); + QObject::connect(can, &CANMessages::rangeChanged, this, &ChartView::rangeChanged); + QObject::connect(can, &CANMessages::eventsMerged, this, &ChartView::updateSeries); QObject::connect(dynamic_cast(chart->axisX()), &QValueAxis::rangeChanged, can, &CANMessages::setRange); QObject::connect(dbc(), &DBCManager::signalUpdated, [this](const QString &msg_id, const QString &sig_name) { if (this->id == msg_id && this->sig_name == sig_name) @@ -202,15 +212,13 @@ ChartWidget::ChartWidget(const QString &id, const QString &sig_name, QWidget *pa updateSeries(); } -void ChartWidget::updateState() { - auto chart = chart_view->chart(); - auto axis_x = dynamic_cast(chart->axisX()); - - int x = chart->plotArea().left() + chart->plotArea().width() * (can->currentSec() - axis_x->min()) / (axis_x->max() - axis_x->min()); - line_marker->setX(x); +void ChartView::updateState() { + auto axis_x = dynamic_cast(chart()->axisX()); + int x = chart()->plotArea().left() + chart()->plotArea().width() * (can->currentSec() - axis_x->min()) / (axis_x->max() - axis_x->min()); + line_marker->setLine(x, 0, x, height()); } -void ChartWidget::updateSeries() { +void ChartView::updateSeries() { const Signal *sig = dbc()->signal(id, sig_name); auto events = can->events(); if (!sig || !events) return; @@ -234,15 +242,16 @@ void ChartWidget::updateSeries() { } } } - QLineSeries *series = (QLineSeries *)chart_view->chart()->series()[0]; + QLineSeries *series = (QLineSeries *)chart()->series()[0]; series->replace(vals); + series->setPointLabelsColor(Qt::black); auto [begin, end] = can->range(); - chart_view->chart()->axisX()->setRange(begin, end); + chart()->axisX()->setRange(begin, end); updateAxisY(); } -void ChartWidget::rangeChanged(qreal min, qreal max) { - auto axis_x = dynamic_cast(chart_view->chart()->axisX()); +void ChartView::rangeChanged(qreal min, qreal max) { + auto axis_x = dynamic_cast(chart()->axisX()); if (axis_x->min() != min || axis_x->max() != max) { axis_x->setRange(min, max); } @@ -250,9 +259,9 @@ void ChartWidget::rangeChanged(qreal min, qreal max) { } // auto zoom on yaxis -void ChartWidget::updateAxisY() { - const auto axis_x = dynamic_cast(chart_view->chart()->axisX()); - const auto axis_y = dynamic_cast(chart_view->chart()->axisY()); +void ChartView::updateAxisY() { + const auto axis_x = dynamic_cast(chart()->axisX()); + const auto axis_y = dynamic_cast(chart()->axisY()); // vals is a sorted list auto begin = std::lower_bound(vals.begin(), vals.end(), axis_x->min(), [](auto &p, double x) { return p.x() < x; }); if (begin == vals.end()) @@ -271,7 +280,17 @@ void ChartWidget::updateAxisY() { } } -// ChartView +void ChartView::enterEvent(QEvent *event) { + track_line->setVisible(true); + value_text->setVisible(true); + QChartView::enterEvent(event); +} + +void ChartView::leaveEvent(QEvent *event) { + track_line->setVisible(false); + value_text->setVisible(false); + QChartView::leaveEvent(event); +} void ChartView::mouseReleaseEvent(QMouseEvent *event) { auto rubber = findChild(); @@ -289,20 +308,31 @@ void ChartView::mouseReleaseEvent(QMouseEvent *event) { } // TODO: right-click to reset zoom QChartView::mouseReleaseEvent(event); + line_marker->setVisible(true); } +void ChartView::mouseMoveEvent(QMouseEvent *ev) { + auto rubber = findChild(); + bool show = !(rubber && rubber->isVisible()); -// LineMarker + if (show) { + const auto plot_area = chart()->plotArea(); + float x = std::clamp((float)ev->pos().x(), (float)plot_area.left(), (float)plot_area.right()); + track_line->setLine(x, plot_area.top(), x, plot_area.bottom()); -void LineMarker::setX(double x) { - if (x != x_pos) { - x_pos = x; - update(); + auto [begin, end] = can->range(); + double sec = begin + ((x - plot_area.x()) / plot_area.width()) * (end - begin); + auto value = std::lower_bound(vals.begin(), vals.end(), sec, [](auto &p, double x) { return p.x() < x; }); + value_text->setPos(x + 6, plot_area.bottom() - 25); + if (value != vals.end()) { + value_text->setText(QString("(%1, %2)").arg(value->x(), 0, 'f', 3).arg(value->y())); + } else { + value_text->setText("(--, --)"); + } } -} -void LineMarker::paintEvent(QPaintEvent *event) { - QPainter p(this); - p.setPen(QPen(Qt::black, 2)); - p.drawLine(QPointF{x_pos, 50.}, QPointF{x_pos, (qreal)height() - 11}); + value_text->setVisible(show); + track_line->setVisible(show); + line_marker->setVisible(show); + QChartView::mouseMoveEvent(ev); } diff --git a/tools/cabana/chartswidget.h b/tools/cabana/chartswidget.h index 7dbf0f108b..af12560cc9 100644 --- a/tools/cabana/chartswidget.h +++ b/tools/cabana/chartswidget.h @@ -3,6 +3,8 @@ #include #include +#include +#include #include #include #include @@ -14,24 +16,29 @@ using namespace QtCharts; -class LineMarker : public QWidget { -Q_OBJECT +class ChartView : public QChartView { + Q_OBJECT public: - LineMarker(QWidget *parent) : QWidget(parent) {} - void setX(double x); + ChartView(const QString &id, const QString &sig_name, QWidget *parent = nullptr); private: - void paintEvent(QPaintEvent *event) override; - double x_pos = -1; -}; + void mouseReleaseEvent(QMouseEvent *event) override; + void mouseMoveEvent(QMouseEvent *ev) override; + void enterEvent(QEvent *event) override; + void leaveEvent(QEvent *event) override; -class ChartView : public QChartView { - Q_OBJECT + void updateSeries(); + void rangeChanged(qreal min, qreal max); + void updateAxisY(); + void updateState(); -public: - ChartView(QChart *chart, QWidget *parent = nullptr) : QChartView(chart, parent) {} - void mouseReleaseEvent(QMouseEvent *event) override; + QGraphicsLineItem *track_line; + QGraphicsSimpleTextItem *value_text; + QGraphicsLineItem *line_marker; + QList vals; + QString id; + QString sig_name; }; class ChartWidget : public QWidget { @@ -44,18 +51,10 @@ public: signals: void remove(); -private: - void updateState(); - void addData(const CanData &can_data, const Signal &sig); - void updateSeries(); - void rangeChanged(qreal min, qreal max); - void updateAxisY(); - +protected: QString id; QString sig_name; ChartView *chart_view = nullptr; - LineMarker *line_marker = nullptr; - QList vals; }; class ChartsWidget : public QWidget { From a397418ef82957289779cbfbcf9cb138d9f2cd3f Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 14 Oct 2022 04:25:21 +0800 Subject: [PATCH 052/101] Cabana: scrollable binary view (#26065) --- tools/cabana/detailwidget.cc | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/tools/cabana/detailwidget.cc b/tools/cabana/detailwidget.cc index 7c1847230b..531cd4c665 100644 --- a/tools/cabana/detailwidget.cc +++ b/tools/cabana/detailwidget.cc @@ -141,17 +141,14 @@ BinaryView::BinaryView(QWidget *parent) { table->horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); table->horizontalHeader()->hide(); table->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); - table->setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); main_layout->addWidget(table); table->setColumnCount(9); - setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Fixed); } void BinaryView::setMessage(const QString &message_id) { msg_id = message_id; const Msg *msg = dbc()->msg(msg_id); - int row_count = msg ? msg->size : can->lastMessage(msg_id).dat.size(); - + const int row_count = msg ? msg->size : can->lastMessage(msg_id).dat.size(); table->setRowCount(row_count); table->setColumnCount(9); for (int i = 0; i < table->rowCount(); ++i) { @@ -178,8 +175,7 @@ void BinaryView::setMessage(const QString &message_id) { } } } - - table->setFixedHeight(table->rowHeight(0) * table->rowCount() + table->horizontalHeader()->height() + 2); + table->setFixedHeight(table->rowHeight(0) * std::min(row_count, 8) + 2); updateState(); } From 982ea83cf9accc6aefd05169c420f457b21dcc0a Mon Sep 17 00:00:00 2001 From: Mitchell Goff Date: Thu, 13 Oct 2022 14:27:59 -0700 Subject: [PATCH 053/101] Added updateZoom function to map_renderer, plus custom style.json (#25997) * Added updateZoom function to map_renderer, plus custom style.json * Render 512x512 maps * Define STYLE_PATH in navd sconscript --- selfdrive/navd/SConscript | 2 ++ selfdrive/navd/map_renderer.cc | 27 ++++++++++++++++++++++----- selfdrive/navd/map_renderer.h | 1 + selfdrive/navd/map_renderer.py | 3 ++- selfdrive/navd/style.json | 1 + 5 files changed, 28 insertions(+), 6 deletions(-) create mode 100644 selfdrive/navd/style.json diff --git a/selfdrive/navd/SConscript b/selfdrive/navd/SConscript index 4fbe41e80b..b10684eef3 100644 --- a/selfdrive/navd/SConscript +++ b/selfdrive/navd/SConscript @@ -11,6 +11,8 @@ if arch in ['larch64', 'x86_64']: rpath = [Dir(f"#third_party/mapbox-gl-native-qt/{arch}").srcnode().abspath] qt_env["RPATH"] += rpath + style_path = File("style.json").abspath + qt_env['CXXFLAGS'].append(f'-DSTYLE_PATH=\\"{style_path}\\"') qt_libs = ["qt_widgets", "qt_util", "qmapboxgl"] + base_libs nav_src = ["main.cc", "map_renderer.cc"] diff --git a/selfdrive/navd/map_renderer.cc b/selfdrive/navd/map_renderer.cc index d0770cfb48..f85916a4ca 100644 --- a/selfdrive/navd/map_renderer.cc +++ b/selfdrive/navd/map_renderer.cc @@ -1,14 +1,16 @@ #include "selfdrive/navd/map_renderer.h" +#include #include #include #include +#include "common/util.h" #include "common/timing.h" #include "selfdrive/ui/qt/maps/map_helpers.h" -const float ZOOM = 13.5; // Don't go below 13 or features will start to disappear -const int WIDTH = 256; +const float DEFAULT_ZOOM = 13.5; // Don't go below 13 or features will start to disappear +const int WIDTH = 512; const int HEIGHT = WIDTH; const int NUM_VIPC_BUFFERS = 4; @@ -35,9 +37,10 @@ MapRenderer::MapRenderer(const QMapboxGLSettings &settings, bool online) : m_set QOpenGLFramebufferObjectFormat fbo_format; fbo.reset(new QOpenGLFramebufferObject(WIDTH, HEIGHT, fbo_format)); + std::string style = util::read_file(STYLE_PATH); m_map.reset(new QMapboxGL(nullptr, m_settings, fbo->size(), 1)); - m_map->setCoordinateZoom(QMapbox::Coordinate(0, 0), ZOOM); - m_map->setStyleUrl("mapbox://styles/commaai/ckvmksrpd4n0a14pfdo5heqzr"); + m_map->setCoordinateZoom(QMapbox::Coordinate(0, 0), DEFAULT_ZOOM); + m_map->setStyleJson(style.c_str()); m_map->createRenderer(); m_map->resize(fbo->size()); @@ -82,6 +85,15 @@ void MapRenderer::msgUpdate() { } } +void MapRenderer::updateZoom(float zoom) { + if (m_map.isNull()) { + return; + } + + m_map->setZoom(zoom); + update(); +} + void MapRenderer::updatePosition(QMapbox::Coordinate position, float bearing) { if (m_map.isNull()) { return; @@ -185,7 +197,7 @@ void MapRenderer::initLayers() { nav["source"] = "navSource"; m_map->addLayer(nav, "road-intersection"); m_map->setPaintProperty("navLayer", "line-color", QColor("grey")); - m_map->setPaintProperty("navLayer", "line-width", 3); + m_map->setPaintProperty("navLayer", "line-width", 5); m_map->setLayoutProperty("navLayer", "line-cap", "round"); } } @@ -210,6 +222,11 @@ extern "C" { return new MapRenderer(settings, false); } + void map_renderer_update_zoom(MapRenderer *inst, float zoom) { + inst->updateZoom(zoom); + QApplication::processEvents(); + } + void map_renderer_update_position(MapRenderer *inst, float lat, float lon, float bearing) { inst->updatePosition({lat, lon}, bearing); QApplication::processEvents(); diff --git a/selfdrive/navd/map_renderer.h b/selfdrive/navd/map_renderer.h index 855dc91894..921d871632 100644 --- a/selfdrive/navd/map_renderer.h +++ b/selfdrive/navd/map_renderer.h @@ -47,6 +47,7 @@ private: QTimer* timer; public slots: + void updateZoom(float zoom); void updatePosition(QMapbox::Coordinate position, float bearing); void updateRoute(QList coordinates); void msgUpdate(); diff --git a/selfdrive/navd/map_renderer.py b/selfdrive/navd/map_renderer.py index 9000622928..079bb028ce 100755 --- a/selfdrive/navd/map_renderer.py +++ b/selfdrive/navd/map_renderer.py @@ -9,7 +9,7 @@ from cffi import FFI from common.ffi_wrapper import suffix from common.basedir import BASEDIR -HEIGHT = WIDTH = 256 +HEIGHT = WIDTH = 512 def get_ffi(): @@ -18,6 +18,7 @@ def get_ffi(): ffi = FFI() ffi.cdef(""" void* map_renderer_init(char *maps_host, char *token); +void map_renderer_update_zoom(void *inst, float zoom); void map_renderer_update_position(void *inst, float lat, float lon, float bearing); void map_renderer_update_route(void *inst, char *polyline); void map_renderer_update(void *inst); diff --git a/selfdrive/navd/style.json b/selfdrive/navd/style.json new file mode 100644 index 0000000000..06bb750d1f --- /dev/null +++ b/selfdrive/navd/style.json @@ -0,0 +1 @@ +{"version": 8, "name": "Navigation Model", "metadata": {"mapbox:type": "default", "mapbox:origin": "monochrome-dark-v1", "mapbox:sdk-support": {"android": "10.0.0", "ios": "10.0.0", "js": "2.3.0"}, "mapbox:autocomposite": true, "mapbox:groups": {"Transit, transit-labels": {"name": "Transit, transit-labels", "collapsed": true}, "Administrative boundaries, admin": {"name": "Administrative boundaries, admin", "collapsed": true}, "Transit, bridges": {"name": "Transit, bridges", "collapsed": true}, "Transit, surface": {"name": "Transit, surface", "collapsed": true}, "Road network, bridges": {"name": "Road network, bridges", "collapsed": false}, "Land, water, & sky, water": {"name": "Land, water, & sky, water", "collapsed": true}, "Road network, tunnels": {"name": "Road network, tunnels", "collapsed": false}, "Road network, road-labels": {"name": "Road network, road-labels", "collapsed": true}, "Buildings, built": {"name": "Buildings, built", "collapsed": true}, "Natural features, natural-labels": {"name": "Natural features, natural-labels", "collapsed": true}, "Road network, surface": {"name": "Road network, surface", "collapsed": false}, "Land, water, & sky, built": {"name": "Land, water, & sky, built", "collapsed": true}, "Place labels, place-labels": {"name": "Place labels, place-labels", "collapsed": true}, "Point of interest labels, poi-labels": {"name": "Point of interest labels, poi-labels", "collapsed": true}, "Road network, tunnels-case": {"name": "Road network, tunnels-case", "collapsed": true}, "Transit, built": {"name": "Transit, built", "collapsed": true}, "Road network, surface-icons": {"name": "Road network, surface-icons", "collapsed": false}, "Land, water, & sky, land": {"name": "Land, water, & sky, land", "collapsed": true}}}, "center": [-117.19189443261149, 32.756553679559985], "zoom": 12.932776547838778, "bearing": 0, "pitch": 0.5017568344510897, "sources": {"composite": {"url": "mapbox://mapbox.mapbox-streets-v8", "type": "vector", "maxzoom": 13}}, "sprite": "mapbox://sprites/commaai/ckvmksrpd4n0a14pfdo5heqzr/bkx9h9tjdf3xedbnjvfo5xnbv", "glyphs": "mapbox://fonts/mapbox/{fontstack}/{range}.pbf", "layers": [{"id": "land", "type": "background", "layout": {"visibility": "none"}, "paint": {"background-color": "rgb(252, 252, 252)"}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, land"}}, {"minzoom": 5, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, land"}, "filter": ["==", ["get", "class"], "national_park"], "type": "fill", "source": "composite", "id": "national-park", "paint": {"fill-color": "rgb(240, 240, 240)", "fill-opacity": ["interpolate", ["linear"], ["zoom"], 5, 0, 6, 0.5, 10, 0.5]}, "source-layer": "landuse_overlay"}, {"minzoom": 5, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, land"}, "filter": ["match", ["get", "class"], ["park", "airport", "glacier", "pitch", "sand", "facility"], true, false], "type": "fill", "source": "composite", "id": "landuse", "paint": {"fill-color": "rgb(240, 240, 240)", "fill-opacity": ["interpolate", ["linear"], ["zoom"], 5, 0, 6, ["match", ["get", "class"], "glacier", 0.5, 1]]}, "source-layer": "landuse"}, {"id": "waterway-shadow", "type": "line", "source": "composite", "source-layer": "waterway", "minzoom": 8, "layout": {"line-cap": ["step", ["zoom"], "butt", 11, "round"], "line-join": "round", "visibility": "none"}, "paint": {"line-color": "rgb(204, 204, 204)", "line-width": ["interpolate", ["exponential", 1.3], ["zoom"], 9, ["match", ["get", "class"], ["canal", "river"], 0.1, 0], 20, ["match", ["get", "class"], ["canal", "river"], 8, 3]], "line-translate": ["interpolate", ["exponential", 1.2], ["zoom"], 7, ["literal", [0, 0]], 16, ["literal", [-1, -1]]], "line-translate-anchor": "viewport", "line-opacity": ["interpolate", ["linear"], ["zoom"], 8, 0, 8.5, 1]}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, water"}}, {"id": "water-shadow", "type": "fill", "source": "composite", "source-layer": "water", "layout": {"visibility": "none"}, "paint": {"fill-color": "rgb(204, 204, 204)", "fill-translate": ["interpolate", ["exponential", 1.2], ["zoom"], 7, ["literal", [0, 0]], 16, ["literal", [-1, -1]]], "fill-translate-anchor": "viewport"}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, water"}}, {"id": "waterway", "type": "line", "source": "composite", "source-layer": "waterway", "minzoom": 8, "layout": {"line-cap": ["step", ["zoom"], "butt", 11, "round"], "line-join": "round", "visibility": "none"}, "paint": {"line-color": "rgb(224, 224, 224)", "line-width": ["interpolate", ["exponential", 1.3], ["zoom"], 9, ["match", ["get", "class"], ["canal", "river"], 0.1, 0], 20, ["match", ["get", "class"], ["canal", "river"], 8, 3]], "line-opacity": ["interpolate", ["linear"], ["zoom"], 8, 0, 8.5, 1]}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, water"}}, {"id": "water", "type": "fill", "source": "composite", "source-layer": "water", "layout": {"visibility": "none"}, "paint": {"fill-color": "rgb(224, 224, 224)"}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, water"}}, {"minzoom": 13, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, built"}, "filter": ["all", ["==", ["geometry-type"], "Polygon"], ["==", ["get", "class"], "land"]], "type": "fill", "source": "composite", "id": "land-structure-polygon", "paint": {"fill-color": "rgb(252, 252, 252)"}, "source-layer": "structure"}, {"minzoom": 13, "layout": {"line-cap": "round", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, built"}, "filter": ["all", ["==", ["geometry-type"], "LineString"], ["==", ["get", "class"], "land"]], "type": "line", "source": "composite", "id": "land-structure-line", "paint": {"line-width": ["interpolate", ["exponential", 1.99], ["zoom"], 14, 0.75, 20, 40], "line-color": "rgb(252, 252, 252)"}, "source-layer": "structure"}, {"minzoom": 11, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "transit", "mapbox:group": "Transit, built"}, "filter": ["all", ["==", ["geometry-type"], "Polygon"], ["match", ["get", "type"], ["runway", "taxiway", "helipad"], true, false]], "type": "fill", "source": "composite", "id": "aeroway-polygon", "paint": {"fill-color": "rgb(255, 255, 255)", "fill-opacity": ["interpolate", ["linear"], ["zoom"], 11, 0, 11.5, 1]}, "source-layer": "aeroway"}, {"minzoom": 9, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "transit", "mapbox:group": "Transit, built"}, "filter": ["==", ["geometry-type"], "LineString"], "type": "line", "source": "composite", "id": "aeroway-line", "paint": {"line-color": "rgb(255, 255, 255)", "line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 9, ["match", ["get", "type"], "runway", 1, 0.5], 18, ["match", ["get", "type"], "runway", 80, 20]]}, "source-layer": "aeroway"}, {"minzoom": 13, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "buildings", "mapbox:group": "Buildings, built"}, "filter": ["all", ["!=", ["get", "type"], "building:part"], ["==", ["get", "underground"], "false"]], "type": "line", "source": "composite", "id": "building-outline", "paint": {"line-color": "rgb(227, 227, 227)", "line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 15, 0.75, 20, 3], "line-opacity": ["interpolate", ["linear"], ["zoom"], 15, 0, 16, 1]}, "source-layer": "building"}, {"minzoom": 13, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "buildings", "mapbox:group": "Buildings, built"}, "filter": ["all", ["!=", ["get", "type"], "building:part"], ["==", ["get", "underground"], "false"]], "type": "fill", "source": "composite", "id": "building", "paint": {"fill-color": ["interpolate", ["linear"], ["zoom"], 15, "rgb(242, 242, 242)", 16, "rgb(242, 242, 242)"], "fill-opacity": ["interpolate", ["linear"], ["zoom"], 15, 0, 16, 1], "fill-outline-color": "rgb(227, 227, 227)"}, "source-layer": "building"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels-case"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["step", ["zoom"], ["match", ["get", "class"], ["street", "street_limited", "primary_link", "track"], true, false], 1, ["match", ["get", "class"], ["street", "street_limited", "track", "primary_link", "secondary_link", "tertiary_link", "service"], true, false]], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-street-minor-low", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 2, "track", 1, 0.5], 18, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 18, 12]], "line-color": "rgb(235, 235, 235)", "line-opacity": ["step", ["zoom"], 1, 14, 0]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels-case"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["step", ["zoom"], ["match", ["get", "class"], ["street", "street_limited", "primary_link", "track"], true, false], 1, ["match", ["get", "class"], ["street", "street_limited", "track", "primary_link", "secondary_link", "tertiary_link", "service"], true, false]], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-street-minor-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(255, 255, 255)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 2, "track", 1, 0.5], 18, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 18, 12]], "line-opacity": ["step", ["zoom"], 0, 14, 1], "line-dasharray": [3, 3]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels-case"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["match", ["get", "class"], ["primary", "secondary", "tertiary"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-primary-secondary-tertiary-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, ["match", ["get", "class"], "primary", 1, 0.75], 18, 2], "line-color": "rgb(255, 255, 255)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, ["match", ["get", "class"], "primary", 0.75, 0.1], 18, ["match", ["get", "class"], "primary", 32, 26]], "line-dasharray": [3, 3]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels-case"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-major-link-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(255, 255, 255)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-dasharray": [3, 3]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels-case"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-motorway-trunk-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, 1, 18, 2], "line-color": "rgb(255, 255, 255)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-dasharray": [3, 3]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels-case"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["==", ["get", "class"], "construction"], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-construction", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, 2, 18, 18], "line-color": "rgb(235, 235, 235)", "line-dasharray": ["step", ["zoom"], ["literal", [0.4, 0.8]], 15, ["literal", [0.3, 0.6]], 16, ["literal", [0.2, 0.3]], 17, ["literal", [0.2, 0.25]], 18, ["literal", [0.15, 0.15]]]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-major-link", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-color": "rgb(235, 235, 235)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["step", ["zoom"], ["match", ["get", "class"], ["street", "street_limited", "primary_link", "track"], true, false], 1, ["match", ["get", "class"], ["street", "street_limited", "track", "primary_link", "secondary_link", "tertiary_link", "service"], true, false]], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-street-minor", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 2, "track", 1, 0.5], 18, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 18, 12]], "line-color": "rgb(235, 235, 235)", "line-opacity": ["step", ["zoom"], 0, 14, 1]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["match", ["get", "class"], ["primary", "secondary", "tertiary"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-primary-secondary-tertiary", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, ["match", ["get", "class"], "primary", 0.75, 0.1], 18, ["match", ["get", "class"], "primary", 32, 26]], "line-color": "rgb(235, 235, 235)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-motorway-trunk", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-color": "rgb(235, 235, 235)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"icon-image": "turning-circle-outline", "icon-size": ["interpolate", ["exponential", 1.5], ["zoom"], 14, 0.122, 18, 0.969, 20, 1], "icon-allow-overlap": true, "icon-ignore-placement": true, "icon-padding": 0, "icon-rotation-alignment": "map", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["==", ["geometry-type"], "Point"], ["match", ["get", "class"], ["turning_circle", "turning_loop"], true, false]], "type": "symbol", "source": "composite", "id": "turning-feature-outline", "paint": {}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["step", ["zoom"], ["==", ["get", "class"], "track"], 1, ["match", ["get", "class"], ["track", "secondary_link", "tertiary_link", "service"], true, false]], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-minor-low", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, ["match", ["get", "class"], "track", 1, 0.5], 18, 12], "line-color": "rgb(255, 255, 255)", "line-opacity": ["step", ["zoom"], 1, 14, 0]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["step", ["zoom"], ["==", ["get", "class"], "track"], 1, ["match", ["get", "class"], ["track", "secondary_link", "tertiary_link", "service"], true, false]], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-minor-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, ["match", ["get", "class"], "track", 1, 0.5], 18, 12], "line-opacity": ["step", ["zoom"], 0, 14, 1]}, "source-layer": "road"}, {"minzoom": 11, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["street", "street_limited", "primary_link"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-street-low", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-color": "rgb(255, 255, 255)", "line-opacity": ["step", ["zoom"], 1, 14, 0]}, "source-layer": "road"}, {"minzoom": 11, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["street", "street_limited", "primary_link"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-street-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-opacity": ["step", ["zoom"], 0, 14, 1]}, "source-layer": "road"}, {"minzoom": 8, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["secondary", "tertiary"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-secondary-tertiary-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, 0.75, 18, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.1, 18, 26], "line-opacity": ["step", ["zoom"], 0, 10, 1]}, "source-layer": "road"}, {"minzoom": 7, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["==", ["get", "class"], "primary"], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-primary-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, 1, 18, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-opacity": ["step", ["zoom"], 0, 10, 1]}, "source-layer": "road"}, {"minzoom": 10, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-major-link-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-opacity": ["step", ["zoom"], 0, 11, 1]}, "source-layer": "road"}, {"minzoom": 5, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-motorway-trunk-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, 1, 18, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-opacity": ["step", ["zoom"], ["match", ["get", "class"], "motorway", 1, 0], 6, 1]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["==", ["get", "class"], "construction"], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-construction", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, 2, 18, 18], "line-color": "rgb(255, 255, 255)", "line-dasharray": ["step", ["zoom"], ["literal", [0.4, 0.8]], 15, ["literal", [0.3, 0.6]], 16, ["literal", [0.2, 0.3]], 17, ["literal", [0.2, 0.25]], 18, ["literal", [0.15, 0.15]]]}, "source-layer": "road"}, {"minzoom": 10, "layout": {"line-cap": ["step", ["zoom"], "butt", 13, "round"], "line-join": ["step", ["zoom"], "miter", 13, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-major-link", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["step", ["zoom"], ["==", ["get", "class"], "track"], 1, ["match", ["get", "class"], ["track", "secondary_link", "tertiary_link", "service"], true, false]], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-minor", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, ["match", ["get", "class"], "track", 1, 0.5], 18, 12], "line-color": "rgb(255, 255, 255)", "line-opacity": ["step", ["zoom"], 0, 14, 1]}, "source-layer": "road"}, {"minzoom": 11, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["street", "street_limited", "primary_link"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-street", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-color": "rgb(255, 255, 255)", "line-opacity": ["step", ["zoom"], 0, 14, 1]}, "source-layer": "road"}, {"minzoom": 8, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["secondary", "tertiary"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-secondary-tertiary", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.1, 18, 26], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"minzoom": 6, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["==", ["get", "class"], "primary"], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-primary", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"id": "road-motorway-trunk", "type": "line", "source": "composite", "source-layer": "road", "filter": ["all", ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "layout": {"line-cap": ["step", ["zoom"], "butt", 13, "round"], "line-join": ["step", ["zoom"], "miter", 13, "round"]}, "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-color": "rgb(255, 255, 255)"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}}, {"minzoom": 13, "layout": {"line-join": "round", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "transit", "mapbox:group": "Transit, surface"}, "filter": ["all", ["match", ["get", "class"], ["major_rail", "minor_rail"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false]], "type": "line", "source": "composite", "id": "road-rail", "paint": {"line-color": ["interpolate", ["linear"], ["zoom"], 13, "rgb(242, 242, 242)", 17, "rgb(227, 227, 227)"], "line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, 0.5, 20, 1]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"icon-image": "turning-circle", "icon-size": ["interpolate", ["exponential", 1.5], ["zoom"], 14, 0.095, 18, 1], "icon-allow-overlap": true, "icon-ignore-placement": true, "icon-padding": 0, "icon-rotation-alignment": "map", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface-icons"}, "filter": ["all", ["==", ["geometry-type"], "Point"], ["match", ["get", "class"], ["turning_circle", "turning_loop"], true, false]], "type": "symbol", "source": "composite", "id": "turning-feature", "paint": {}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["step", ["zoom"], ["match", ["get", "class"], ["street", "street_limited", "primary_link", "track"], true, false], 1, ["match", ["get", "class"], ["street", "street_limited", "track", "primary_link", "secondary_link", "tertiary_link", "service"], true, false]], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-street-minor-low", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 2, "track", 1, 0.5], 18, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 18, 12]], "line-color": "rgb(255, 255, 255)", "line-opacity": ["step", ["zoom"], 1, 14, 0]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["step", ["zoom"], ["match", ["get", "class"], ["street", "street_limited", "primary_link", "track"], true, false], 1, ["match", ["get", "class"], ["street", "street_limited", "track", "primary_link", "secondary_link", "tertiary_link", "service"], true, false]], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-street-minor-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 2, "track", 1, 0.5], 18, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 18, 12]], "line-opacity": ["step", ["zoom"], 0, 14, 1]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["match", ["get", "class"], ["primary", "secondary", "tertiary"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-primary-secondary-tertiary-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, ["match", ["get", "class"], "primary", 1, 0.75], 18, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, ["match", ["get", "class"], "primary", 0.75, 0.1], 18, ["match", ["get", "class"], "primary", 32, 26]], "line-opacity": ["step", ["zoom"], 0, 10, 1]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["<=", ["get", "layer"], 1], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-major-link-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["<=", ["get", "layer"], 1], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-motorway-trunk-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, 1, 18, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["==", ["get", "class"], "construction"], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-construction", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, 2, 18, 18], "line-color": "rgb(255, 255, 255)", "line-dasharray": ["step", ["zoom"], ["literal", [0.4, 0.8]], 15, ["literal", [0.3, 0.6]], 16, ["literal", [0.2, 0.3]], 17, ["literal", [0.2, 0.25]], 18, ["literal", [0.15, 0.15]]]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": "round", "line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["<=", ["get", "layer"], 1], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-major-link", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["step", ["zoom"], ["match", ["get", "class"], ["street", "street_limited", "primary_link", "track"], true, false], 1, ["match", ["get", "class"], ["street", "street_limited", "track", "primary_link", "secondary_link", "tertiary_link", "service"], true, false]], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-street-minor", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 2, "track", 1, 0.5], 18, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 18, 12]], "line-color": "rgb(255, 255, 255)", "line-opacity": ["step", ["zoom"], 0, 14, 1]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["match", ["get", "class"], ["primary", "secondary", "tertiary"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-primary-secondary-tertiary", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, ["match", ["get", "class"], "primary", 0.75, 0.1], 18, ["match", ["get", "class"], "primary", 32, 26]], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": "round", "line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["<=", ["get", "layer"], 1], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-motorway-trunk", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], [">=", ["get", "layer"], 2], ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-major-link-2-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], [">=", ["get", "layer"], 2], ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-motorway-trunk-2-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, 1, 18, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": "round", "line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], [">=", ["get", "layer"], 2], ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-major-link-2", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], [">=", ["get", "layer"], 2], ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-motorway-trunk-2", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-join": "round", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "transit", "mapbox:group": "Transit, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["match", ["get", "class"], ["major_rail", "minor_rail"], true, false]], "type": "line", "source": "composite", "id": "bridge-rail", "paint": {"line-color": "rgb(227, 227, 227)", "line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, 0.5, 20, 1]}, "source-layer": "road"}, {"minzoom": 7, "layout": {"line-join": "bevel", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "admin-boundaries", "mapbox:group": "Administrative boundaries, admin"}, "filter": ["all", ["==", ["get", "admin_level"], 1], ["==", ["get", "maritime"], "false"], ["match", ["get", "worldview"], ["all", "US"], true, false]], "type": "line", "source": "composite", "id": "admin-1-boundary-bg", "paint": {"line-color": ["interpolate", ["linear"], ["zoom"], 8, "rgb(227, 227, 227)", 16, "rgb(227, 227, 227)"], "line-width": ["interpolate", ["linear"], ["zoom"], 7, 3.75, 12, 5.5], "line-opacity": ["interpolate", ["linear"], ["zoom"], 7, 0, 8, 0.75], "line-dasharray": [1, 0], "line-blur": ["interpolate", ["linear"], ["zoom"], 3, 0, 8, 3]}, "source-layer": "admin"}, {"minzoom": 1, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "admin-boundaries", "mapbox:group": "Administrative boundaries, admin"}, "filter": ["all", ["==", ["get", "admin_level"], 0], ["==", ["get", "maritime"], "false"], ["match", ["get", "worldview"], ["all", "US"], true, false]], "type": "line", "source": "composite", "id": "admin-0-boundary-bg", "paint": {"line-width": ["interpolate", ["linear"], ["zoom"], 3, 3.5, 10, 8], "line-color": "rgb(227, 227, 227)", "line-opacity": ["interpolate", ["linear"], ["zoom"], 3, 0, 4, 0.5], "line-blur": ["interpolate", ["linear"], ["zoom"], 3, 0, 10, 2]}, "source-layer": "admin"}, {"minzoom": 2, "layout": {"line-join": "round", "line-cap": "round", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "admin-boundaries", "mapbox:group": "Administrative boundaries, admin"}, "filter": ["all", ["==", ["get", "admin_level"], 1], ["==", ["get", "maritime"], "false"], ["match", ["get", "worldview"], ["all", "US"], true, false]], "type": "line", "source": "composite", "id": "admin-1-boundary", "paint": {"line-dasharray": ["step", ["zoom"], ["literal", [2, 0]], 7, ["literal", [2, 2, 6, 2]]], "line-width": ["interpolate", ["linear"], ["zoom"], 7, 0.75, 12, 1.5], "line-opacity": ["interpolate", ["linear"], ["zoom"], 2, 0, 3, 1], "line-color": ["interpolate", ["linear"], ["zoom"], 3, "rgb(224, 224, 224)", 7, "rgb(184, 184, 184)"]}, "source-layer": "admin"}, {"minzoom": 1, "layout": {"line-join": "round", "line-cap": "round", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "admin-boundaries", "mapbox:group": "Administrative boundaries, admin"}, "filter": ["all", ["==", ["get", "admin_level"], 0], ["==", ["get", "disputed"], "false"], ["==", ["get", "maritime"], "false"], ["match", ["get", "worldview"], ["all", "US"], true, false]], "type": "line", "source": "composite", "id": "admin-0-boundary", "paint": {"line-color": "rgb(184, 184, 184)", "line-width": ["interpolate", ["linear"], ["zoom"], 3, 0.5, 10, 2], "line-dasharray": [10, 0]}, "source-layer": "admin"}, {"minzoom": 1, "layout": {"line-join": "round", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "admin-boundaries", "mapbox:group": "Administrative boundaries, admin"}, "filter": ["all", ["==", ["get", "disputed"], "true"], ["==", ["get", "admin_level"], 0], ["==", ["get", "maritime"], "false"], ["match", ["get", "worldview"], ["all", "US"], true, false]], "type": "line", "source": "composite", "id": "admin-0-boundary-disputed", "paint": {"line-color": "rgb(184, 184, 184)", "line-width": ["interpolate", ["linear"], ["zoom"], 3, 0.5, 10, 2], "line-dasharray": ["step", ["zoom"], ["literal", [3.25, 3.25]], 6, ["literal", [2.5, 2.5]], 7, ["literal", [2, 2.25]], 8, ["literal", [1.75, 2]]]}, "source-layer": "admin"}, {"minzoom": 10, "layout": {"text-size": ["interpolate", ["linear"], ["zoom"], 10, ["match", ["get", "class"], ["motorway", "trunk", "primary", "secondary", "tertiary"], 10, ["motorway_link", "trunk_link", "primary_link", "secondary_link", "tertiary_link", "street", "street_limited"], 9, 6.5], 18, ["match", ["get", "class"], ["motorway", "trunk", "primary", "secondary", "tertiary"], 16, ["motorway_link", "trunk_link", "primary_link", "secondary_link", "tertiary_link", "street", "street_limited"], 14, 13]], "text-max-angle": 30, "text-font": ["DIN Pro Regular", "Arial Unicode MS Regular"], "symbol-placement": "line", "text-padding": 1, "visibility": "none", "text-rotation-alignment": "map", "text-pitch-alignment": "viewport", "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "text-letter-spacing": 0.01}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, road-labels"}, "filter": ["step", ["zoom"], ["match", ["get", "class"], ["motorway", "trunk", "primary", "secondary", "tertiary"], true, false], 1, ["match", ["get", "class"], ["motorway", "trunk", "primary", "secondary", "tertiary", "street", "street_limited"], true, false], 2, ["match", ["get", "class"], ["path", "pedestrian", "golf", "ferry", "aerialway"], false, true]], "type": "symbol", "source": "composite", "id": "road-label", "paint": {"text-color": "rgb(128, 128, 128)", "text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 1, "text-halo-blur": 1}, "source-layer": "road"}, {"minzoom": 13, "layout": {"text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "icon-image": "intersection", "icon-text-fit": "both", "icon-text-fit-padding": [1, 2, 1, 2], "text-size": ["interpolate", ["exponential", 1.2], ["zoom"], 15, 9, 18, 12], "text-font": ["DIN Pro Bold", "Arial Unicode MS Bold"], "visibility": "none"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, road-labels"}, "filter": ["all", ["==", ["get", "class"], "intersection"], ["has", "name"]], "type": "symbol", "source": "composite", "id": "road-intersection", "paint": {"text-color": "rgb(153, 153, 153)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"text-font": ["DIN Pro Italic", "Arial Unicode MS Regular"], "text-max-angle": 30, "symbol-spacing": ["interpolate", ["linear", 1], ["zoom"], 15, 250, 17, 400], "text-size": ["interpolate", ["linear"], ["zoom"], 13, 12, 18, 16], "symbol-placement": "line", "text-pitch-alignment": "viewport", "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "visibility": "none"}, "metadata": {"mapbox:featureComponent": "natural-features", "mapbox:group": "Natural features, natural-labels"}, "filter": ["all", ["match", ["get", "class"], ["canal", "river", "stream"], ["match", ["get", "worldview"], ["all", "US"], true, false], ["disputed_canal", "disputed_river", "disputed_stream"], ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["==", ["geometry-type"], "LineString"]], "type": "symbol", "source": "composite", "id": "waterway-label", "paint": {"text-color": "rgb(150, 150, 150)"}, "source-layer": "natural_label"}, {"minzoom": 4, "layout": {"text-size": ["step", ["zoom"], ["step", ["get", "sizerank"], 18, 5, 12], 17, ["step", ["get", "sizerank"], 18, 13, 12]], "text-max-angle": 30, "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "text-font": ["DIN Pro Medium", "Arial Unicode MS Regular"], "symbol-placement": "line-center", "text-pitch-alignment": "viewport", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "natural-features", "mapbox:group": "Natural features, natural-labels"}, "filter": ["all", ["match", ["get", "class"], ["glacier", "landform"], ["match", ["get", "worldview"], ["all", "US"], true, false], ["disputed_glacier", "disputed_landform"], ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["==", ["geometry-type"], "LineString"], ["<=", ["get", "filterrank"], 1]], "type": "symbol", "source": "composite", "id": "natural-line-label", "paint": {"text-halo-width": 0.5, "text-halo-color": "rgb(255, 255, 255)", "text-halo-blur": 0.5, "text-color": "rgb(128, 128, 128)"}, "source-layer": "natural_label"}, {"minzoom": 4, "layout": {"text-size": ["step", ["zoom"], ["step", ["get", "sizerank"], 18, 5, 12], 17, ["step", ["get", "sizerank"], 18, 13, 12]], "icon-image": "", "text-font": ["DIN Pro Medium", "Arial Unicode MS Regular"], "text-offset": ["literal", [0, 0]], "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "visibility": "none"}, "metadata": {"mapbox:featureComponent": "natural-features", "mapbox:group": "Natural features, natural-labels"}, "filter": ["all", ["match", ["get", "class"], ["dock", "glacier", "landform", "water_feature", "wetland"], ["match", ["get", "worldview"], ["all", "US"], true, false], ["disputed_dock", "disputed_glacier", "disputed_landform", "disputed_water_feature", "disputed_wetland"], ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["==", ["geometry-type"], "Point"], ["<=", ["get", "filterrank"], 1]], "type": "symbol", "source": "composite", "id": "natural-point-label", "paint": {"icon-opacity": ["step", ["zoom"], ["step", ["get", "sizerank"], 0, 5, 1], 17, ["step", ["get", "sizerank"], 0, 13, 1]], "text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 0.5, "text-halo-blur": 0.5, "text-color": "rgb(128, 128, 128)"}, "source-layer": "natural_label"}, {"id": "water-line-label", "type": "symbol", "metadata": {"mapbox:featureComponent": "natural-features", "mapbox:group": "Natural features, natural-labels"}, "source": "composite", "source-layer": "natural_label", "filter": ["all", ["match", ["get", "class"], ["bay", "ocean", "reservoir", "sea", "water"], ["match", ["get", "worldview"], ["all", "US"], true, false], ["disputed_bay", "disputed_ocean", "disputed_reservoir", "disputed_sea", "disputed_water"], ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["==", ["geometry-type"], "LineString"]], "layout": {"text-size": ["interpolate", ["linear"], ["zoom"], 7, ["step", ["get", "sizerank"], 20, 6, 18, 12, 12], 10, ["step", ["get", "sizerank"], 15, 9, 12], 18, ["step", ["get", "sizerank"], 15, 9, 14]], "text-max-angle": 30, "text-letter-spacing": ["match", ["get", "class"], "ocean", 0.25, ["sea", "bay"], 0.15, 0], "text-font": ["DIN Pro Italic", "Arial Unicode MS Regular"], "symbol-placement": "line-center", "text-pitch-alignment": "viewport", "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "visibility": "none"}, "paint": {"text-color": "rgb(150, 150, 150)"}}, {"id": "water-point-label", "type": "symbol", "source": "composite", "source-layer": "natural_label", "filter": ["all", ["match", ["get", "class"], ["bay", "ocean", "reservoir", "sea", "water"], ["match", ["get", "worldview"], ["all", "US"], true, false], ["disputed_bay", "disputed_ocean", "disputed_reservoir", "disputed_sea", "disputed_water"], ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["==", ["geometry-type"], "Point"]], "layout": {"text-line-height": 1.3, "text-size": ["interpolate", ["linear"], ["zoom"], 7, ["step", ["get", "sizerank"], 20, 6, 15, 12, 12], 10, ["step", ["get", "sizerank"], 15, 9, 12]], "text-font": ["DIN Pro Italic", "Arial Unicode MS Regular"], "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "text-letter-spacing": ["match", ["get", "class"], "ocean", 0.25, ["bay", "sea"], 0.15, 0.01], "text-max-width": ["match", ["get", "class"], "ocean", 4, "sea", 5, ["bay", "water"], 7, 10], "visibility": "none"}, "paint": {"text-color": "rgb(150, 150, 150)"}, "metadata": {"mapbox:featureComponent": "natural-features", "mapbox:group": "Natural features, natural-labels"}}, {"minzoom": 6, "layout": {"text-size": ["step", ["zoom"], ["step", ["get", "sizerank"], 18, 5, 12], 17, ["step", ["get", "sizerank"], 18, 13, 12]], "icon-image": "", "text-font": ["DIN Pro Medium", "Arial Unicode MS Regular"], "text-offset": [0, 0], "text-anchor": ["step", ["zoom"], ["step", ["get", "sizerank"], "center", 5, "top"], 17, ["step", ["get", "sizerank"], "center", 13, "top"]], "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "visibility": "none"}, "metadata": {"mapbox:featureComponent": "point-of-interest-labels", "mapbox:group": "Point of interest labels, poi-labels"}, "filter": ["<=", ["get", "filterrank"], ["+", ["step", ["zoom"], 1, 2, 3, 4, 5], 1]], "type": "symbol", "source": "composite", "id": "poi-label", "paint": {"text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 0.5, "text-halo-blur": 0.5, "text-color": ["step", ["zoom"], ["step", ["get", "sizerank"], "rgb(184, 184, 184)", 5, "rgb(161, 161, 161)"], 17, ["step", ["get", "sizerank"], "rgb(184, 184, 184)", 13, "rgb(161, 161, 161)"]]}, "source-layer": "poi_label"}, {"minzoom": 8, "layout": {"text-line-height": 1.1, "text-size": ["step", ["get", "sizerank"], 18, 9, 12], "icon-image": ["get", "maki"], "text-font": ["DIN Pro Medium", "Arial Unicode MS Regular"], "visibility": "none", "text-offset": [0, 0.75], "text-rotation-alignment": "viewport", "text-anchor": "top", "text-field": ["step", ["get", "sizerank"], ["coalesce", ["get", "name_en"], ["get", "name"]], 15, ["get", "ref"]], "text-letter-spacing": 0.01, "text-max-width": 9}, "metadata": {"mapbox:featureComponent": "transit", "mapbox:group": "Transit, transit-labels"}, "filter": ["match", ["get", "class"], ["military", "civil"], ["match", ["get", "worldview"], ["all", "US"], true, false], ["disputed_military", "disputed_civil"], ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], "type": "symbol", "source": "composite", "id": "airport-label", "paint": {"text-color": "rgb(128, 128, 128)", "text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 1}, "source-layer": "airport_label"}, {"minzoom": 10, "layout": {"text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "text-transform": "uppercase", "text-font": ["DIN Pro Regular", "Arial Unicode MS Regular"], "text-letter-spacing": ["match", ["get", "type"], "suburb", 0.15, 0.1], "text-max-width": 7, "text-padding": 3, "text-size": ["interpolate", ["cubic-bezier", 0.5, 0, 1, 1], ["zoom"], 11, ["match", ["get", "type"], "suburb", 11, 10.5], 15, ["match", ["get", "type"], "suburb", 15, 14]], "visibility": "none"}, "metadata": {"mapbox:featureComponent": "place-labels", "mapbox:group": "Place labels, place-labels"}, "maxzoom": 15, "filter": ["all", ["match", ["get", "class"], "settlement_subdivision", ["match", ["get", "worldview"], ["all", "US"], true, false], "disputed_settlement_subdivision", ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["<=", ["get", "filterrank"], 4]], "type": "symbol", "source": "composite", "id": "settlement-subdivision-label", "paint": {"text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 1, "text-color": "rgb(179, 179, 179)", "text-halo-blur": 0.5}, "source-layer": "place_label"}, {"minzoom": 3, "layout": {"text-line-height": 1.1, "text-size": ["interpolate", ["cubic-bezier", 0.2, 0, 0.9, 1], ["zoom"], 3, ["step", ["get", "symbolrank"], 12, 9, 11, 10, 10.5, 12, 9.5, 14, 8.5, 16, 6.5, 17, 4], 13, ["step", ["get", "symbolrank"], 23, 9, 21, 10, 19, 11, 17, 12, 16, 13, 15, 15, 13]], "text-radial-offset": ["step", ["zoom"], ["match", ["get", "capital"], 2, 0.6, 0.55], 8, 0], "icon-image": ["step", ["zoom"], ["case", ["==", ["get", "capital"], 2], "border-dot-13", ["step", ["get", "symbolrank"], "dot-11", 9, "dot-10", 11, "dot-9"]], 8, ""], "text-font": ["DIN Pro Regular", "Arial Unicode MS Regular"], "text-justify": "auto", "visibility": "none", "text-anchor": ["step", ["zoom"], ["get", "text_anchor"], 8, "center"], "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "text-max-width": 7}, "metadata": {"mapbox:featureComponent": "place-labels", "mapbox:group": "Place labels, place-labels"}, "maxzoom": 13, "filter": ["all", ["<=", ["get", "filterrank"], 3], ["match", ["get", "class"], "settlement", ["match", ["get", "worldview"], ["all", "US"], true, false], "disputed_settlement", ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["step", ["zoom"], [">", ["get", "symbolrank"], 6], 1, [">=", ["get", "symbolrank"], 7], 2, [">=", ["get", "symbolrank"], 8], 3, [">=", ["get", "symbolrank"], 10], 4, [">=", ["get", "symbolrank"], 11], 5, [">=", ["get", "symbolrank"], 13], 6, [">=", ["get", "symbolrank"], 15]]], "type": "symbol", "source": "composite", "id": "settlement-minor-label", "paint": {"text-color": ["step", ["get", "symbolrank"], "rgb(128, 128, 128)", 11, "rgb(161, 161, 161)", 16, "rgb(184, 184, 184)"], "text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 1, "text-halo-blur": 1}, "source-layer": "place_label"}, {"minzoom": 3, "layout": {"text-line-height": 1.1, "text-size": ["interpolate", ["cubic-bezier", 0.2, 0, 0.9, 1], ["zoom"], 3, ["step", ["get", "symbolrank"], 13, 6, 12], 6, ["step", ["get", "symbolrank"], 16, 6, 15, 7, 14], 8, ["step", ["get", "symbolrank"], 18, 9, 17, 10, 15], 15, ["step", ["get", "symbolrank"], 23, 9, 22, 10, 20, 11, 18, 12, 16, 13, 15, 15, 13]], "text-radial-offset": ["step", ["zoom"], ["match", ["get", "capital"], 2, 0.6, 0.55], 8, 0], "icon-image": ["step", ["zoom"], ["case", ["==", ["get", "capital"], 2], "border-dot-13", ["step", ["get", "symbolrank"], "dot-11", 9, "dot-10", 11, "dot-9"]], 8, ""], "text-font": ["DIN Pro Medium", "Arial Unicode MS Regular"], "text-justify": ["step", ["zoom"], ["match", ["get", "text_anchor"], ["left", "bottom-left", "top-left"], "left", ["right", "bottom-right", "top-right"], "right", "center"], 8, "center"], "visibility": "none", "text-anchor": ["step", ["zoom"], ["get", "text_anchor"], 8, "center"], "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "text-max-width": 7}, "metadata": {"mapbox:featureComponent": "place-labels", "mapbox:group": "Place labels, place-labels"}, "maxzoom": 15, "filter": ["all", ["<=", ["get", "filterrank"], 3], ["match", ["get", "class"], "settlement", ["match", ["get", "worldview"], ["all", "US"], true, false], "disputed_settlement", ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["step", ["zoom"], false, 1, ["<=", ["get", "symbolrank"], 6], 2, ["<", ["get", "symbolrank"], 7], 3, ["<", ["get", "symbolrank"], 8], 4, ["<", ["get", "symbolrank"], 10], 5, ["<", ["get", "symbolrank"], 11], 6, ["<", ["get", "symbolrank"], 13], 7, ["<", ["get", "symbolrank"], 15], 8, [">=", ["get", "symbolrank"], 11], 9, [">=", ["get", "symbolrank"], 15]]], "type": "symbol", "source": "composite", "id": "settlement-major-label", "paint": {"text-color": ["step", ["get", "symbolrank"], "rgb(128, 128, 128)", 11, "rgb(161, 161, 161)", 16, "rgb(184, 184, 184)"], "text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 1, "text-halo-blur": 1}, "source-layer": "place_label"}, {"minzoom": 3, "layout": {"text-size": ["interpolate", ["cubic-bezier", 0.85, 0.7, 0.65, 1], ["zoom"], 4, ["step", ["get", "symbolrank"], 10, 6, 9.5, 7, 9], 9, ["step", ["get", "symbolrank"], 21, 6, 16, 7, 13]], "text-transform": "uppercase", "text-font": ["DIN Pro Bold", "Arial Unicode MS Bold"], "text-field": ["step", ["zoom"], ["step", ["get", "symbolrank"], ["coalesce", ["get", "name_en"], ["get", "name"]], 5, ["coalesce", ["get", "abbr"], ["get", "name_en"], ["get", "name"]]], 5, ["coalesce", ["get", "name_en"], ["get", "name"]]], "text-letter-spacing": 0.15, "text-max-width": 6, "visibility": "none"}, "metadata": {"mapbox:featureComponent": "place-labels", "mapbox:group": "Place labels, place-labels"}, "maxzoom": 9, "filter": ["match", ["get", "class"], "state", ["match", ["get", "worldview"], ["all", "US"], true, false], "disputed_state", ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], "type": "symbol", "source": "composite", "id": "state-label", "paint": {"text-color": "rgb(184, 184, 184)", "text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 1}, "source-layer": "place_label"}, {"minzoom": 1, "layout": {"text-line-height": 1.1, "text-size": ["interpolate", ["cubic-bezier", 0.2, 0, 0.7, 1], ["zoom"], 1, ["step", ["get", "symbolrank"], 11, 4, 9, 5, 8], 9, ["step", ["get", "symbolrank"], 22, 4, 19, 5, 17]], "text-radial-offset": ["step", ["zoom"], 0.6, 8, 0], "icon-image": "", "text-font": ["DIN Pro Medium", "Arial Unicode MS Regular"], "text-justify": ["step", ["zoom"], ["match", ["get", "text_anchor"], ["left", "bottom-left", "top-left"], "left", ["right", "bottom-right", "top-right"], "right", "center"], 7, "auto"], "visibility": "none", "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "text-max-width": 6}, "metadata": {"mapbox:featureComponent": "place-labels", "mapbox:group": "Place labels, place-labels"}, "maxzoom": 10, "filter": ["match", ["get", "class"], "country", ["match", ["get", "worldview"], ["all", "US"], true, false], "disputed_country", ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], "type": "symbol", "source": "composite", "id": "country-label", "paint": {"icon-opacity": ["step", ["zoom"], ["case", ["has", "text_anchor"], 1, 0], 7, 0], "text-color": "rgb(128, 128, 128)", "text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 1.25}, "source-layer": "place_label"}], "created": "2021-11-05T16:12:04.822Z", "modified": "2021-11-25T13:58:04.167Z", "id": "ckvmksrpd4n0a14pfdo5heqzr", "owner": "commaai", "visibility": "private", "protected": false, "draft": false} \ No newline at end of file From 7e9961b9ac8c8e22197148d3741164c072200d3c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 13 Oct 2022 17:40:07 -0700 Subject: [PATCH 054/101] FPv2: support collecting versions for specific ecus (#25699) * Add VMCU address for EV6 * Rename vmcu * add to tests add to tests * rename to more generic name * more explicit * remove print * Like this much better, removes subtle fingerprinting problems * clean up * add test and clean up * remove hyundai stuffs * global * Fpv2Config class * fix missing fw versions from import order * unused * revert for now * test for fpv2 configs with subtests * subtests don't work that way * remove this * . * intersection * print ecus * shorter * fix typing * use config --- selfdrive/car/chrysler/values.py | 9 ++++----- selfdrive/car/fw_query_definitions.py | 4 +++- selfdrive/car/fw_versions.py | 5 +++++ selfdrive/car/tests/test_fw_fingerprint.py | 7 +++++++ 4 files changed, 19 insertions(+), 6 deletions(-) diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 7180ace524..c703ef6cb8 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -166,14 +166,13 @@ FW_QUERY_CONFIG = FwQueryConfig( bus=0, ), ], + extra_ecus=[ + (Ecu.hcp, 0x7e2, None), # manages transmission on hybrids + (Ecu.abs, 0x7e4, None), # alt address for abs on hybrids + ], ) FW_VERSIONS = { - CAR.PACIFICA_2019_HYBRID: { - (Ecu.hcp, 0x7e2, None): [], - (Ecu.abs, 0x7e4, None): [], - }, - CAR.RAM_1500: { (Ecu.combinationMeter, 0x742, None): [ b'68294063AH', diff --git a/selfdrive/car/fw_query_definitions.py b/selfdrive/car/fw_query_definitions.py index c3b74da920..c7e4d4eb30 100755 --- a/selfdrive/car/fw_query_definitions.py +++ b/selfdrive/car/fw_query_definitions.py @@ -2,7 +2,7 @@ import capnp from dataclasses import dataclass, field import struct -from typing import Dict, List +from typing import Dict, List, Optional, Tuple import panda.python.uds as uds @@ -64,3 +64,5 @@ class FwQueryConfig: requests: List[Request] # Overrides and removes from essential ecus for specific models and ecus (exact matching) non_essential_ecus: Dict[capnp.lib.capnp._EnumModule, List[str]] = field(default_factory=dict) + # Ecus added for data collection, not to be fingerprinted on + extra_ecus: List[Tuple[capnp.lib.capnp._EnumModule, int, Optional[int]]] = field(default_factory=list) diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 7e03f4b020..d3e8eae0de 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -213,6 +213,11 @@ def get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs, timeout=0.1, debug=Fa def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1, debug=False, progress=False): versions = VERSIONS.copy() + + # Each brand can define extra ECUs to query for data collection + for brand, config in FW_QUERY_CONFIGS.items(): + versions[brand]["debug"] = {ecu: [] for ecu in config.extra_ecus} + if query_brand is not None: versions = {query_brand: versions[query_brand]} diff --git a/selfdrive/car/tests/test_fw_fingerprint.py b/selfdrive/car/tests/test_fw_fingerprint.py index f0d2744a98..ed323b0563 100755 --- a/selfdrive/car/tests/test_fw_fingerprint.py +++ b/selfdrive/car/tests/test_fw_fingerprint.py @@ -44,6 +44,13 @@ class TestFwFingerprint(unittest.TestCase): duplicates = {fw for fw in ecu_fw if ecu_fw.count(fw) > 1} self.assertFalse(len(duplicates), f"{car_model}: Duplicate FW versions: Ecu.{ECU_NAME[ecu[0]]}, {duplicates}") + def test_data_collection_ecus(self): + for brand, config in FW_QUERY_CONFIGS.items(): + for car_model, ecus in VERSIONS[brand].items(): + bad_ecus = set(ecus).intersection(config.extra_ecus) + with self.subTest(car_model=car_model): + self.assertFalse(len(bad_ecus), f'{car_model}: Fingerprints contain ECUs added for data collection: {bad_ecus}') + def test_blacklisted_ecus(self): blacklisted_addrs = (0x7c4, 0x7d0) # includes A/C ecu and an unknown ecu for car_model, ecus in FW_VERSIONS.items(): From a02f42959c330d7df45c623b08c285e43c19726d Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Thu, 13 Oct 2022 19:45:42 -0700 Subject: [PATCH 055/101] Hyundai docs: fix model name/year formatting (#26074) * fix formatting so that model years can be parsed * generate car docs --- docs/CARS.md | 8 ++++---- selfdrive/car/hyundai/values.py | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 77d6b890db..40eef06102 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -57,8 +57,8 @@ A supported vehicle is one that just works when you install a comma three. All s |Hyundai|Elantra 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| |Hyundai|Elantra Hybrid 2021-23|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| |Hyundai|Genesis 2015-16|Smart Cruise Control (SCC)|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai J| -|Hyundai|Ioniq 5 2022 (with HDA II)|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai Q| -|Hyundai|Ioniq 5 2022 (without HDA II)|Highway Driving Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| +|Hyundai|Ioniq 5 (with HDA II) 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai Q| +|Hyundai|Ioniq 5 (without HDA II) 2022|Highway Driving Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| |Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |Hyundai|Ioniq Electric 2020|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| @@ -84,8 +84,8 @@ A supported vehicle is one that just works when you install a comma three. All s |Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Kia|Ceed 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| -|Kia|EV6 2022 (with HDA II)|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P| -|Kia|EV6 2022 (without HDA II)|Highway Driving Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Kia|EV6 (with HDA II) 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P| +|Kia|EV6 (without HDA II) 2022|Highway Driving Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| |Kia|Forte 2019-21|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| |Kia|K5 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| |Kia|Niro EV 2019|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 2d5e6792ee..a24992f90f 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -142,8 +142,8 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { CAR.VELOSTER: HyundaiCarInfo("Hyundai Veloster 2019-20", min_enable_speed=5. * CV.MPH_TO_MS, harness=Harness.hyundai_e), CAR.SONATA_HYBRID: HyundaiCarInfo("Hyundai Sonata Hybrid 2020-22", "All", harness=Harness.hyundai_a), CAR.IONIQ_5: [ - HyundaiCarInfo("Hyundai Ioniq 5 2022 (without HDA II)" , "Highway Driving Assist", harness=Harness.hyundai_k), - HyundaiCarInfo("Hyundai Ioniq 5 2022 (with HDA II)", "Highway Driving Assist II", harness=Harness.hyundai_q), + HyundaiCarInfo("Hyundai Ioniq 5 (without HDA II) 2022" , "Highway Driving Assist", harness=Harness.hyundai_k), + HyundaiCarInfo("Hyundai Ioniq 5 (with HDA II) 2022", "Highway Driving Assist II", harness=Harness.hyundai_q), ], CAR.TUCSON_HYBRID_4TH_GEN: HyundaiCarInfo("Hyundai Tucson Hybrid 2022", "All", harness=Harness.hyundai_n), @@ -175,8 +175,8 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { 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 (without HDA II)", "Highway Driving Assist", harness=Harness.hyundai_l), - HyundaiCarInfo("Kia EV6 2022 (with HDA II)", "Highway Driving Assist II", harness=Harness.hyundai_p) + HyundaiCarInfo("Kia EV6 (without HDA II) 2022", "Highway Driving Assist", harness=Harness.hyundai_l), + HyundaiCarInfo("Kia EV6 (with HDA II) 2022", "Highway Driving Assist II", harness=Harness.hyundai_p) ], # Genesis From ed87c0f95a42a304c1ebc2892c1c740f147c78c1 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 13 Oct 2022 19:50:09 -0700 Subject: [PATCH 056/101] CAN-FD HKG: add ADAS Driving ECU query (#26075) add ADAS Driving ECU query --- selfdrive/car/hyundai/values.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index a24992f90f..d3a4b8bbb1 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -299,6 +299,9 @@ FW_QUERY_CONFIG = FwQueryConfig( [HYUNDAI_VERSION_RESPONSE], ), ], + extra_ecus=[ + (Ecu.adas, 0x730, None), # ADAS Driving ECU on HDA2 platforms + ], ) FW_VERSIONS = { From 422167cdf96b52eaaf001f27b447f23055e31709 Mon Sep 17 00:00:00 2001 From: Matt Webb Date: Thu, 13 Oct 2022 20:51:57 -0700 Subject: [PATCH 057/101] HKG: add missing FW versions for 2022 Kia EV6 Light (#26071) Fingerprint 2022 Kia EV6 Light --- selfdrive/car/hyundai/values.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index d3a4b8bbb1..77759f1fa7 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1322,11 +1322,13 @@ FW_VERSIONS = { }, CAR.KIA_EV6: { (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00CV IEB \x02 101!\x10\x18 58520-CV100', b'\xf1\x00CV IEB \x03 101!\x10\x18 58520-CV100', b'\xf1\x8758520CV100\xf1\x00CV IEB \x02 101!\x10\x18 58520-CV100', ], (Ecu.eps, 0x7d4, None): [ b'\xf1\x00CV1 MDPS R 1.00 1.04 57700-CV000 1B30', + b'\xf1\x00CV1 MDPS R 1.00 1.05 57700-CV000 2425', ], (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 ', @@ -1334,6 +1336,7 @@ FW_VERSIONS = { ], (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.05 99210-CV000 211027', + b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.06 99210-CV000 220328', b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.05 99210-CV000 211027', ], }, From 5d00e5cc71106c6c4a9b25e3a2873e9e0606544c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 14 Oct 2022 15:53:24 -0700 Subject: [PATCH 058/101] GM: remove brake scaling (#26080) * Don't add a weird factor to ret.brake * update refs --- selfdrive/car/gm/carstate.py | 4 ++-- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index a5f89c58b0..f90b130d93 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -50,8 +50,8 @@ class CarState(CarStateBase): # that the brake is being intermittently pressed without user interaction. # To avoid a cruise fault we need to match the ECM's brake pressed signal and threshold # https://static.nhtsa.gov/odi/tsbs/2017/MC-10137629-9999.pdf - ret.brake = pt_cp.vl["ECMAcceleratorPos"]["BrakePedalPos"] / 0xd0 - ret.brakePressed = pt_cp.vl["ECMAcceleratorPos"]["BrakePedalPos"] >= 8 + ret.brake = pt_cp.vl["ECMAcceleratorPos"]["BrakePedalPos"] + ret.brakePressed = ret.brake >= 8 # Regen braking is braking if self.CP.transmissionType == TransmissionType.direct: diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 6a8f5a273c..99257fa930 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -1e4bb3f620bddbe6ead966d6f2dd7db3fd730308 \ No newline at end of file +1066a612bcaab6103d44ab93ad68397a85d37833 \ No newline at end of file From c0840e0c33257b7ee86ace2c9a0b985ae61ca71c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 14 Oct 2022 16:50:07 -0700 Subject: [PATCH 059/101] Fix 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 99257fa930..864b7019a0 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -1066a612bcaab6103d44ab93ad68397a85d37833 \ No newline at end of file +e5a86c14e2318f2dd218b3985cdbea6f875f7d83 From 91a7bb4ea3f01f40a7d8e88e857d60ef090dad2c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 14 Oct 2022 16:54:13 -0700 Subject: [PATCH 060/101] GM camera ACC: raise brake pressed threshold (#26081) * Different brake pressed thresholds * comment * bump to master --- panda | 2 +- selfdrive/car/gm/carstate.py | 7 ++++++- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/panda b/panda index c39528d299..5962bcd08a 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit c39528d299aae6a1ebbdbccddeae55bc76a534e3 +Subproject commit 5962bcd08ae4e7c5193535efb45cc9c39da52f54 diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index f90b130d93..21eb440d7f 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -51,7 +51,12 @@ class CarState(CarStateBase): # To avoid a cruise fault we need to match the ECM's brake pressed signal and threshold # https://static.nhtsa.gov/odi/tsbs/2017/MC-10137629-9999.pdf ret.brake = pt_cp.vl["ECMAcceleratorPos"]["BrakePedalPos"] - ret.brakePressed = ret.brake >= 8 + if self.CP.networkLocation != NetworkLocation.fwdCamera: + ret.brakePressed = ret.brake >= 8 + else: + # While car is braking, cancel button causes ECM to enter a soft disable state with a fault status. + # Match ECM threshold at a standstill to allow the camera to cancel earlier + ret.brakePressed = ret.brake >= 20 # Regen braking is braking if self.CP.transmissionType == TransmissionType.direct: From 4e82f68de2641e628f0df1aa82e5a5e935c8cce6 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 14 Oct 2022 22:21:53 -0700 Subject: [PATCH 061/101] GM camera ACC: prevent fault when engaging at a stop (#26079) * prevent bolt fault * comment * only for camera ACC * fixup alert * bump cereal to master * use new name * Update selfdrive/car/gm/interface.py * Update selfdrive/car/gm/interface.py * Update selfdrive/car/gm/interface.py * only care about prevent engagement when we look at PCM --- cereal | 2 +- selfdrive/car/gm/interface.py | 8 +++++++- selfdrive/controls/lib/events.py | 4 ++++ 3 files changed, 12 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index 3eca747334..5766e645f2 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 3eca747334ca2138bf35d70399d58d0706a3cbd2 +Subproject commit 5766e645f2ee2a131b145fb1ea9e3b7c55a4a740 diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 22ea83759a..248828e757 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -212,7 +212,13 @@ class CarInterface(CarInterfaceBase): if ret.cruiseState.standstill: events.add(EventName.resumeRequired) if ret.vEgo < self.CP.minSteerSpeed: - events.add(car.CarEvent.EventName.belowSteerSpeed) + events.add(EventName.belowSteerSpeed) + + if self.CP.networkLocation == NetworkLocation.fwdCamera and self.CP.pcmCruise: + # The ECM has a higher brake pressed threshold than the camera, causing an + # ACC fault when you engage at a stop with your foot partially on the brake + if ret.vEgoRaw < 0.1 and ret.brake < 20: + events.add(EventName.gmAccFaultedTemp) ret.events = events.to_msg() diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 91f1748ecb..5bfe89b31c 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -811,6 +811,10 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { ET.NO_ENTRY: NoEntryAlert("Cruise Faulted"), }, + EventName.gmAccFaultedTemp: { + ET.NO_ENTRY: NoEntryAlert("Cruise Temporarily Faulted"), + }, + EventName.controlsMismatch: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("Controls Mismatch"), ET.NO_ENTRY: NoEntryAlert("Controls Mismatch"), From deac907cb44230f641fde5ca1ba22d7c5e236d90 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 16 Oct 2022 02:36:09 +0800 Subject: [PATCH 062/101] Cabana: right click on the chart to reset zoom (#26088) --- tools/cabana/chartswidget.cc | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index e704dea95a..5dafd8ec37 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -305,8 +305,14 @@ void ChartView::mouseReleaseEvent(QMouseEvent *event) { event->accept(); return; } + } else if (event->button() == Qt::RightButton) { + // reset zoom + if (can->isZoomed()) { + can->resetRange(); + event->accept(); + return; + } } - // TODO: right-click to reset zoom QChartView::mouseReleaseEvent(event); line_marker->setVisible(true); } From df6c135cfaabe830d2447800d49daac445660c64 Mon Sep 17 00:00:00 2001 From: AlexandreSato <66435071+AlexandreSato@users.noreply.github.com> Date: Sat, 15 Oct 2022 16:15:47 -0300 Subject: [PATCH 063/101] Multilang: Update pt-BR translation. (#26089) * update pt-BR translations * fix some cutoff texts * update pt-BR translations --- selfdrive/ui/translations/main_pt-BR.ts | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 6a772a1f69..8f59bf4715 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -60,11 +60,11 @@ Cellular Metered - + Plano de Dados Limitado Prevent large data uploads when on a metered connection - + Evite grandes uploads de dados quando estiver em uma conexão limitada @@ -476,7 +476,7 @@ trabalho definido PRIME FEATURES: - APRIMORAMENTOS PRIME: + BENEFÍCIOS PRIME: Remote access From 553068f8c3afd9fd2c3a3a412dd20a8e03c6c58f Mon Sep 17 00:00:00 2001 From: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com> Date: Sat, 15 Oct 2022 15:27:34 -0400 Subject: [PATCH 064/101] Hyundai: CAN-FD Hybrid gas pressed signal (#26086) * Hyundai: Gate 0x105 behind hybrid CAN-FD only * Update values.py * bump panda Co-authored-by: Adeeb Shihadeh --- panda | 2 +- selfdrive/car/hyundai/carstate.py | 4 ++-- selfdrive/car/hyundai/values.py | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/panda b/panda index 5962bcd08a..62868c36a8 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 5962bcd08ae4e7c5193535efb45cc9c39da52f54 +Subproject commit 62868c36a80d1f44064da7b47423f0ef331f64e9 diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 948634e974..5da1dd72c8 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -156,7 +156,7 @@ class CarState(CarStateBase): if self.CP.carFingerprint in EV_CAR: ret.gas = cp.vl["ACCELERATOR"]["ACCELERATOR_PEDAL"] / 255. - else: + elif self.CP.carFingerprint in HYBRID_CAR: ret.gas = cp.vl["ACCELERATOR_ALT"]["ACCELERATOR_PEDAL"] / 1023. ret.gasPressed = ret.gas > 1e-5 ret.brakePressed = cp.vl["BRAKE"]["BRAKE_PRESSED"] == 1 @@ -466,7 +466,7 @@ class CarState(CarStateBase): checks += [ ("ACCELERATOR", 100), ] - else: + elif CP.carFingerprint in HYBRID_CAR: signals += [ ("ACCELERATOR_PEDAL", "ACCELERATOR_ALT"), ] diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 77759f1fa7..734e56c033 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1397,7 +1397,7 @@ CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.TUCSON_HYBRID_4TH_GEN} # The camera does SCC on these cars, rather than the radar CAMERA_SCC_CAR = {CAR.KONA_EV_2022, } -HYBRID_CAR = {CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019} # these cars use a different gas signal +HYBRID_CAR = {CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.TUCSON_HYBRID_4TH_GEN} # these cars use a different gas signal EV_CAR = {CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_NIRO_EV, CAR.KONA_EV_2022, CAR.KIA_EV6, CAR.IONIQ_5} # these cars require a special panda safety mode due to missing counters and checksums in the messages From bf5a6565c0f2d6791606ff906f6ddb4cba27fb18 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 15 Oct 2022 16:05:52 -0700 Subject: [PATCH 065/101] cabana: misc touchups (#26092) * fix time formatting * disable vertical resize * Update tools/cabana/videowidget.cc --- tools/cabana/detailwidget.cc | 2 +- tools/cabana/videowidget.cc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/tools/cabana/detailwidget.cc b/tools/cabana/detailwidget.cc index 531cd4c665..4127b6c3ed 100644 --- a/tools/cabana/detailwidget.cc +++ b/tools/cabana/detailwidget.cc @@ -1,4 +1,3 @@ - #include "tools/cabana/detailwidget.h" #include @@ -138,6 +137,7 @@ BinaryView::BinaryView(QWidget *parent) { QVBoxLayout *main_layout = new QVBoxLayout(this); main_layout->setContentsMargins(0, 0, 0, 0); table = new QTableWidget(this); + table->verticalHeader()->setSectionResizeMode(QHeaderView::Stretch); table->horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); table->horizontalHeader()->hide(); table->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc index 193a6f8788..9e2129afaf 100644 --- a/tools/cabana/videowidget.cc +++ b/tools/cabana/videowidget.cc @@ -11,7 +11,7 @@ #include inline QString formatTime(int seconds) { - return QDateTime::fromTime_t(seconds).toString(seconds > 60 * 60 ? "hh::mm::ss" : "mm::ss"); + return QDateTime::fromTime_t(seconds).toString(seconds > 60 * 60 ? "hh:mm:ss" : "mm:ss"); } VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) { From b654ebdd25bb3903e94ca5cc6f55d53a256f5c06 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Sat, 15 Oct 2022 20:04:35 -0700 Subject: [PATCH 066/101] Refactor model: no klblock (#26035) * ff138dc0-d097-4818-b40e-dba5ba89d5d6/449 13274b7d-b546-4b91-a587-33b4af7dec6a/700 * b1bb39be-c6ce-4744-8e63-92969fda6bfc/449 f3ebfba1-f686-448f-be9b-b4d5010be91c/700 * model ref Co-authored-by: Yassine Yousfi --- selfdrive/modeld/models/supercombo.onnx | 4 ++-- selfdrive/test/process_replay/model_replay_ref_commit | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index aee0ac37ff..59b8883d2a 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:c4d37af666344af6bb218e0b939b1152ad3784c15ac79e37bcf0124643c8286a -size 58539563 +oid sha256:022a830c39267f378f45204682060c93e3aa304bbd8cfa6b2dfe4fa8f419102d +size 56972617 diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 2446ec061d..b3e9c8c488 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -c171250d2cc013b3eca1cda4fb62f3d0dda28d4d +bfb0a2a52212d2aa1619d999aaae97fa7f7ff788 From e25ea8529698053f4c1b915b7e014ebdc499e56a Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 16 Oct 2022 22:55:53 +0800 Subject: [PATCH 067/101] Cabana: complete edit functions (#26097) complete forms --- tools/cabana/chartswidget.cc | 105 ++++++++-------- tools/cabana/chartswidget.h | 25 ++-- tools/cabana/dbcmanager.cc | 22 ++-- tools/cabana/dbcmanager.h | 7 +- tools/cabana/detailwidget.cc | 215 ++++++++++++++++++--------------- tools/cabana/detailwidget.h | 42 +++---- tools/cabana/historylog.cc | 5 +- tools/cabana/messageswidget.cc | 20 +-- tools/cabana/signaledit.cc | 74 +++++------- tools/cabana/signaledit.h | 29 ++--- 10 files changed, 260 insertions(+), 284 deletions(-) diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index 5dafd8ec37..d0f5356fac 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -1,7 +1,6 @@ #include "tools/cabana/chartswidget.h" #include -#include #include #include #include @@ -14,6 +13,7 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) { // title bar title_bar = new QWidget(this); + title_bar->setVisible(false); QHBoxLayout *title_layout = new QHBoxLayout(title_bar); title_layout->setContentsMargins(0, 0, 0, 0); title_label = new QLabel(tr("Charts")); @@ -25,13 +25,11 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) { title_layout->addWidget(range_label); reset_zoom_btn = new QPushButton("⟲", this); - reset_zoom_btn->setVisible(false); reset_zoom_btn->setFixedSize(30, 30); reset_zoom_btn->setToolTip(tr("Reset zoom (drag on chart to zoom X-Axis)")); title_layout->addWidget(reset_zoom_btn); remove_all_btn = new QPushButton("✖", this); - remove_all_btn->setVisible(false); remove_all_btn->setToolTip(tr("Remove all charts")); remove_all_btn->setFixedSize(30, 30); title_layout->addWidget(remove_all_btn); @@ -56,10 +54,20 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) { main_layout->addWidget(charts_scroll); - updateTitleBar(); - - QObject::connect(dbc(), &DBCManager::signalRemoved, this, &ChartsWidget::removeChart); QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &ChartsWidget::removeAll); + QObject::connect(dbc(), &DBCManager::signalRemoved, this, &ChartsWidget::removeChart); + QObject::connect(dbc(), &DBCManager::signalUpdated, [this](const Signal *sig) { + if (auto it = charts.find(sig); it != charts.end()) { + it.value()->chart_view->updateSeries(); + } + }); + QObject::connect(dbc(), &DBCManager::msgUpdated, [this](const QString &id) { + for (auto chart : charts) { + if (chart->id == id) + chart->updateTitle(); + } + }); + QObject::connect(can, &CANMessages::rangeChanged, [this]() { updateTitleBar(); }); QObject::connect(reset_zoom_btn, &QPushButton::clicked, can, &CANMessages::resetRange); QObject::connect(remove_all_btn, &QPushButton::clicked, this, &ChartsWidget::removeAll); @@ -71,54 +79,43 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) { } void ChartsWidget::updateTitleBar() { - if (!charts.size()) { - title_bar->setVisible(false); - return; - } - - title_label->setText(tr("Charts (%1)").arg(charts.size())); + title_bar->setVisible(!charts.isEmpty()); + if (charts.isEmpty()) return; // show select range + range_label->setVisible(can->isZoomed()); + reset_zoom_btn->setEnabled(can->isZoomed()); if (can->isZoomed()) { auto [min, max] = can->range(); range_label->setText(tr("%1 - %2").arg(min, 0, 'f', 2).arg(max, 0, 'f', 2)); - range_label->setVisible(true); - reset_zoom_btn->setEnabled(true); - } else { - reset_zoom_btn->setEnabled(false); - range_label->setVisible(false); } + title_label->setText(tr("Charts (%1)").arg(charts.size())); dock_btn->setText(docking ? "⬈" : "⬋"); dock_btn->setToolTip(docking ? tr("Undock charts") : tr("Dock charts")); - remove_all_btn->setVisible(!charts.empty()); - reset_zoom_btn->setVisible(!charts.empty()); - title_bar->setVisible(true); } -void ChartsWidget::addChart(const QString &id, const QString &sig_name) { - const QString char_name = id + ":" + sig_name; - if (charts.find(char_name) == charts.end()) { - auto chart = new ChartWidget(id, sig_name, this); - QObject::connect(chart, &ChartWidget::remove, [=]() { - removeChart(id, sig_name); - }); +void ChartsWidget::addChart(const QString &id, const Signal *sig) { + if (!charts.contains(sig)) { + auto chart = new ChartWidget(id, sig, this); + QObject::connect(chart, &ChartWidget::remove, [=]() { removeChart(sig); }); charts_layout->insertWidget(0, chart); - charts[char_name] = chart; + charts.insert(sig, chart); } updateTitleBar(); } -void ChartsWidget::removeChart(const QString &id, const QString &sig_name) { - if (auto it = charts.find(id + ":" + sig_name); it != charts.end()) { - it->second->deleteLater(); - charts.erase(it); +void ChartsWidget::removeChart(const Signal *sig) { + auto it = charts.find(sig); + if (it != charts.end()) { + it.value()->deleteLater(); + charts.remove(sig); } updateTitleBar(); } void ChartsWidget::removeAll() { - for (auto [_, chart] : charts) + for (auto chart : charts) chart->deleteLater(); charts.clear(); updateTitleBar(); @@ -134,19 +131,16 @@ bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) { // ChartWidget -ChartWidget::ChartWidget(const QString &id, const QString &sig_name, QWidget *parent) : id(id), sig_name(sig_name), QWidget(parent) { +ChartWidget::ChartWidget(const QString &id, const Signal *sig, QWidget *parent) : id(id), signal(sig), QWidget(parent) { QVBoxLayout *main_layout = new QVBoxLayout(this); - - QWidget *chart_widget = new QWidget(this); - QVBoxLayout *chart_layout = new QVBoxLayout(chart_widget); - chart_layout->setSpacing(0); - chart_layout->setContentsMargins(0, 0, 0, 0); + main_layout->setSpacing(0); + main_layout->setContentsMargins(0, 0, 0, 0); QWidget *header = new QWidget(this); header->setStyleSheet("background-color:white"); QHBoxLayout *header_layout = new QHBoxLayout(header); header_layout->setContentsMargins(11, 11, 11, 0); - QLabel *title = new QLabel(tr("%1 %2").arg(dbc()->msg(id)->name.c_str()).arg(id)); + title = new QLabel(tr("%1 %2").arg(dbc()->msg(id)->name.c_str()).arg(id)); header_layout->addWidget(title); header_layout->addStretch(); @@ -155,26 +149,28 @@ ChartWidget::ChartWidget(const QString &id, const QString &sig_name, QWidget *pa remove_btn->setToolTip(tr("Remove chart")); QObject::connect(remove_btn, &QPushButton::clicked, this, &ChartWidget::remove); header_layout->addWidget(remove_btn); - chart_layout->addWidget(header); + main_layout->addWidget(header); - chart_view = new ChartView(id, sig_name, this); + chart_view = new ChartView(id, sig, this); chart_view->setFixedHeight(300); - chart_layout->addWidget(chart_view); - chart_layout->addStretch(); - - main_layout->addWidget(chart_widget); + main_layout->addWidget(chart_view); + main_layout->addStretch(); setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Fixed); } +void ChartWidget::updateTitle() { + title->setText(tr("%1 %2").arg(dbc()->msg(id)->name.c_str()).arg(id)); +} + // ChartView -ChartView::ChartView(const QString &id, const QString &sig_name, QWidget *parent) - : id(id), sig_name(sig_name), QChartView(nullptr, parent) { +ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent) + : id(id), signal(sig), QChartView(nullptr, parent) { QLineSeries *series = new QLineSeries(); series->setUseOpenGL(true); QChart *chart = new QChart(); - chart->setTitle(sig_name); + chart->setTitle(sig->name.c_str()); chart->addSeries(series); chart->createDefaultAxes(); chart->legend()->hide(); @@ -205,10 +201,7 @@ ChartView::ChartView(const QString &id, const QString &sig_name, QWidget *parent QObject::connect(can, &CANMessages::rangeChanged, this, &ChartView::rangeChanged); QObject::connect(can, &CANMessages::eventsMerged, this, &ChartView::updateSeries); QObject::connect(dynamic_cast(chart->axisX()), &QValueAxis::rangeChanged, can, &CANMessages::setRange); - QObject::connect(dbc(), &DBCManager::signalUpdated, [this](const QString &msg_id, const QString &sig_name) { - if (this->id == msg_id && this->sig_name == sig_name) - updateSeries(); - }); + updateSeries(); } @@ -219,9 +212,9 @@ void ChartView::updateState() { } void ChartView::updateSeries() { - const Signal *sig = dbc()->signal(id, sig_name); + chart()->setTitle(signal->name.c_str()); auto events = can->events(); - if (!sig || !events) return; + if (!events) return; auto l = id.split(':'); int bus = l[0].toInt(); @@ -235,7 +228,7 @@ void ChartView::updateSeries() { for (auto c : evt->event.getCan()) { if (bus == c.getSrc() && address == c.getAddress()) { auto dat = c.getDat(); - double value = get_raw_value((uint8_t *)dat.begin(), dat.size(), *sig); + double value = get_raw_value((uint8_t *)dat.begin(), dat.size(), *signal); double ts = (evt->mono_time / (double)1e9) - route_start_time; // seconds vals.push_back({ts, value}); } diff --git a/tools/cabana/chartswidget.h b/tools/cabana/chartswidget.h index af12560cc9..a3c470e960 100644 --- a/tools/cabana/chartswidget.h +++ b/tools/cabana/chartswidget.h @@ -9,7 +9,6 @@ #include #include #include -#include #include "tools/cabana/canmessages.h" #include "tools/cabana/dbcmanager.h" @@ -20,7 +19,8 @@ class ChartView : public QChartView { Q_OBJECT public: - ChartView(const QString &id, const QString &sig_name, QWidget *parent = nullptr); + ChartView(const QString &id, const Signal *sig, QWidget *parent = nullptr); + void updateSeries(); private: void mouseReleaseEvent(QMouseEvent *event) override; @@ -28,7 +28,6 @@ private: void enterEvent(QEvent *event) override; void leaveEvent(QEvent *event) override; - void updateSeries(); void rangeChanged(qreal min, qreal max); void updateAxisY(); void updateState(); @@ -38,22 +37,23 @@ private: QGraphicsLineItem *line_marker; QList vals; QString id; - QString sig_name; + const Signal *signal; }; class ChartWidget : public QWidget { Q_OBJECT public: - ChartWidget(const QString &id, const QString &sig_name, QWidget *parent); - inline QChart *chart() const { return chart_view->chart(); } + ChartWidget(const QString &id, const Signal *sig, QWidget *parent); + void updateTitle(); signals: void remove(); -protected: +public: QString id; - QString sig_name; + const Signal *signal; + QLabel *title; ChartView *chart_view = nullptr; }; @@ -62,11 +62,8 @@ class ChartsWidget : public QWidget { public: ChartsWidget(QWidget *parent = nullptr); - void addChart(const QString &id, const QString &sig_name); - void removeChart(const QString &id, const QString &sig_name); - inline bool hasChart(const QString &id, const QString &sig_name) { - return charts.find(id + sig_name) != charts.end(); - } + void addChart(const QString &id, const Signal *sig); + void removeChart(const Signal *sig); signals: void dock(bool floating); @@ -85,5 +82,5 @@ private: QPushButton *reset_zoom_btn; QPushButton *remove_all_btn; QVBoxLayout *charts_layout; - std::map charts; + QHash charts; }; diff --git a/tools/cabana/dbcmanager.cc b/tools/cabana/dbcmanager.cc index 1cb6da7fb5..5b1bddcabe 100644 --- a/tools/cabana/dbcmanager.cc +++ b/tools/cabana/dbcmanager.cc @@ -36,14 +36,17 @@ void DBCManager::updateMsg(const QString &id, const QString &name, uint32_t size void DBCManager::addSignal(const QString &id, const Signal &sig) { if (Msg *m = const_cast(msg(id))) { m->sigs.push_back(sig); - emit signalAdded(id, QString::fromStdString(sig.name)); + emit signalAdded(&m->sigs.back()); } } void DBCManager::updateSignal(const QString &id, const QString &sig_name, const Signal &sig) { - if (Signal *s = const_cast(signal(id, sig_name))) { - *s = sig; - emit signalUpdated(id, sig_name); + if (Msg *m = const_cast(msg(id))) { + auto it = std::find_if(m->sigs.begin(), m->sigs.end(), [=](auto &sig) { return sig_name == sig.name.c_str(); }); + if (it != m->sigs.end()) { + *it = sig; + emit signalUpdated(&(*it)); + } } } @@ -51,21 +54,12 @@ void DBCManager::removeSignal(const QString &id, const QString &sig_name) { if (Msg *m = const_cast(msg(id))) { auto it = std::find_if(m->sigs.begin(), m->sigs.end(), [=](auto &sig) { return sig_name == sig.name.c_str(); }); if (it != m->sigs.end()) { + emit signalRemoved(&(*it)); m->sigs.erase(it); - emit signalRemoved(id, sig_name); } } } -const Signal *DBCManager::signal(const QString &id, const QString &sig_name) const { - if (auto m = msg(id)) { - auto it = std::find_if(m->sigs.begin(), m->sigs.end(), [&](auto &s) { return sig_name == s.name.c_str(); }); - if (it != m->sigs.end()) - return &(*it); - } - return nullptr; -} - uint32_t DBCManager::addressFromId(const QString &id) { return id.mid(id.indexOf(':') + 1).toUInt(nullptr, 16); } diff --git a/tools/cabana/dbcmanager.h b/tools/cabana/dbcmanager.h index 06c071be82..1f890a39db 100644 --- a/tools/cabana/dbcmanager.h +++ b/tools/cabana/dbcmanager.h @@ -14,7 +14,6 @@ public: void open(const QString &dbc_file_name); void save(const QString &dbc_file_name); - const Signal *signal(const QString &id, const QString &sig_name) const; void addSignal(const QString &id, const Signal &sig); void updateSignal(const QString &id, const QString &sig_name, const Signal &sig); void removeSignal(const QString &id, const QString &sig_name); @@ -31,9 +30,9 @@ public: } signals: - void signalAdded(const QString &id, const QString &sig_name); - void signalRemoved(const QString &id, const QString &sig_name); - void signalUpdated(const QString &id, const QString &sig_name); + void signalAdded(const Signal *sig); + void signalRemoved(const Signal *sig); + void signalUpdated(const Signal *sig); void msgUpdated(const QString &id); void DBCFileChanged(); diff --git a/tools/cabana/detailwidget.cc b/tools/cabana/detailwidget.cc index 4127b6c3ed..021e1b73cf 100644 --- a/tools/cabana/detailwidget.cc +++ b/tools/cabana/detailwidget.cc @@ -3,9 +3,9 @@ #include #include #include +#include #include #include -#include // DetailWidget @@ -32,60 +32,52 @@ DetailWidget::DetailWidget(QWidget *parent) : QWidget(parent) { binary_view = new BinaryView(this); main_layout->addWidget(binary_view, 0, Qt::AlignTop); - // signal header - signals_header = new QWidget(this); - QHBoxLayout *signals_header_layout = new QHBoxLayout(signals_header); - signals_header_layout->addWidget(new QLabel(tr("Signals"))); - signals_header_layout->addStretch(); - QPushButton *add_sig_btn = new QPushButton(tr("Add signal"), this); - signals_header_layout->addWidget(add_sig_btn); - signals_header->setVisible(false); - main_layout->addWidget(signals_header); - - // scroll area + // signals + signals_container = new QWidget(this); + signals_container->setLayout(new QVBoxLayout); + signals_container->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Maximum); + scroll = new ScrollArea(this); - QWidget *container = new QWidget(this); - container->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Maximum); - QVBoxLayout *container_layout = new QVBoxLayout(container); - signal_edit_layout = new QVBoxLayout(); - signal_edit_layout->setSpacing(2); - container_layout->addLayout(signal_edit_layout); - - scroll->setWidget(container); + scroll->setWidget(signals_container); scroll->setWidgetResizable(true); scroll->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); main_layout->addWidget(scroll); + // history log history_log = new HistoryLog(this); main_layout->addWidget(history_log); - QObject::connect(add_sig_btn, &QPushButton::clicked, this, &DetailWidget::addSignal); QObject::connect(edit_btn, &QPushButton::clicked, this, &DetailWidget::editMsg); + QObject::connect(binary_view, &BinaryView::cellsSelected, this, &DetailWidget::addSignal); QObject::connect(can, &CANMessages::updated, this, &DetailWidget::updateState); + QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &DetailWidget::dbcMsgChanged); } void DetailWidget::setMessage(const QString &message_id) { - msg_id = message_id; - for (auto f : signal_forms) { - f->deleteLater(); + if (msg_id != message_id) { + msg_id = message_id; + dbcMsgChanged(); } - signal_forms.clear(); +} + +void DetailWidget::dbcMsgChanged() { + if (msg_id.isEmpty()) return; + qDeleteAll(signals_container->findChildren()); + QString msg_name = tr("untitled"); if (auto msg = dbc()->msg(msg_id)) { for (int i = 0; i < msg->sigs.size(); ++i) { - auto form = new SignalEdit(i, msg_id, msg->sigs[i], getColor(i)); - signal_edit_layout->addWidget(form); - QObject::connect(form, &SignalEdit::showChart, this, &DetailWidget::showChart); + auto form = new SignalEdit(i, msg_id, msg->sigs[i]); + signals_container->layout()->addWidget(form); + QObject::connect(form, &SignalEdit::showChart, [this, sig = &msg->sigs[i]]() { emit showChart(msg_id, sig); }); QObject::connect(form, &SignalEdit::showFormClicked, this, &DetailWidget::showForm); - signal_forms.push_back(form); + QObject::connect(form, &SignalEdit::remove, this, &DetailWidget::removeSignal); + QObject::connect(form, &SignalEdit::save, this, &DetailWidget::saveSignal); } - name_label->setText(msg->name.c_str()); - signals_header->setVisible(true); - } else { - name_label->setText(tr("untitled")); - signals_header->setVisible(false); + msg_name = msg->name.c_str(); } edit_btn->setVisible(true); + name_label->setText(msg_name); binary_view->setMessage(msg_id); history_log->setMessage(msg_id); @@ -99,60 +91,90 @@ void DetailWidget::updateState() { history_log->updateState(); } -void DetailWidget::editMsg() { - EditMessageDialog dlg(msg_id, this); - if (dlg.exec()) { - setMessage(msg_id); +void DetailWidget::showForm() { + SignalEdit *sender = qobject_cast(QObject::sender()); + for (auto f : signals_container->findChildren()) { + f->setFormVisible(f == sender && !f->isFormVisible()); + if (f == sender) { + QTimer::singleShot(0, [=]() { scroll->ensureWidgetVisible(f); }); + } } } -void DetailWidget::addSignal() { - AddSignalDialog dlg(msg_id, this); +void DetailWidget::editMsg() { + auto msg = dbc()->msg(msg_id); + QString name = msg ? msg->name.c_str() : "untitled"; + int size = msg ? msg->size : can->lastMessage(msg_id).dat.size(); + EditMessageDialog dlg(msg_id, name, size, this); if (dlg.exec()) { - setMessage(msg_id); + dbc()->updateMsg(msg_id, dlg.name_edit->text(), dlg.size_spin->value()); + dbcMsgChanged(); } } -void DetailWidget::showForm() { - SignalEdit *sender = qobject_cast(QObject::sender()); - if (sender->isFormVisible()) { - sender->setFormVisible(false); - } else { - for (auto f : signal_forms) { - f->setFormVisible(f == sender); - if (f == sender) { - // scroll to header - QTimer::singleShot(0, [=]() { - const QPoint p = f->mapTo(scroll, QPoint(0, 0)); - scroll->verticalScrollBar()->setValue(p.y() + scroll->verticalScrollBar()->value()); - }); - } +void DetailWidget::addSignal(int start_bit, int size) { + if (dbc()->msg(msg_id)) { + AddSignalDialog dlg(msg_id, start_bit, size, this); + if (dlg.exec()) { + dbc()->addSignal(msg_id, dlg.form->getSignal()); + dbcMsgChanged(); } } } +void DetailWidget::saveSignal() { + SignalEdit *sig_form = qobject_cast(QObject::sender()); + auto s = sig_form->form->getSignal(); + dbc()->updateSignal(msg_id, sig_form->sig_name, s); + // update binary view and history log + binary_view->setMessage(msg_id); + history_log->setMessage(msg_id); +} + +void DetailWidget::removeSignal() { + SignalEdit *sig_form = qobject_cast(QObject::sender()); + QString text = tr("Are you sure you want to remove signal '%1'").arg(sig_form->sig_name); + if (QMessageBox::Yes == QMessageBox::question(this, tr("Remove signal"), text)) { + dbc()->removeSignal(msg_id, sig_form->sig_name); + dbcMsgChanged(); + } +} + // BinaryView -BinaryView::BinaryView(QWidget *parent) { - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(0, 0, 0, 0); - table = new QTableWidget(this); - table->verticalHeader()->setSectionResizeMode(QHeaderView::Stretch); - table->horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); - table->horizontalHeader()->hide(); - table->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); - main_layout->addWidget(table); - table->setColumnCount(9); +BinaryView::BinaryView(QWidget *parent) : QTableWidget(parent) { + horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); + verticalHeader()->setSectionResizeMode(QHeaderView::Stretch); + horizontalHeader()->hide(); + setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + setColumnCount(9); + + // replace selection model + auto old_model = selectionModel(); + setSelectionModel(new BinarySelectionModel(model())); + delete old_model; +} + +void BinaryView::mouseReleaseEvent(QMouseEvent *event) { + QTableWidget::mouseReleaseEvent(event); + + if (auto items = selectedItems(); !items.isEmpty()) { + int start_bit = items.first()->row() * 8 + items.first()->column(); + int size = items.back()->row() * 8 + items.back()->column() - start_bit + 1; + emit cellsSelected(start_bit, size); + } } void BinaryView::setMessage(const QString &message_id) { msg_id = message_id; + if (msg_id.isEmpty()) return; + const Msg *msg = dbc()->msg(msg_id); - const int row_count = msg ? msg->size : can->lastMessage(msg_id).dat.size(); - table->setRowCount(row_count); - table->setColumnCount(9); - for (int i = 0; i < table->rowCount(); ++i) { - for (int j = 0; j < table->columnCount(); ++j) { + int row_count = msg ? msg->size : can->lastMessage(msg_id).dat.size(); + setRowCount(row_count); + setColumnCount(9); + for (int i = 0; i < rowCount(); ++i) { + for (int j = 0; j < columnCount(); ++j) { auto item = new QTableWidgetItem(); item->setFlags(item->flags() ^ Qt::ItemIsEditable); item->setTextAlignment(Qt::AlignCenter); @@ -160,8 +182,9 @@ void BinaryView::setMessage(const QString &message_id) { QFont font; font.setBold(true); item->setFont(font); + item->setFlags(item->flags() ^ Qt::ItemIsSelectable); } - table->setItem(i, j, item); + setItem(i, j, item); } } @@ -170,71 +193,73 @@ void BinaryView::setMessage(const QString &message_id) { for (int i = 0; i < msg->sigs.size(); ++i) { const auto &sig = msg->sigs[i]; int start = sig.is_little_endian ? sig.start_bit : bigEndianBitIndex(sig.start_bit); - for (int j = start; j <= start + sig.size - 1; ++j) { - table->item(j / 8, j % 8)->setBackground(QColor(getColor(i))); + for (int j = start; j <= std::min(start + sig.size - 1, rowCount() * columnCount() - 1); ++j) { + item(j / 8, j % 8)->setBackground(QColor(getColor(i))); } } } - table->setFixedHeight(table->rowHeight(0) * std::min(row_count, 8) + 2); + + setFixedHeight(rowHeight(0) * std::min(row_count, 8) + 2); + clearSelection(); updateState(); } void BinaryView::updateState() { - if (msg_id.isEmpty()) return; - const auto &binary = can->lastMessage(msg_id).dat; - setUpdatesEnabled(false); char hex[3] = {'\0'}; for (int i = 0; i < binary.size(); ++i) { for (int j = 0; j < 8; ++j) { - table->item(i, j)->setText(QChar((binary[i] >> (7 - j)) & 1 ? '1' : '0')); + item(i, j)->setText(QChar((binary[i] >> (7 - j)) & 1 ? '1' : '0')); } hex[0] = toHex(binary[i] >> 4); hex[1] = toHex(binary[i] & 0xf); - table->item(i, 8)->setText(hex); + item(i, 8)->setText(hex); } setUpdatesEnabled(true); } +void BinarySelectionModel::select(const QItemSelection &selection, QItemSelectionModel::SelectionFlags command) { + QItemSelection new_selection = selection; + if (auto indexes = selection.indexes(); !indexes.isEmpty()) { + auto [begin_idx, end_idx] = (QModelIndex[]){indexes.first(), indexes.back()}; + for (int row = begin_idx.row(); row <= end_idx.row(); ++row) { + int left_col = (row == begin_idx.row()) ? begin_idx.column() : 0; + int right_col = (row == end_idx.row()) ? end_idx.column() : 7; + new_selection.merge({model()->index(row, left_col), model()->index(row, right_col)}, command); + } + } + QItemSelectionModel::select(new_selection, command); +} + // EditMessageDialog -EditMessageDialog::EditMessageDialog(const QString &msg_id, QWidget *parent) : msg_id(msg_id), QDialog(parent) { +EditMessageDialog::EditMessageDialog(const QString &msg_id, const QString &title, int size, QWidget *parent) : QDialog(parent) { setWindowTitle(tr("Edit message")); QVBoxLayout *main_layout = new QVBoxLayout(this); QFormLayout *form_layout = new QFormLayout(); form_layout->addRow("ID", new QLabel(msg_id)); - const auto msg = dbc()->msg(msg_id); - name_edit = new QLineEdit(this); - name_edit->setText(msg ? msg->name.c_str() : "untitled"); + name_edit = new QLineEdit(title, this); form_layout->addRow(tr("Name"), name_edit); size_spin = new QSpinBox(this); - size_spin->setValue(msg ? msg->size : can->lastMessage(msg_id).dat.size()); + // TODO: limit the maximum? + size_spin->setMinimum(1); + size_spin->setValue(size); form_layout->addRow(tr("Size"), size_spin); main_layout->addLayout(form_layout); auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); main_layout->addWidget(buttonBox); - setFixedWidth(parent->width() * 0.9); - connect(buttonBox, &QDialogButtonBox::accepted, this, &EditMessageDialog::save); + connect(buttonBox, &QDialogButtonBox::accepted, this, &QDialog::accept); connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); } -void EditMessageDialog::save() { - const QString name = name_edit->text(); - if (size_spin->value() <= 0 || name_edit->text().isEmpty() || name == tr("untitled")) - return; - - dbc()->updateMsg(msg_id, name, size_spin->value()); - QDialog::accept(); -} - // ScrollArea bool ScrollArea::eventFilter(QObject *obj, QEvent *ev) { diff --git a/tools/cabana/detailwidget.h b/tools/cabana/detailwidget.h index 99fe321012..db174873f7 100644 --- a/tools/cabana/detailwidget.h +++ b/tools/cabana/detailwidget.h @@ -1,12 +1,7 @@ #pragma once -#include -#include -#include #include #include -#include -#include #include "opendbc/can/common.h" #include "opendbc/can/common_dbc.h" @@ -15,29 +10,32 @@ #include "tools/cabana/historylog.h" #include "tools/cabana/signaledit.h" -class BinaryView : public QWidget { - Q_OBJECT +class BinarySelectionModel : public QItemSelectionModel { +public: + BinarySelectionModel(QAbstractItemModel *model = nullptr) : QItemSelectionModel(model) {} + void select(const QItemSelection &selection, QItemSelectionModel::SelectionFlags command) override; +}; +class BinaryView : public QTableWidget { + Q_OBJECT public: - BinaryView(QWidget *parent); + BinaryView(QWidget *parent = nullptr); + void mouseReleaseEvent(QMouseEvent *event) override; void setMessage(const QString &message_id); void updateState(); +signals: + void cellsSelected(int start_bit, int size); private: QString msg_id; - QTableWidget *table; }; class EditMessageDialog : public QDialog { Q_OBJECT public: - EditMessageDialog(const QString &msg_id, QWidget *parent); + EditMessageDialog(const QString &msg_id, const QString &title, int size, QWidget *parent); -protected: - void save(); - - QString msg_id; QLineEdit *name_edit; QSpinBox *size_spin; }; @@ -57,24 +55,24 @@ class DetailWidget : public QWidget { public: DetailWidget(QWidget *parent); void setMessage(const QString &message_id); + void dbcMsgChanged(); signals: - void showChart(const QString &msg_id, const QString &sig_name); - -private slots: - void showForm(); + void showChart(const QString &msg_id, const Signal *sig); + void removeChart(const Signal *sig); private: - void addSignal(); + void addSignal(int start_bit, int size); + void saveSignal(); + void removeSignal(); void editMsg(); + void showForm(); void updateState(); QString msg_id; QLabel *name_label, *time_label; QPushButton *edit_btn; - QVBoxLayout *signal_edit_layout; - QWidget *signals_header; - QList signal_forms; + QWidget *signals_container; HistoryLog *history_log; BinaryView *binary_view; ScrollArea *scroll; diff --git a/tools/cabana/historylog.cc b/tools/cabana/historylog.cc index 494e281cb1..5a77b5aa9e 100644 --- a/tools/cabana/historylog.cc +++ b/tools/cabana/historylog.cc @@ -52,9 +52,8 @@ QVariant HistoryLogModel::headerData(int section, Qt::Orientation orientation, i void HistoryLogModel::updateState() { if (msg_id.isEmpty()) return; - const auto &can_msgs = can->messages(msg_id); int prev_row_count = row_count; - row_count = can_msgs.size(); + row_count = can->messages(msg_id).size(); int delta = row_count - prev_row_count; if (delta > 0) { beginInsertRows({}, prev_row_count, row_count - 1); @@ -64,7 +63,7 @@ void HistoryLogModel::updateState() { endRemoveRows(); } if (row_count > 0) { - emit dataChanged(index(0, 0), index(row_count - 1, column_count - 1)); + emit dataChanged(index(0, 0), index(row_count - 1, column_count - 1), {Qt::DisplayRole}); emit headerDataChanged(Qt::Vertical, 0, row_count - 1); } } diff --git a/tools/cabana/messageswidget.cc b/tools/cabana/messageswidget.cc index eaf84fbace..f10cbf44b4 100644 --- a/tools/cabana/messageswidget.cc +++ b/tools/cabana/messageswidget.cc @@ -68,7 +68,7 @@ MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) { }); QObject::connect(table_widget->selectionModel(), &QItemSelectionModel::currentChanged, [=](const QModelIndex ¤t, const QModelIndex &previous) { if (current.isValid()) { - emit msgSelectionChanged(table_widget->model()->data(current, Qt::UserRole).toString()); + emit msgSelectionChanged(current.data(Qt::UserRole).toString()); } }); @@ -78,11 +78,8 @@ MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) { void MessagesWidget::dbcSelectionChanged(const QString &dbc_file) { dbc()->open(dbc_file); - // update detailwidget - auto current = table_widget->selectionModel()->currentIndex(); - if (current.isValid()) { - emit msgSelectionChanged(table_widget->model()->data(current, Qt::UserRole).toString()); - } + // TODO: reset model? + table_widget->sortByColumn(0, Qt::AscendingOrder); } // MessageListModel @@ -90,9 +87,6 @@ void MessagesWidget::dbcSelectionChanged(const QString &dbc_file) { QVariant MessageListModel::headerData(int section, Qt::Orientation orientation, int role) const { if (orientation == Qt::Horizontal && role == Qt::DisplayRole) return (QString[]){"Name", "ID", "Count", "Bytes"}[section]; - else if (orientation == Qt::Vertical && role == Qt::DisplayRole) { - // return QString::number(section); - } return {}; } @@ -100,17 +94,15 @@ QVariant MessageListModel::data(const QModelIndex &index, int role) const { if (role == Qt::DisplayRole) { auto it = std::next(can->can_msgs.begin(), index.row()); if (it != can->can_msgs.end() && !it.value().empty()) { - const auto &d = it.value().front(); const QString &msg_id = it.key(); switch (index.column()) { case 0: { auto msg = dbc()->msg(msg_id); - QString name = msg ? msg->name.c_str() : "untitled"; - return name; + return msg ? msg->name.c_str() : "untitled"; } case 1: return msg_id; case 2: return can->counters[msg_id]; - case 3: return toHex(d.dat); + case 3: return toHex(it.value().front().dat); } } } else if (role == Qt::UserRole) { @@ -132,6 +124,6 @@ void MessageListModel::updateState() { } if (row_count > 0) { - emit dataChanged(index(0, 0), index(row_count - 1, 3)); + emit dataChanged(index(0, 0), index(row_count - 1, 3), {Qt::DisplayRole}); } } diff --git a/tools/cabana/signaledit.cc b/tools/cabana/signaledit.cc index 3f48450195..2da3e2eec2 100644 --- a/tools/cabana/signaledit.cc +++ b/tools/cabana/signaledit.cc @@ -3,7 +3,6 @@ #include #include #include -#include #include // SignalForm @@ -15,13 +14,10 @@ SignalForm::SignalForm(const Signal &sig, QWidget *parent) : start_bit(sig.start form_layout->addRow(tr("Name"), name); size = new QSpinBox(); + size->setMinimum(1); size->setValue(sig.size); form_layout->addRow(tr("Size"), size); - msb = new QSpinBox(); - msb->setValue(sig.msb); - form_layout->addRow(tr("Most significant bit"), msb); - endianness = new QComboBox(); endianness->addItems({"Little", "Big"}); endianness->setCurrentIndex(sig.is_little_endian ? 0 : 1); @@ -56,7 +52,8 @@ SignalForm::SignalForm(const Signal &sig, QWidget *parent) : start_bit(sig.start form_layout->addRow(tr("Value descriptions"), val_desc); } -std::optional SignalForm::getSignal() { +Signal SignalForm::getSignal() { + // TODO: Check if the size is valid, and no duplicate name Signal sig = {}; sig.start_bit = start_bit; sig.name = name->text().toStdString(); @@ -72,17 +69,17 @@ std::optional SignalForm::getSignal() { sig.lsb = bigEndianStartBitsIndex(bigEndianBitIndex(sig.start_bit) + sig.size - 1); sig.msb = sig.start_bit; } - return (sig.name.empty() || sig.size <= 0) ? std::nullopt : std::optional(sig); + return sig; } // SignalEdit -SignalEdit::SignalEdit(int index, const QString &id, const Signal &sig, const QString &color, QWidget *parent) - : id(id), name_(sig.name.c_str()), QWidget(parent) { +SignalEdit::SignalEdit(int index, const QString &msg_id, const Signal &sig, QWidget *parent) + : sig_name(sig.name.c_str()), QWidget(parent) { QVBoxLayout *main_layout = new QVBoxLayout(this); main_layout->setContentsMargins(0, 0, 0, 0); - // title + // title bar QHBoxLayout *title_layout = new QHBoxLayout(); icon = new QLabel(">"); icon->setFixedSize(15, 30); @@ -90,24 +87,25 @@ SignalEdit::SignalEdit(int index, const QString &id, const Signal &sig, const QS title_layout->addWidget(icon); title = new ElidedLabel(this); title->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::MinimumExpanding); - title->setText(QString("%1. %2").arg(index + 1).arg(sig.name.c_str())); - title->setStyleSheet(QString("font-weight:bold; color:%1").arg(color)); + title->setText(QString("%1. %2").arg(index + 1).arg(sig_name)); + title->setStyleSheet(QString("font-weight:bold; color:%1").arg(getColor(index))); title_layout->addWidget(title); - plot_btn = new QPushButton("📈"); + QPushButton *plot_btn = new QPushButton("📈"); plot_btn->setToolTip(tr("Show Plot")); plot_btn->setFixedSize(30, 30); - QObject::connect(plot_btn, &QPushButton::clicked, [=]() { emit showChart(id, name_); }); + QObject::connect(plot_btn, &QPushButton::clicked, this, &SignalEdit::showChart); title_layout->addWidget(plot_btn); main_layout->addLayout(title_layout); + // signal form form_container = new QWidget(this); QVBoxLayout *v_layout = new QVBoxLayout(form_container); form = new SignalForm(sig, this); v_layout->addWidget(form); QHBoxLayout *h = new QHBoxLayout(); - remove_btn = new QPushButton(tr("Remove Signal")); + QPushButton *remove_btn = new QPushButton(tr("Remove Signal")); h->addWidget(remove_btn); h->addStretch(); QPushButton *save_btn = new QPushButton(tr("Save")); @@ -117,13 +115,19 @@ SignalEdit::SignalEdit(int index, const QString &id, const Signal &sig, const QS form_container->setVisible(false); main_layout->addWidget(form_container); - QFrame* hline = new QFrame(); + // bottom line + QFrame *hline = new QFrame(); hline->setFrameShape(QFrame::HLine); hline->setFrameShadow(QFrame::Sunken); main_layout->addWidget(hline); QObject::connect(remove_btn, &QPushButton::clicked, this, &SignalEdit::remove); - QObject::connect(save_btn, &QPushButton::clicked, this, &SignalEdit::save); + QObject::connect(save_btn, &QPushButton::clicked, [=]() { + QString new_name = form->getSignal().name.c_str(); + title->setText(QString("%1. %2").arg(index + 1).arg(new_name)); + emit save(); + sig_name = new_name; + }); QObject::connect(title, &ElidedLabel::clicked, this, &SignalEdit::showFormClicked); } @@ -132,40 +136,24 @@ void SignalEdit::setFormVisible(bool visible) { icon->setText(visible ? "▼" : ">"); } -void SignalEdit::save() { - if (auto s = form->getSignal()) - dbc()->updateSignal(id, name_, *s); -} - -void SignalEdit::remove() { - QMessageBox msgbox; - msgbox.setText(tr("Remove signal")); - msgbox.setInformativeText(tr("Are you sure you want to remove signal '%1'").arg(name_)); - msgbox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel); - msgbox.setDefaultButton(QMessageBox::Cancel); - if (msgbox.exec()) { - dbc()->removeSignal(id, name_); - deleteLater(); - } -} - // AddSignalDialog -AddSignalDialog::AddSignalDialog(const QString &id, QWidget *parent) : QDialog(parent) { +AddSignalDialog::AddSignalDialog(const QString &id, int start_bit, int size, QWidget *parent) : QDialog(parent) { setWindowTitle(tr("Add signal to %1").arg(dbc()->msg(id)->name.c_str())); QVBoxLayout *main_layout = new QVBoxLayout(this); - Signal sig = {.name = "untitled"}; - auto form = new SignalForm(sig, this); + + Signal sig = { + .name = "untitled", + .start_bit = bigEndianBitIndex(start_bit), + .is_little_endian = false, + .size = size, + }; + form = new SignalForm(sig, this); main_layout->addWidget(form); auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); main_layout->addWidget(buttonBox); setFixedWidth(parent->width() * 0.9); connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); - connect(buttonBox, &QDialogButtonBox::accepted, [=]() { - if (auto signal = form->getSignal()) { - dbc()->addSignal(id, *signal); - } - QDialog::accept(); - }); + connect(buttonBox, &QDialogButtonBox::accepted, this, &QDialog::accept); } diff --git a/tools/cabana/signaledit.h b/tools/cabana/signaledit.h index 00c13948b7..f31408657f 100644 --- a/tools/cabana/signaledit.h +++ b/tools/cabana/signaledit.h @@ -1,7 +1,5 @@ #pragma once -#include - #include #include #include @@ -15,14 +13,12 @@ #include "tools/cabana/dbcmanager.h" class SignalForm : public QWidget { - Q_OBJECT - public: SignalForm(const Signal &sig, QWidget *parent); - std::optional getSignal(); + Signal getSignal(); QLineEdit *name, *unit, *comment, *val_desc; - QSpinBox *size, *msb, *lsb, *offset; + QSpinBox *size, *offset; QDoubleSpinBox *factor, *min_val, *max_val; QComboBox *sign, *endianness; int start_bit = 0; @@ -32,31 +28,26 @@ class SignalEdit : public QWidget { Q_OBJECT public: - SignalEdit(int index, const QString &id, const Signal &sig, const QString &color, QWidget *parent = nullptr); + SignalEdit(int index, const QString &msg_id, const Signal &sig, QWidget *parent = nullptr); void setFormVisible(bool show); inline bool isFormVisible() const { return form_container->isVisible(); } - void save(); + QString sig_name; + SignalForm *form; signals: - void showChart(const QString &msg_id, const QString &sig_name); + void showChart(); void showFormClicked(); - -protected: void remove(); + void save(); - QString id; - QString name_; - QPushButton *plot_btn; +protected: ElidedLabel *title; - SignalForm *form; QWidget *form_container; - QPushButton *remove_btn; QLabel *icon; }; class AddSignalDialog : public QDialog { - Q_OBJECT - public: - AddSignalDialog(const QString &id, QWidget *parent); + AddSignalDialog(const QString &id, int start_bit, int size, QWidget *parent); + SignalForm *form; }; From e3268d88c5226afaf5a300a775b8989bcff18b20 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 16 Oct 2022 23:24:34 +0800 Subject: [PATCH 068/101] cabana: use monospace font for hex string (#26102) specify monospace font for hex string --- tools/cabana/detailwidget.cc | 3 ++- tools/cabana/historylog.cc | 7 ++++++- tools/cabana/messageswidget.cc | 5 +++++ 3 files changed, 13 insertions(+), 2 deletions(-) diff --git a/tools/cabana/detailwidget.cc b/tools/cabana/detailwidget.cc index 021e1b73cf..a9899ec650 100644 --- a/tools/cabana/detailwidget.cc +++ b/tools/cabana/detailwidget.cc @@ -1,6 +1,7 @@ #include "tools/cabana/detailwidget.h" #include +#include #include #include #include @@ -179,7 +180,7 @@ void BinaryView::setMessage(const QString &message_id) { item->setFlags(item->flags() ^ Qt::ItemIsEditable); item->setTextAlignment(Qt::AlignCenter); if (j == 8) { - QFont font; + QFont font = QFontDatabase::systemFont(QFontDatabase::FixedFont); font.setBold(true); item->setFont(font); item->setFlags(item->flags() ^ Qt::ItemIsSelectable); diff --git a/tools/cabana/historylog.cc b/tools/cabana/historylog.cc index 5a77b5aa9e..cbb3b6e882 100644 --- a/tools/cabana/historylog.cc +++ b/tools/cabana/historylog.cc @@ -1,20 +1,25 @@ #include "tools/cabana/historylog.h" +#include #include #include QVariant HistoryLogModel::data(const QModelIndex &index, int role) const { + auto msg = dbc()->msg(msg_id); if (role == Qt::DisplayRole) { const auto &can_msgs = can->messages(msg_id); if (index.row() < can_msgs.size()) { const auto &can_data = can_msgs[index.row()]; - auto msg = dbc()->msg(msg_id); if (msg && index.column() < msg->sigs.size()) { return get_raw_value((uint8_t *)can_data.dat.begin(), can_data.dat.size(), msg->sigs[index.column()]); } else { return toHex(can_data.dat); } } + } else if (role == Qt::FontRole) { + if (index.column() == 0 && !(msg && msg->sigs.size() > 0)) { + return QFontDatabase::systemFont(QFontDatabase::FixedFont); + } } return {}; } diff --git a/tools/cabana/messageswidget.cc b/tools/cabana/messageswidget.cc index f10cbf44b4..3c9af67ea6 100644 --- a/tools/cabana/messageswidget.cc +++ b/tools/cabana/messageswidget.cc @@ -2,6 +2,7 @@ #include #include +#include #include #include #include @@ -107,6 +108,10 @@ QVariant MessageListModel::data(const QModelIndex &index, int role) const { } } else if (role == Qt::UserRole) { return std::next(can->can_msgs.begin(), index.row()).key(); + } else if (role == Qt::FontRole) { + if (index.column() == 3) { + return QFontDatabase::systemFont(QFontDatabase::FixedFont); + } } return {}; } From d4f9343a2c1f5345dec07a93b25594b588cd9963 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 17 Oct 2022 03:30:23 +0800 Subject: [PATCH 069/101] Cabana: load from high quality video by default (#26100) --- tools/cabana/cabana.cc | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/tools/cabana/cabana.cc b/tools/cabana/cabana.cc index 88b175663f..1096487973 100644 --- a/tools/cabana/cabana.cc +++ b/tools/cabana/cabana.cc @@ -14,6 +14,7 @@ int main(int argc, char *argv[]) { cmd_parser.addHelpOption(); cmd_parser.addPositionalArgument("route", "the drive to replay. find your drives at connect.comma.ai"); cmd_parser.addOption({"demo", "use a demo route instead of providing your own"}); + cmd_parser.addOption({"qcam", "load qcamera"}); cmd_parser.addOption({"data_dir", "local directory with routes", "data_dir"}); cmd_parser.process(app); const QStringList args = cmd_parser.positionalArguments(); @@ -23,7 +24,7 @@ int main(int argc, char *argv[]) { const QString route = args.empty() ? DEMO_ROUTE : args.first(); CANMessages p(&app); - if (!p.loadRoute(route, cmd_parser.value("data_dir"), true)) { + if (!p.loadRoute(route, cmd_parser.value("data_dir"), cmd_parser.isSet("qcam"))) { return 0; } MainWindow w; From d109dda720b502a94f914c1a29ffdea6d01fbc6f Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 17 Oct 2022 03:31:26 +0800 Subject: [PATCH 070/101] Cabana: click on video to play/pause (#26099) --- tools/cabana/videowidget.cc | 19 ++++++++++--------- tools/cabana/videowidget.h | 3 +++ 2 files changed, 13 insertions(+), 9 deletions(-) diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc index 9e2129afaf..b6fe8de3e2 100644 --- a/tools/cabana/videowidget.cc +++ b/tools/cabana/videowidget.cc @@ -5,7 +5,6 @@ #include #include #include -#include #include #include #include @@ -39,9 +38,9 @@ VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) { // btn controls QHBoxLayout *control_layout = new QHBoxLayout(); - QPushButton *play = new QPushButton("⏸"); - play->setStyleSheet("font-weight:bold"); - control_layout->addWidget(play); + play_btn = new QPushButton("⏸"); + play_btn->setStyleSheet("font-weight:bold"); + control_layout->addWidget(play_btn); QButtonGroup *group = new QButtonGroup(this); group->setExclusive(true); @@ -61,11 +60,13 @@ VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) { QObject::connect(can, &CANMessages::updated, this, &VideoWidget::updateState); QObject::connect(slider, &QSlider::sliderReleased, [this]() { can->seekTo(slider->value() / 1000.0); }); QObject::connect(slider, &QSlider::valueChanged, [=](int value) { time_label->setText(formatTime(value / 1000)); }); - QObject::connect(play, &QPushButton::clicked, [=]() { - bool is_paused = can->isPaused(); - play->setText(is_paused ? "⏸" : "▶"); - can->pause(!is_paused); - }); + QObject::connect(cam_widget, &CameraViewWidget::clicked, [this]() { pause(!can->isPaused()); }); + QObject::connect(play_btn, &QPushButton::clicked, [=]() { pause(!can->isPaused()); }); +} + +void VideoWidget::pause(bool pause) { + play_btn->setText(!pause ? "⏸" : "▶"); + can->pause(pause); } void VideoWidget::rangeChanged(double min, double max) { diff --git a/tools/cabana/videowidget.h b/tools/cabana/videowidget.h index e80e3b48f9..fd896f1e11 100644 --- a/tools/cabana/videowidget.h +++ b/tools/cabana/videowidget.h @@ -1,6 +1,7 @@ #pragma once #include +#include #include #include @@ -29,8 +30,10 @@ public: protected: void rangeChanged(double min, double max); void updateState(); + void pause(bool pause); CameraViewWidget *cam_widget; QLabel *end_time_label; + QPushButton *play_btn; Slider *slider; }; From 00494a44f4fb8f9e18ce82e22bf40fbe6bc1a805 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 16 Oct 2022 15:54:36 -0700 Subject: [PATCH 071/101] CI speedup (#26096) * CI speedup * use the new stuff * push * no regressions * try that * don't let this slip * fix modeld tests * fix linter * modernize prebuilt * cleanup * fix those * increase a bit --- .github/workflows/prebuilt.yaml | 8 +- .github/workflows/selfdrive_tests.yaml | 109 +++++++++--------- .github/workflows/setup/action.yaml | 8 +- .github/workflows/tools_tests.yaml | 45 +++++--- .pre-commit-config.yaml | 1 + release/build_devel.sh | 4 +- selfdrive/modeld/tests/__init__.py | 0 .../modeld/{test => tests}/dmon_lag/repro.cc | 0 .../{test => tests}/snpe_benchmark/.gitignore | 0 .../snpe_benchmark/benchmark.cc | 1 + .../snpe_benchmark/benchmark.sh | 0 .../modeld/{test => tests}/test_modeld.py | 0 .../modeld/{test => tests}/tf_test/build.sh | 0 .../modeld/{test => tests}/tf_test/main.cc | 0 .../{test => tests}/tf_test/pb_loader.py | 0 .../{test => tests}/timing/benchmark.py | 0 16 files changed, 95 insertions(+), 81 deletions(-) create mode 100644 selfdrive/modeld/tests/__init__.py rename selfdrive/modeld/{test => tests}/dmon_lag/repro.cc (100%) rename selfdrive/modeld/{test => tests}/snpe_benchmark/.gitignore (100%) rename selfdrive/modeld/{test => tests}/snpe_benchmark/benchmark.cc (99%) rename selfdrive/modeld/{test => tests}/snpe_benchmark/benchmark.sh (100%) rename selfdrive/modeld/{test => tests}/test_modeld.py (100%) rename selfdrive/modeld/{test => tests}/tf_test/build.sh (100%) rename selfdrive/modeld/{test => tests}/tf_test/main.cc (100%) rename selfdrive/modeld/{test => tests}/tf_test/pb_loader.py (100%) rename selfdrive/modeld/{test => tests}/timing/benchmark.py (100%) diff --git a/.github/workflows/prebuilt.yaml b/.github/workflows/prebuilt.yaml index b659d4ceee..c8b4c51e38 100644 --- a/.github/workflows/prebuilt.yaml +++ b/.github/workflows/prebuilt.yaml @@ -2,7 +2,6 @@ name: prebuilt on: schedule: - cron: '0 * * * *' - workflow_dispatch: env: @@ -11,9 +10,7 @@ env: DOCKER_LOGIN: docker login ghcr.io -u ${{ github.actor }} -p ${{ secrets.GITHUB_TOKEN }} BUILD: | - docker pull $(grep -iohP '(?<=^from)\s+\S+' Dockerfile.openpilot_base) || true - 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 . + DOCKER_BUILDKIT=1 docker build --pull --build-arg BUILDKIT_INLINE_CACHE=1 --cache-from $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $BASE_IMAGE:latest -f Dockerfile.openpilot_base . jobs: build_prebuilt: @@ -37,8 +34,7 @@ jobs: - name: Build Docker image run: | eval "$BUILD" - docker pull $DOCKER_REGISTRY/$IMAGE_NAME:latest || true - docker build --cache-from $DOCKER_REGISTRY/$IMAGE_NAME:latest -t $DOCKER_REGISTRY/$IMAGE_NAME:latest -f Dockerfile.openpilot . + DOCKER_BUILDKIT=1 docker build --pull --build-arg BUILDKIT_INLINE_CACHE=1 --cache-from $DOCKER_REGISTRY/$IMAGE_NAME:latest -t $DOCKER_REGISTRY/$IMAGE_NAME:latest -f Dockerfile.openpilot . - name: Push to container registry run: | $DOCKER_LOGIN diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index cd34c6d27c..d84779103b 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -18,15 +18,12 @@ env: DOCKER_LOGIN: docker login ghcr.io -u ${{ github.actor }} -p ${{ secrets.GITHUB_TOKEN }} BUILD: | - docker pull $(grep -iohP '(?<=^from)\s+\S+' Dockerfile.openpilot_base) || true - 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 . + DOCKER_BUILDKIT=1 docker build --pull --build-arg BUILDKIT_INLINE_CACHE=1 --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 FILEREADER_CACHE=1 -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 . + DOCKER_BUILDKIT=1 docker build --pull --build-arg BUILDKIT_INLINE_CACHE=1 --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 -v /tmp/openpilot_cache:/tmp/openpilot_cache $CL_BASE_IMAGE /bin/sh -c UNIT_TEST: coverage run --append -m unittest discover @@ -41,13 +38,10 @@ jobs: steps: - uses: actions/checkout@v3 with: - fetch-depth: 0 submodules: true - name: Build devel run: TARGET_DIR=$STRIPPED_DIR release/build_devel.sh - uses: ./.github/workflows/setup - with: - save-cache: true - name: Check submodules if: github.ref == 'refs/heads/master' && github.repository == 'commaai/openpilot' run: release/check-submodules.sh @@ -72,18 +66,20 @@ jobs: build_all: name: build all runs-on: ubuntu-20.04 - timeout-minutes: 50 + timeout-minutes: 30 steps: - uses: actions/checkout@v3 with: submodules: true - uses: ./.github/workflows/setup + with: + save-cache: true - name: Build openpilot with all flags run: ${{ env.RUN }} "scons -j$(nproc) --extras && release/check-dirty.sh" - name: Cleanup scons cache run: | ${{ env.RUN }} "rm -rf /tmp/scons_cache/* && \ - scons -j$(nproc) --extras --cache-populate" + scons -j$(nproc) --cache-populate" #build_mac: # name: build macos @@ -145,7 +141,7 @@ jobs: docker_push: name: docker push runs-on: ubuntu-20.04 - timeout-minutes: 50 + timeout-minutes: 22 if: github.ref == 'refs/heads/master' && github.event_name != 'pull_request' && github.repository == 'commaai/openpilot' needs: static_analysis # hack to ensure slow tests run first since this and static_analysis are fast steps: @@ -154,12 +150,14 @@ jobs: submodules: true - name: Build Docker image run: eval "$BUILD" + timeout-minutes: 13 - name: Push to container registry run: | $DOCKER_LOGIN docker push $DOCKER_REGISTRY/$BASE_IMAGE:latest - name: Build CL Docker image run: eval "$BUILD_CL" + timeout-minutes: 4 - name: Push to container registry run: | $DOCKER_LOGIN @@ -168,7 +166,7 @@ jobs: static_analysis: name: static analysis runs-on: ubuntu-20.04 - timeout-minutes: 50 + timeout-minutes: 20 steps: - uses: actions/checkout@v3 with: @@ -176,21 +174,23 @@ jobs: - name: Build Docker image run: eval "$BUILD" - name: pre-commit + timeout-minutes: 5 run: ${{ env.RUN }} "pre-commit run --all" valgrind: name: valgrind runs-on: ubuntu-20.04 - timeout-minutes: 50 + timeout-minutes: 20 steps: - uses: actions/checkout@v3 with: submodules: true - uses: ./.github/workflows/setup + - name: Build openpilot + run: ${{ env.RUN }} "scons -j$(nproc)" - name: Run valgrind run: | - ${{ env.RUN }} "scons -j$(nproc) && \ - python selfdrive/test/test_valgrind_replay.py" + ${{ env.RUN }} "python selfdrive/test/test_valgrind_replay.py" - name: Print logs if: always() run: cat selfdrive/test/valgrind_logs.txt @@ -198,16 +198,18 @@ jobs: unit_tests: name: unit tests runs-on: ubuntu-20.04 - timeout-minutes: 50 + timeout-minutes: 30 steps: - uses: actions/checkout@v3 with: submodules: true - uses: ./.github/workflows/setup + - name: Build openpilot + run: ${{ env.RUN }} "scons -j$(nproc)" - name: Run unit tests + timeout-minutes: 15 run: | ${{ env.RUN }} "export SKIP_LONG_TESTS=1 && \ - scons -j$(nproc) && \ $UNIT_TEST common && \ $UNIT_TEST opendbc/can && \ $UNIT_TEST selfdrive/boardd && \ @@ -220,7 +222,6 @@ jobs: $UNIT_TEST selfdrive/athena && \ $UNIT_TEST selfdrive/thermald && \ $UNIT_TEST system/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 && \ @@ -239,7 +240,7 @@ jobs: process_replay: name: process replay runs-on: ubuntu-20.04 - timeout-minutes: 50 + timeout-minutes: 25 steps: - uses: actions/checkout@v3 with: @@ -251,10 +252,12 @@ jobs: with: path: /tmp/comma_download_cache key: proc-replay-${{ hashFiles('.github/workflows/selfdrive_tests.yaml', 'selfdrive/test/process_replay/ref_commit') }} + - name: Build openpilot + run: | + ${{ env.RUN }} "scons -j$(nproc)" - name: Run replay run: | - ${{ env.RUN }} "scons -j$(nproc) && \ - CI=1 coverage run selfdrive/test/process_replay/test_processes.py -j$(nproc) && \ + ${{ env.RUN }} "CI=1 coverage run selfdrive/test/process_replay/test_processes.py -j$(nproc) && \ coverage xml" - name: Print diff if: always() @@ -268,15 +271,14 @@ jobs: - name: Upload reference logs 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" + ${{ env.RUN }} "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 + test_modeld: + name: model tests runs-on: ubuntu-20.04 - timeout-minutes: 50 + timeout-minutes: 20 steps: - uses: actions/checkout@v3 with: @@ -285,29 +287,41 @@ jobs: - name: Build Docker image # Sim docker is needed to get the OpenCL drivers run: eval "$BUILD_CL" - - name: Run replay + - name: Build openpilot + run: | + ${{ env.RUN }} "scons -j$(nproc)" + - name: Run model replay with ONNX + timeout-minutes: 2 + run: | + ${{ env.RUN_CL }} "ONNXCPU=1 CI=1 coverage run selfdrive/test/process_replay/model_replay.py && \ + coverage xml" + - name: Run unit tests + timeout-minutes: 5 run: | - ${{ env.RUN_CL }} "scons -j$(nproc) && \ - ONNXCPU=1 CI=1 coverage run \ - selfdrive/test/process_replay/model_replay.py -j$(nproc) && \ + ${{ env.RUN_CL }} "$UNIT_TEST selfdrive/modeld && \ coverage xml" + - name: "Upload coverage to Codecov" + uses: codecov/codecov-action@v2 test_longitudinal: name: longitudinal runs-on: ubuntu-20.04 - timeout-minutes: 50 + timeout-minutes: 20 steps: - uses: actions/checkout@v3 with: submodules: true - uses: ./.github/workflows/setup + - name: Build openpilot + run: | + ${{ env.RUN }} "scons -j$(nproc)" - name: Test longitudinal run: | ${{ env.RUN }} "mkdir -p selfdrive/test/out && \ - scons -j$(nproc) && \ cd selfdrive/test/longitudinal_maneuvers && \ coverage run ./test_longitudinal.py && \ coverage xml" + timeout-minutes: 2 - name: "Upload coverage to Codecov" uses: codecov/codecov-action@v2 - uses: actions/upload-artifact@v2 @@ -320,7 +334,7 @@ jobs: test_cars: name: cars runs-on: ubuntu-20.04 - timeout-minutes: 50 + timeout-minutes: 20 strategy: fail-fast: false matrix: @@ -336,10 +350,12 @@ jobs: with: path: /tmp/comma_download_cache key: car_models-${{ hashFiles('selfdrive/car/tests/test_models.py', 'selfdrive/car/tests/routes.py') }}-${{ matrix.job }} + - name: Build openpilot + run: ${{ env.RUN }} "scons -j$(nproc)" - name: Test car models + timeout-minutes: 12 run: | - ${{ env.RUN }} "scons -j$(nproc) && \ - coverage run -m pytest selfdrive/car/tests/test_models.py && \ + ${{ env.RUN }} "coverage run -m pytest selfdrive/car/tests/test_models.py && \ coverage xml && \ chmod -R 777 /tmp/comma_download_cache" env: @@ -348,29 +364,10 @@ jobs: - name: "Upload coverage to Codecov" uses: codecov/codecov-action@v2 - docs: - name: build docs - runs-on: ubuntu-20.04 - timeout-minutes: 50 - steps: - - uses: actions/checkout@v3 - with: - submodules: true - - name: Build docker container - run: | - docker pull $DOCKER_REGISTRY/$BASE_IMAGE:latest || true - docker pull $DOCKER_REGISTRY/openpilot-docs:latest || true - DOCKER_BUILDKIT=1 docker build --cache-from $DOCKER_REGISTRY/openpilot-docs:latest -t $DOCKER_REGISTRY/openpilot-docs:latest -f docs/docker/Dockerfile . - - name: Push docker container - if: github.ref == 'refs/heads/master' && github.event_name != 'pull_request' && github.repository == 'commaai/openpilot' - run: | - $DOCKER_LOGIN - docker push $DOCKER_REGISTRY/openpilot-docs:latest - car_docs_diff: - name: comment on PR with car docs diff + name: PR comments runs-on: ubuntu-20.04 - timeout-minutes: 50 + timeout-minutes: 20 if: github.event_name == 'pull_request' steps: - uses: actions/checkout@v3 diff --git a/.github/workflows/setup/action.yaml b/.github/workflows/setup/action.yaml index 79c4c890ab..186a9d9095 100644 --- a/.github/workflows/setup/action.yaml +++ b/.github/workflows/setup/action.yaml @@ -15,9 +15,9 @@ runs: # build cache - id: date shell: bash - run: echo "::set-output name=date::$(git log -1 --pretty='format:%cd' --date=format:'%Y-%m-%d')" + run: echo "CACHE_COMMIT_DATE=$(git log -1 --pretty='format:%cd' --date=format:'%Y-%m-%d-%H:%M')" >> $GITHUB_ENV - shell: bash - run: echo "${{ steps.date.outputs.date }}" + run: echo "$CACHE_COMMIT_DATE" - shell: bash run: echo "CACHE_SKIP_SAVE=true" >> $GITHUB_ENV if: github.ref != 'refs/heads/master' || inputs.save-cache == 'false' @@ -27,9 +27,9 @@ runs: uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b with: path: /tmp/scons_cache - key: scons-${{ steps.date.outputs.date }}-${{ github.sha }} + key: scons-${{ env.CACHE_COMMIT_DATE }}-${{ github.sha }} restore-keys: | - scons-${{ steps.date.outputs.date }}- + scons-${{ env.CACHE_COMMIT_DATE }}- scons- # build our docker image diff --git a/.github/workflows/tools_tests.yaml b/.github/workflows/tools_tests.yaml index 9dc5c05837..549a2f4195 100644 --- a/.github/workflows/tools_tests.yaml +++ b/.github/workflows/tools_tests.yaml @@ -2,6 +2,8 @@ name: tools on: push: + branches-ignore: + - 'testing-closet*' pull_request: concurrency: @@ -15,21 +17,20 @@ env: DOCKER_LOGIN: docker login ghcr.io -u ${{ github.actor }} -p ${{ secrets.GITHUB_TOKEN }} BUILD: | - docker pull $(grep -iohP '(?<=^from)\s+\S+' Dockerfile.openpilot_base) || true - 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 . + DOCKER_BUILDKIT=1 docker build --pull --build-arg BUILDKIT_INLINE_CACHE=1 --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 $GITHUB_WORKSPACE:/tmp/openpilot -w /tmp/openpilot -e FILEREADER_CACHE=1 -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 $(grep -iohP '(?<=^from)\s+\S+' Dockerfile.openpilot_base_cl) || true - docker pull $DOCKER_REGISTRY/$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: docker run --shm-size 1G -v $PWD:/tmp/openpilot -e PYTHONPATH=/tmp/openpilot -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e \ - GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/comma_download_cache:/tmp/comma_download_cache $BASE_IMAGE /bin/sh -c + DOCKER_BUILDKIT=1 docker build --pull --build-arg BUILDKIT_INLINE_CACHE=1 --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 $GITHUB_WORKSPACE:/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 + jobs: plotjuggler: name: plotjuggler runs-on: ubuntu-20.04 - timeout-minutes: 30 + timeout-minutes: 20 steps: - uses: actions/checkout@v3 with: @@ -37,6 +38,7 @@ jobs: - name: Build Docker image run: eval "$BUILD" - name: Unit test + timeout-minutes: 2 run: | ${{ env.RUN }} "scons -j$(nproc) --directory=/tmp/openpilot/cereal && \ apt-get update && \ @@ -47,7 +49,7 @@ jobs: simulator: name: simulator runs-on: ubuntu-20.04 - timeout-minutes: 50 + timeout-minutes: 30 env: IMAGE_NAME: openpilot-sim if: github.repository == 'commaai/openpilot' @@ -61,12 +63,29 @@ jobs: run: eval "$BUILD" - name: Build base cl image run: eval "$BUILD_CL" - - name: Pull latest simulator image - run: docker pull $DOCKER_REGISTRY/$IMAGE_NAME:latest || true - name: Build simulator image - run: docker build --cache-from $DOCKER_REGISTRY/$IMAGE_NAME:latest -t $DOCKER_REGISTRY/$IMAGE_NAME:latest -f tools/sim/Dockerfile.sim . + run: DOCKER_BUILDKIT=1 docker build --pull --build-arg BUILDKIT_INLINE_CACHE=1 --cache-from $DOCKER_REGISTRY/$IMAGE_NAME:latest -t $DOCKER_REGISTRY/$IMAGE_NAME:latest -f tools/sim/Dockerfile.sim . - name: Push to container registry if: github.ref == 'refs/heads/master' && github.repository == 'commaai/openpilot' run: | $DOCKER_LOGIN docker push $DOCKER_REGISTRY/$IMAGE_NAME:latest + + docs: + name: build docs + runs-on: ubuntu-20.04 + timeout-minutes: 25 + steps: + - uses: actions/checkout@v3 + with: + submodules: true + - name: Build docker container + run: | + DOCKER_BUILDKIT=1 docker build --pull --build-arg BUILDKIT_INLINE_CACHE=1 --cache-from $DOCKER_REGISTRY/openpilot-docs:latest -t $DOCKER_REGISTRY/openpilot-docs:latest -f docs/docker/Dockerfile . + - name: Push docker container + if: github.ref == 'refs/heads/master' && github.event_name != 'pull_request' && github.repository == 'commaai/openpilot' + run: | + $DOCKER_LOGIN + docker push $DOCKER_REGISTRY/openpilot-docs:latest + + diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 25b8490f92..85c24b911b 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -53,6 +53,7 @@ repos: types: [python] exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(laika_repo/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)' args: + - -j0 - -rn - -sn - --rcfile=.pylintrc diff --git a/release/build_devel.sh b/release/build_devel.sh index 7108334808..668ac0de19 100755 --- a/release/build_devel.sh +++ b/release/build_devel.sh @@ -22,8 +22,8 @@ pre-commit uninstall || true echo "[-] bringing master-ci and devel in sync T=$SECONDS" cd $TARGET_DIR -git fetch origin master-ci -git fetch origin devel +git fetch --depth 1 origin master-ci +git fetch --depth 1 origin devel git checkout -f --track origin/master-ci git reset --hard master-ci diff --git a/selfdrive/modeld/tests/__init__.py b/selfdrive/modeld/tests/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/modeld/test/dmon_lag/repro.cc b/selfdrive/modeld/tests/dmon_lag/repro.cc similarity index 100% rename from selfdrive/modeld/test/dmon_lag/repro.cc rename to selfdrive/modeld/tests/dmon_lag/repro.cc diff --git a/selfdrive/modeld/test/snpe_benchmark/.gitignore b/selfdrive/modeld/tests/snpe_benchmark/.gitignore similarity index 100% rename from selfdrive/modeld/test/snpe_benchmark/.gitignore rename to selfdrive/modeld/tests/snpe_benchmark/.gitignore diff --git a/selfdrive/modeld/test/snpe_benchmark/benchmark.cc b/selfdrive/modeld/tests/snpe_benchmark/benchmark.cc similarity index 99% rename from selfdrive/modeld/test/snpe_benchmark/benchmark.cc rename to selfdrive/modeld/tests/snpe_benchmark/benchmark.cc index 1e2072eea1..021e065d81 100644 --- a/selfdrive/modeld/test/snpe_benchmark/benchmark.cc +++ b/selfdrive/modeld/tests/snpe_benchmark/benchmark.cc @@ -102,6 +102,7 @@ void get_testframe(int index, std::unique_ptr &input) { fread(frame_buffer, length, 1, pFile); // std::cout << *(frame_buffer+length/4-1) << std::endl; std::copy(frame_buffer, frame_buffer+(length/4), input->begin()); + fclose(pFile); } void SaveITensor(const std::string& path, const zdl::DlSystem::ITensor* tensor) diff --git a/selfdrive/modeld/test/snpe_benchmark/benchmark.sh b/selfdrive/modeld/tests/snpe_benchmark/benchmark.sh similarity index 100% rename from selfdrive/modeld/test/snpe_benchmark/benchmark.sh rename to selfdrive/modeld/tests/snpe_benchmark/benchmark.sh diff --git a/selfdrive/modeld/test/test_modeld.py b/selfdrive/modeld/tests/test_modeld.py similarity index 100% rename from selfdrive/modeld/test/test_modeld.py rename to selfdrive/modeld/tests/test_modeld.py diff --git a/selfdrive/modeld/test/tf_test/build.sh b/selfdrive/modeld/tests/tf_test/build.sh similarity index 100% rename from selfdrive/modeld/test/tf_test/build.sh rename to selfdrive/modeld/tests/tf_test/build.sh diff --git a/selfdrive/modeld/test/tf_test/main.cc b/selfdrive/modeld/tests/tf_test/main.cc similarity index 100% rename from selfdrive/modeld/test/tf_test/main.cc rename to selfdrive/modeld/tests/tf_test/main.cc diff --git a/selfdrive/modeld/test/tf_test/pb_loader.py b/selfdrive/modeld/tests/tf_test/pb_loader.py similarity index 100% rename from selfdrive/modeld/test/tf_test/pb_loader.py rename to selfdrive/modeld/tests/tf_test/pb_loader.py diff --git a/selfdrive/modeld/test/timing/benchmark.py b/selfdrive/modeld/tests/timing/benchmark.py similarity index 100% rename from selfdrive/modeld/test/timing/benchmark.py rename to selfdrive/modeld/tests/timing/benchmark.py From f8091837c92ed096ef3b886d1b09fe758d6ae9f2 Mon Sep 17 00:00:00 2001 From: Lee Jong Mun <43285072+crwusiz@users.noreply.github.com> Date: Tue, 18 Oct 2022 02:15:03 +0900 Subject: [PATCH 072/101] kor translation update (#26111) --- selfdrive/ui/translations/main_ko.ts | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 86cd8f990a..f84797eb60 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -60,11 +60,11 @@ Cellular Metered - + 데이터 요금제 Prevent large data uploads when on a metered connection - + 데이터 요금제 연결 시 대용량 데이터 업로드 방지 From 93346c31d3728d27eaff56a3068690a47eac86ef Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 18 Oct 2022 01:20:27 +0800 Subject: [PATCH 073/101] Cabana: add chart_height setting (#26066) add chart_height setting --- tools/cabana/canmessages.cc | 5 ++++- tools/cabana/canmessages.h | 1 + tools/cabana/chartswidget.cc | 11 ++++++++++- tools/cabana/chartswidget.h | 1 + tools/cabana/mainwin.cc | 7 +++++++ tools/cabana/mainwin.h | 1 + 6 files changed, 24 insertions(+), 2 deletions(-) diff --git a/tools/cabana/canmessages.cc b/tools/cabana/canmessages.cc index b717424ece..3cf08eaaa0 100644 --- a/tools/cabana/canmessages.cc +++ b/tools/cabana/canmessages.cc @@ -141,11 +141,14 @@ void Settings::save() { s.setValue("fps", fps); s.setValue("log_size", can_msg_log_size); s.setValue("cached_segment", cached_segment_limit); + s.setValue("chart_height", chart_height); + emit changed(); } void Settings::load() { QSettings s("settings", QSettings::IniFormat); fps = s.value("fps", 10).toInt(); can_msg_log_size = s.value("log_size", 100).toInt(); - cached_segment_limit = s.value("cached_segment", 3.).toInt(); + cached_segment_limit = s.value("cached_segment", 3).toInt(); + chart_height = s.value("chart_height", 200).toInt(); } diff --git a/tools/cabana/canmessages.h b/tools/cabana/canmessages.h index 3d33f801a7..7f6955369b 100644 --- a/tools/cabana/canmessages.h +++ b/tools/cabana/canmessages.h @@ -19,6 +19,7 @@ public: int fps = 10; int can_msg_log_size = 100; int cached_segment_limit = 3; + int chart_height = 200; signals: void changed(); diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index d0f5356fac..e69729c03a 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -76,6 +76,11 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) { docking = !docking; updateTitleBar(); }); + QObject::connect(&settings, &Settings::changed, [this]() { + for (auto chart : charts) { + chart->setHeight(settings.chart_height); + } + }); } void ChartsWidget::updateTitleBar() { @@ -152,7 +157,7 @@ ChartWidget::ChartWidget(const QString &id, const Signal *sig, QWidget *parent) main_layout->addWidget(header); chart_view = new ChartView(id, sig, this); - chart_view->setFixedHeight(300); + chart_view->setFixedHeight(settings.chart_height); main_layout->addWidget(chart_view); main_layout->addStretch(); @@ -205,6 +210,10 @@ ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent) updateSeries(); } +void ChartWidget::setHeight(int height) { + chart_view->setFixedHeight(height); +} + void ChartView::updateState() { auto axis_x = dynamic_cast(chart()->axisX()); int x = chart()->plotArea().left() + chart()->plotArea().width() * (can->currentSec() - axis_x->min()) / (axis_x->max() - axis_x->min()); diff --git a/tools/cabana/chartswidget.h b/tools/cabana/chartswidget.h index a3c470e960..3e43409dc4 100644 --- a/tools/cabana/chartswidget.h +++ b/tools/cabana/chartswidget.h @@ -46,6 +46,7 @@ Q_OBJECT public: ChartWidget(const QString &id, const Signal *sig, QWidget *parent); void updateTitle(); + void setHeight(int height); signals: void remove(); diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc index c9d9c85141..999a4816b0 100644 --- a/tools/cabana/mainwin.cc +++ b/tools/cabana/mainwin.cc @@ -96,6 +96,12 @@ SettingsDlg::SettingsDlg(QWidget *parent) : QDialog(parent) { cached_segment->setValue(settings.cached_segment_limit); form_layout->addRow(tr("Cached segments limit"), cached_segment); + chart_height = new QSpinBox(this); + chart_height->setRange(100, 500); + chart_height->setSingleStep(10); + chart_height->setValue(settings.chart_height); + form_layout->addRow(tr("Chart height"), chart_height); + main_layout->addLayout(form_layout); auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); @@ -110,6 +116,7 @@ void SettingsDlg::save() { settings.fps = fps->value(); settings.can_msg_log_size = log_size->value(); settings.cached_segment_limit = cached_segment->value(); + settings.chart_height = chart_height->value(); settings.save(); accept(); } diff --git a/tools/cabana/mainwin.h b/tools/cabana/mainwin.h index 14c4b1dfa9..594e608b59 100644 --- a/tools/cabana/mainwin.h +++ b/tools/cabana/mainwin.h @@ -33,4 +33,5 @@ public: QSpinBox *fps; QSpinBox *log_size ; QSpinBox *cached_segment; + QSpinBox *chart_height; }; From 3a8ddc191fd9a7537254399e3b9e49217de9bf16 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 18 Oct 2022 01:32:31 +0800 Subject: [PATCH 074/101] Move Qt moc files to scons cache directory (#26109) --- SConstruct | 1 + 1 file changed, 1 insertion(+) diff --git a/SConstruct b/SConstruct index 23ab37dc1e..74680c0598 100644 --- a/SConstruct +++ b/SConstruct @@ -327,6 +327,7 @@ qt_flags = [ qt_env['CXXFLAGS'] += qt_flags qt_env['LIBPATH'] += ['#selfdrive/ui'] qt_env['LIBS'] = qt_libs +qt_env['QT_MOCHPREFIX'] = cache_dir + '/moc_files/moc_' if GetOption("clazy"): checks = [ From 6d07268ee5b385010961eab206b0b42a0ae6b5f8 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 18 Oct 2022 01:39:07 +0800 Subject: [PATCH 075/101] tools/replay: reduce test running time (#26110) --- tools/replay/tests/test_replay.cc | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/tools/replay/tests/test_replay.cc b/tools/replay/tests/test_replay.cc index 5b61b6b6f2..3fd410bb6e 100644 --- a/tools/replay/tests/test_replay.cc +++ b/tools/replay/tests/test_replay.cc @@ -207,8 +207,7 @@ void TestReplay::test_seek() { } TEST_CASE("Replay") { - auto flag = GENERATE(REPLAY_FLAG_NO_FILE_CACHE, REPLAY_FLAG_NONE); - TestReplay replay(DEMO_ROUTE, flag); + TestReplay replay(DEMO_ROUTE, (uint8_t)REPLAY_FLAG_NO_VIPC); REQUIRE(replay.load()); replay.test_seek(); } From 1dffbb629a6b629b3079bcea195f64f389fc5d1d Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 17 Oct 2022 10:47:54 -0700 Subject: [PATCH 076/101] GM camera ACC: revert FCW logging (#26114) Revert FCW logging --- selfdrive/car/gm/carstate.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index 21eb440d7f..b67b97093a 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -96,9 +96,7 @@ class CarState(CarStateBase): ret.cruiseState.standstill = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.STANDSTILL if self.CP.networkLocation == NetworkLocation.fwdCamera: ret.cruiseState.speed = cam_cp.vl["ASCMActiveCruiseControlStatus"]["ACCSpeedSetpoint"] * CV.KPH_TO_MS - ret.stockAeb = cam_cp.vl["AEBCmd"]["AEBCmdActive"] != 0 - ret.stockFcw = cam_cp.vl["ASCMActiveCruiseControlStatus"]["FCWAlert"] != 0 return ret @@ -110,7 +108,6 @@ class CarState(CarStateBase): signals += [ ("AEBCmdActive", "AEBCmd"), ("RollingCounter", "ASCMLKASteeringCmd"), - ("FCWAlert", "ASCMActiveCruiseControlStatus"), ("ACCSpeedSetpoint", "ASCMActiveCruiseControlStatus"), ] checks += [ From 9e2a1121ea1103efaceaf52cca83370da73ba988 Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Mon, 17 Oct 2022 12:55:40 -0700 Subject: [PATCH 077/101] athenad: small tests cleanup (#26037) * test helpers * create file helper * clearer * type * fix default create path * static methods --- selfdrive/athena/tests/test_athenad.py | 68 ++++++++++++++------------ 1 file changed, 36 insertions(+), 32 deletions(-) diff --git a/selfdrive/athena/tests/test_athenad.py b/selfdrive/athena/tests/test_athenad.py index 7f511eecf6..5e86a2e821 100755 --- a/selfdrive/athena/tests/test_athenad.py +++ b/selfdrive/athena/tests/test_athenad.py @@ -9,6 +9,7 @@ import threading import queue import unittest from datetime import datetime, timedelta +from typing import Optional from multiprocessing import Process from pathlib import Path @@ -46,12 +47,26 @@ class TestAthenadMethods(unittest.TestCase): else: os.unlink(p) - def wait_for_upload(self): + + # *** test helpers *** + + @staticmethod + def _wait_for_upload(): now = time.time() while time.time() - now < 5: if athenad.upload_queue.qsize() == 0: break + @staticmethod + def _create_file(file: str, parent: Optional[str] = None) -> str: + fn = os.path.join(athenad.ROOT if parent is None else parent, file) + os.makedirs(os.path.dirname(fn), exist_ok=True) + Path(fn).touch() + return fn + + + # *** test cases *** + def test_echo(self): assert dispatcher["echo"]("bob") == "bob" @@ -85,9 +100,7 @@ class TestAthenadMethods(unittest.TestCase): filenames = ['qlog', 'qcamera.ts', 'rlog', 'fcamera.hevc', 'ecamera.hevc', 'dcamera.hevc'] files = [f'{route}--{s}/{f}' for s in segments for f in filenames] for file in files: - fn = os.path.join(athenad.ROOT, file) - os.makedirs(os.path.dirname(fn), exist_ok=True) - Path(fn).touch() + self._create_file(file) resp = dispatcher["listDataDirectory"]() self.assertTrue(resp, 'list empty!') @@ -121,16 +134,14 @@ class TestAthenadMethods(unittest.TestCase): self.assertCountEqual(resp, expected) def test_strip_bz2_extension(self): - fn = os.path.join(athenad.ROOT, 'qlog.bz2') - Path(fn).touch() + fn = self._create_file('qlog.bz2') 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') - Path(fn).touch() + fn = self._create_file('qlog.bz2') item = athenad.UploadItem(path=fn, url="http://localhost:1238", headers={}, created_at=int(time.time()*1000), id='') with self.assertRaises(requests.exceptions.ConnectionError): @@ -142,8 +153,7 @@ class TestAthenadMethods(unittest.TestCase): @with_http_server def test_uploadFileToUrl(self, host): - fn = os.path.join(athenad.ROOT, 'qlog.bz2') - Path(fn).touch() + fn = self._create_file('qlog.bz2') resp = dispatcher["uploadFileToUrl"]("qlog.bz2", f"{host}/qlog.bz2", {}) self.assertEqual(resp['enqueued'], 1) @@ -154,8 +164,7 @@ class TestAthenadMethods(unittest.TestCase): @with_http_server def test_uploadFileToUrl_duplicate(self, host): - fn = os.path.join(athenad.ROOT, 'qlog.bz2') - Path(fn).touch() + self._create_file('qlog.bz2') url1 = f"{host}/qlog.bz2?sig=sig1" dispatcher["uploadFileToUrl"]("qlog.bz2", url1, {}) @@ -172,8 +181,7 @@ class TestAthenadMethods(unittest.TestCase): @with_http_server def test_upload_handler(self, host): - fn = os.path.join(athenad.ROOT, 'qlog.bz2') - Path(fn).touch() + fn = self._create_file('qlog.bz2') item = athenad.UploadItem(path=fn, url=f"{host}/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) end_event = threading.Event() @@ -182,7 +190,7 @@ class TestAthenadMethods(unittest.TestCase): athenad.upload_queue.put_nowait(item) try: - self.wait_for_upload() + self._wait_for_upload() time.sleep(0.1) # TODO: verify that upload actually succeeded @@ -195,8 +203,7 @@ class TestAthenadMethods(unittest.TestCase): def test_upload_handler_retry(self, host, mock_put): for status, retry in ((500, True), (412, False)): mock_put.return_value.status_code = status - fn = os.path.join(athenad.ROOT, 'qlog.bz2') - Path(fn).touch() + fn = self._create_file('qlog.bz2') item = athenad.UploadItem(path=fn, url=f"{host}/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) end_event = threading.Event() @@ -205,7 +212,7 @@ class TestAthenadMethods(unittest.TestCase): athenad.upload_queue.put_nowait(item) try: - self.wait_for_upload() + self._wait_for_upload() time.sleep(0.1) self.assertEqual(athenad.upload_queue.qsize(), 1 if retry else 0) @@ -217,8 +224,7 @@ class TestAthenadMethods(unittest.TestCase): def test_upload_handler_timeout(self): """When an upload times out or fails to connect it should be placed back in the queue""" - fn = os.path.join(athenad.ROOT, 'qlog.bz2') - Path(fn).touch() + fn = self._create_file('qlog.bz2') item = athenad.UploadItem(path=fn, url="http://localhost:44444/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) item_no_retry = item._replace(retry_count=MAX_RETRY_COUNT) @@ -228,14 +234,14 @@ class TestAthenadMethods(unittest.TestCase): try: athenad.upload_queue.put_nowait(item_no_retry) - self.wait_for_upload() + self._wait_for_upload() time.sleep(0.1) # Check that upload with retry count exceeded is not put back self.assertEqual(athenad.upload_queue.qsize(), 0) athenad.upload_queue.put_nowait(item) - self.wait_for_upload() + self._wait_for_upload() time.sleep(0.1) # Check that upload item was put back in the queue with incremented retry count @@ -256,7 +262,7 @@ class TestAthenadMethods(unittest.TestCase): thread = threading.Thread(target=athenad.upload_handler, args=(end_event,)) thread.start() try: - self.wait_for_upload() + self._wait_for_upload() time.sleep(0.1) self.assertEqual(athenad.upload_queue.qsize(), 0) @@ -269,8 +275,7 @@ class TestAthenadMethods(unittest.TestCase): ts = int(t_future.strftime("%s")) * 1000 # Item that would time out if actually uploaded - fn = os.path.join(athenad.ROOT, 'qlog.bz2') - Path(fn).touch() + fn = self._create_file('qlog.bz2') item = athenad.UploadItem(path=fn, url="http://localhost:44444/qlog.bz2", headers={}, created_at=ts, id='', allow_cellular=True) @@ -279,7 +284,7 @@ class TestAthenadMethods(unittest.TestCase): thread.start() try: athenad.upload_queue.put_nowait(item) - self.wait_for_upload() + self._wait_for_upload() time.sleep(0.1) self.assertEqual(athenad.upload_queue.qsize(), 0) @@ -292,8 +297,7 @@ class TestAthenadMethods(unittest.TestCase): @with_http_server def test_listUploadQueueCurrent(self, host): - fn = os.path.join(athenad.ROOT, 'qlog.bz2') - Path(fn).touch() + fn = self._create_file('qlog.bz2') item = athenad.UploadItem(path=fn, url=f"{host}/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) end_event = threading.Event() @@ -302,7 +306,7 @@ class TestAthenadMethods(unittest.TestCase): try: athenad.upload_queue.put_nowait(item) - self.wait_for_upload() + self._wait_for_upload() items = dispatcher["listUploadQueue"]() self.assertEqual(len(items), 1) @@ -405,9 +409,9 @@ class TestAthenadMethods(unittest.TestCase): def test_get_logs_to_send_sorted(self): fl = list() for i in range(10): - fn = os.path.join(swaglog.SWAGLOG_DIR, f'swaglog.{i:010}') - Path(fn).touch() - fl.append(os.path.basename(fn)) + file = f'swaglog.{i:010}' + self._create_file(file, athenad.SWAGLOG_DIR) + fl.append(file) # ensure the list is all logs except most recent sl = athenad.get_logs_to_send_sorted() From 6c65e9bf9837cb00c5feeb3744232597c5b421bb Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 17 Oct 2022 13:50:56 -0700 Subject: [PATCH 078/101] HKG FPv2: whitelist queried Ecus (#26115) * whitelist all ecus * remove engine and fwdCamera from queries they never return to --- 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 734e56c033..3585fcc313 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -293,10 +293,12 @@ FW_QUERY_CONFIG = FwQueryConfig( Request( [HYUNDAI_VERSION_REQUEST_LONG], [HYUNDAI_VERSION_RESPONSE], + whitelist_ecus=[Ecu.transmission, Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera], ), Request( [HYUNDAI_VERSION_REQUEST_MULTI], [HYUNDAI_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.transmission, Ecu.eps, Ecu.abs, Ecu.fwdRadar], ), ], extra_ecus=[ From 581835df80dc2cf4d3c0e18fdf9f2772e643da5a Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 17 Oct 2022 14:04:29 -0700 Subject: [PATCH 079/101] 2018 Kia Stinger: add missing FW versions (#26117) add missing versions from 1ce52d9487767eae --- selfdrive/car/hyundai/values.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 3585fcc313..856bf1abd9 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -743,6 +743,7 @@ FW_VERSIONS = { b'\xf1\x81640E0051\x00\x00\x00\x00\x00\x00\x00\x00', b'\xf1\x82CKJN3TMSDE0B\x00\x00\x00\x00', b'\xf1\x82CKKN3TMD_H0A\x00\x00\x00\x00', + b'\xe0\x19\xff\xe7\xe7g\x01\xa2\x00\x0f\x00\x9e\x00\x06\x00\xff\xff\xff\xff\xff\xff\x00\x00\xff\xff\xff\xff\xff\xff\x00\x00\x0f\x0e\x0f\x0f\x0e\r\x00\x00\x7f\x02.\xff\x00\x00~p\x00\x00\x00\x00u\xff\xf9\xff\x00\x00\x00\x00V\t\xd5\x01\xc0\x00\x00\x00\x007\xfb\xfc\x0b\x8d\x00', ], (Ecu.eps, 0x7d4, None): [ b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5200 4C2CL104', @@ -765,6 +766,8 @@ FW_VERSIONS = { b'\xf1\x87VDKLJ18675252DK6\x89vhgwwwwveVU\x88w\x87w\x99vgf\x97vXfgw_\xff\xc2\xfb\xf1\x89E25\x00\x00\x00\x00\x00\x00\x00\xf1\x82TCK0T33NB2', b'\xf1\x87WAJTE17552812CH4vfFffvfVeT5DwvvVVdFeegeg\x88\x88o\xff\x1a]\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00TCK2T20NB1\x19\xd2\x00\x94', b'\xf1\x87VDHLG17274082DK2wfFf\x89x\x98wUT5T\x88v\x97xgeGefTGTVvO\xff\x1c\x14\xf1\x81E19\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E19\x00\x00\x00\x00\x00\x00\x00SCK0T33UB2\xee[\x97S', + b'\xf1\x87VDHLG17000192DK2xdFffT\xa5VUD$DwT\x86wveVeeD&T\x99\xba\x8f\xff\xcc\x99\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\t\xb7\x17\xf5', + b'\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\t\xb7\x17\xf5', ], }, CAR.PALISADE: { From 60586e0d5835dbb3928321700c9d4d99cdeec216 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 18 Oct 2022 05:39:18 +0800 Subject: [PATCH 080/101] Cabana: align the charts properly (#26116) --- tools/cabana/chartswidget.cc | 20 +++++++++++++++++++- tools/cabana/chartswidget.h | 1 + 2 files changed, 20 insertions(+), 1 deletion(-) diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index e69729c03a..3652720e12 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -2,6 +2,7 @@ #include #include +#include #include #include @@ -183,7 +184,6 @@ ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent) font.setBold(true); chart->setTitleFont(font); chart->setMargins({0, 0, 0, 0}); - chart->layout()->setContentsMargins(0, 0, 0, 0); track_line = new QGraphicsLineItem(chart); track_line->setPen(QPen(Qt::gray, 1, Qt::DashLine)); @@ -202,14 +202,32 @@ ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent) rubber->setPalette(pal); } + QTimer *timer = new QTimer(this); + timer->setInterval(100); + timer->setSingleShot(true); + timer->callOnTimeout(this, &ChartView::adjustChartMargins); + QObject::connect(can, &CANMessages::updated, this, &ChartView::updateState); QObject::connect(can, &CANMessages::rangeChanged, this, &ChartView::rangeChanged); QObject::connect(can, &CANMessages::eventsMerged, this, &ChartView::updateSeries); QObject::connect(dynamic_cast(chart->axisX()), &QValueAxis::rangeChanged, can, &CANMessages::setRange); + QObject::connect(chart, &QChart::plotAreaChanged, [=](const QRectF &plotArea) { + // use a singleshot timer to avoid recursion call. + timer->start(); + }); updateSeries(); } +void ChartView::adjustChartMargins() { + // TODO: Remove hardcoded aligned_pos + const int aligned_pos = 60; + if (chart()->plotArea().left() != aligned_pos) { + const float left_margin = chart()->margins().left() + aligned_pos - chart()->plotArea().left(); + chart()->setMargins(QMargins(left_margin, 0, 0, 0)); + } +} + void ChartWidget::setHeight(int height) { chart_view->setFixedHeight(height); } diff --git a/tools/cabana/chartswidget.h b/tools/cabana/chartswidget.h index 3e43409dc4..fe2e14db9f 100644 --- a/tools/cabana/chartswidget.h +++ b/tools/cabana/chartswidget.h @@ -27,6 +27,7 @@ private: void mouseMoveEvent(QMouseEvent *ev) override; void enterEvent(QEvent *event) override; void leaveEvent(QEvent *event) override; + void adjustChartMargins(); void rangeChanged(qreal min, qreal max); void updateAxisY(); From c6b8a253e68fc62cd9eb3261e7f08d3cb3d3414d Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Mon, 17 Oct 2022 15:36:29 -0700 Subject: [PATCH 081/101] networking: fix metered setting (#26113) when metered set unknown, when unmetered set no --- selfdrive/ui/qt/offroad/wifiManager.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/qt/offroad/wifiManager.cc b/selfdrive/ui/qt/offroad/wifiManager.cc index 62de3041b9..fde8645586 100644 --- a/selfdrive/ui/qt/offroad/wifiManager.cc +++ b/selfdrive/ui/qt/offroad/wifiManager.cc @@ -368,7 +368,7 @@ void WifiManager::updateGsmSettings(bool roaming, QString apn, bool metered) { changes = true; } - int meteredInt = metered ? NM_METERED_NO : NM_METERED_UNKNOWN; + int meteredInt = metered ? NM_METERED_UNKNOWN : NM_METERED_NO; if (settings.value("connection").value("metered").toInt() != meteredInt) { qWarning() << "Changing connection.metered to" << meteredInt; settings["connection"]["metered"] = meteredInt; From e6cab24e08323ce1e8d846365a6ca1770a54f851 Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Mon, 17 Oct 2022 15:38:31 -0700 Subject: [PATCH 082/101] updated: sync submodules (#26121) --- selfdrive/updated.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 9568b28ae3..57f957cfff 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -365,6 +365,7 @@ class Updater: ["git", "checkout", "--force", "--no-recurse-submodules", "-B", branch, "FETCH_HEAD"], ["git", "reset", "--hard"], ["git", "clean", "-xdff"], + ["git", "submodule", "sync"], ["git", "submodule", "init"], ["git", "submodule", "update"], ] From 15b8c7d1dc3a75d78c0bbaa4f6b866374f6e8672 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 17 Oct 2022 17:14:38 -0700 Subject: [PATCH 083/101] ui: publish draw times + add test (#26119) * ui: publish draw times + add test * add some checks * adjust * fix linter * update max Co-authored-by: Comma Device --- cereal | 2 +- selfdrive/debug/check_timings.py | 2 +- selfdrive/test/test_onroad.py | 23 +++++++++++++++++++++-- selfdrive/ui/qt/onroad.cc | 10 ++++++++++ selfdrive/ui/qt/onroad.h | 1 + 5 files changed, 34 insertions(+), 4 deletions(-) diff --git a/cereal b/cereal index 5766e645f2..107048c83e 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 5766e645f2ee2a131b145fb1ea9e3b7c55a4a740 +Subproject commit 107048c83ec2f488286a1be314e7aece0a20a6b1 diff --git a/selfdrive/debug/check_timings.py b/selfdrive/debug/check_timings.py index 083e084ca7..fb8467a3c4 100755 --- a/selfdrive/debug/check_timings.py +++ b/selfdrive/debug/check_timings.py @@ -19,7 +19,7 @@ if __name__ == "__main__": for m in msgs: ts[s].append(m.logMonoTime / 1e6) - if len(ts[s]): + if len(ts[s]) > 2: d = np.diff(ts[s]) print(f"{s:25} {np.mean(d):.2f} {np.std(d):.2f} {np.max(d):.2f} {np.min(d):.2f}") time.sleep(1) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index b29ca5d35b..0d3d7b367a 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -120,8 +120,8 @@ class TestOnroad(unittest.TestCase): if "DEBUG" in os.environ: segs = filter(lambda x: os.path.exists(os.path.join(x, "rlog")), Path(ROOT).iterdir()) segs = sorted(segs, key=lambda x: x.stat().st_mtime) - print(segs[-1]) - cls.lr = list(LogReader(os.path.join(segs[-1], "rlog"))) + print(segs[-2]) + cls.lr = list(LogReader(os.path.join(segs[-2], "rlog"))) return # setup env @@ -187,6 +187,25 @@ class TestOnroad(unittest.TestCase): big_logs = [f for f, n in cnt.most_common(3) if n / sum(cnt.values()) > 30.] self.assertEqual(len(big_logs), 0, f"Log spam: {big_logs}") + def test_ui_timings(self): + result = "\n" + result += "------------------------------------------------\n" + result += "-------------- UI Draw Timing ------------------\n" + result += "------------------------------------------------\n" + + ts = [m.uiDebug.drawTimeMillis for m in self.lr if m.which() == 'uiDebug'] + result += f"min {min(ts):.2f}ms\n" + result += f"max {max(ts):.2f}ms\n" + result += f"std {np.std(ts):.2f}ms\n" + result += f"mean {np.mean(ts):.2f}ms\n" + result += "------------------------------------------------\n" + print(result) + + self.assertGreater(len(ts), 20*50, "insufficient samples") + self.assertLess(max(ts), 30.) + self.assertLess(np.mean(ts), 10.) + self.assertLess(np.std(ts), 5.) + def test_cpu_usage(self): proclogs = [m for m in self.lr if m.which() == 'procLog'] self.assertGreater(len(proclogs), service_list['procLog'].frequency * 45, "insufficient samples") diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 0fbfb0cfc2..66bc38dbfc 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -176,6 +176,8 @@ void OnroadAlerts::paintEvent(QPaintEvent *event) { // NvgWindow NvgWindow::NvgWindow(VisionStreamType type, QWidget* parent) : fps_filter(UI_FREQ, 3, 1. / UI_FREQ), CameraViewWidget("camerad", type, true, parent) { + pm = std::make_unique>({"uiDebug"}); + engage_img = loadPixmap("../assets/img_chffr_wheel.png", {img_size, img_size}); dm_img = loadPixmap("../assets/img_driver_face.png", {img_size, img_size}); } @@ -542,6 +544,8 @@ void NvgWindow::drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV } void NvgWindow::paintGL() { + const double start_draw_t = millis_since_boot(); + UIState *s = uiState(); const cereal::ModelDataV2::Reader &model = (*s->sm)["modelV2"].getModelV2(); CameraViewWidget::setFrameId(model.getFrameId()); @@ -575,6 +579,12 @@ void NvgWindow::paintGL() { LOGW("slow frame rate: %.2f fps", fps); } prev_draw_t = cur_draw_t; + + // publish debug msg + MessageBuilder msg; + auto m = msg.initEvent().initUiDebug(); + m.setDrawTimeMillis(cur_draw_t - start_draw_t); + pm->send("uiDebug", msg); } void NvgWindow::showEvent(QShowEvent *event) { diff --git a/selfdrive/ui/qt/onroad.h b/selfdrive/ui/qt/onroad.h index 25920ccc6a..7ed2c9cc4a 100644 --- a/selfdrive/ui/qt/onroad.h +++ b/selfdrive/ui/qt/onroad.h @@ -68,6 +68,7 @@ private: bool has_eu_speed_limit = false; bool v_ego_cluster_seen = false; int status = STATUS_DISENGAGED; + std::unique_ptr pm; protected: void paintGL() override; From cd12ef4aa19a83f88532f5c1a8c3f290b87fcbf8 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 18 Oct 2022 08:18:04 +0800 Subject: [PATCH 084/101] cabana: add a splitter between message lists and detailview (#26118) * add a splitter between message lists and detailview * space --- tools/cabana/mainwin.cc | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc index 999a4816b0..7aea8097cf 100644 --- a/tools/cabana/mainwin.cc +++ b/tools/cabana/mainwin.cc @@ -5,6 +5,7 @@ #include #include #include +#include #include MainWindow::MainWindow() : QWidget() { @@ -13,12 +14,16 @@ MainWindow::MainWindow() : QWidget() { QHBoxLayout *h_layout = new QHBoxLayout(); main_layout->addLayout(h_layout); + QSplitter *splitter = new QSplitter(Qt::Horizontal, this); + messages_widget = new MessagesWidget(this); - h_layout->addWidget(messages_widget); + splitter->addWidget(messages_widget); detail_widget = new DetailWidget(this); - detail_widget->setFixedWidth(600); - h_layout->addWidget(detail_widget); + splitter->addWidget(detail_widget); + + splitter->setSizes({100, 500}); + h_layout->addWidget(splitter); // right widgets QWidget *right_container = new QWidget(this); From 409e8f5f89a38f9893a1f28f8fabd3bf526b46eb Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 18 Oct 2022 08:18:24 +0800 Subject: [PATCH 085/101] cabana: faster history log with better stretch mode (#26112) --- tools/cabana/historylog.cc | 59 ++++++++++++++------------------------ tools/cabana/historylog.h | 13 +++++---- 2 files changed, 28 insertions(+), 44 deletions(-) diff --git a/tools/cabana/historylog.cc b/tools/cabana/historylog.cc index cbb3b6e882..c0efbca280 100644 --- a/tools/cabana/historylog.cc +++ b/tools/cabana/historylog.cc @@ -5,21 +5,16 @@ #include QVariant HistoryLogModel::data(const QModelIndex &index, int role) const { - auto msg = dbc()->msg(msg_id); + bool has_signal = dbc_msg && !dbc_msg->sigs.empty(); if (role == Qt::DisplayRole) { - const auto &can_msgs = can->messages(msg_id); - if (index.row() < can_msgs.size()) { - const auto &can_data = can_msgs[index.row()]; - if (msg && index.column() < msg->sigs.size()) { - return get_raw_value((uint8_t *)can_data.dat.begin(), can_data.dat.size(), msg->sigs[index.column()]); - } else { - return toHex(can_data.dat); - } - } - } else if (role == Qt::FontRole) { - if (index.column() == 0 && !(msg && msg->sigs.size() > 0)) { - return QFontDatabase::systemFont(QFontDatabase::FixedFont); + const auto &m = can->messages(msg_id)[index.row()]; + if (index.column() == 0) { + return QString::number(m.ts, 'f', 2); } + return has_signal ? QString::number(get_raw_value((uint8_t *)m.dat.begin(), m.dat.size(), dbc_msg->sigs[index.column() - 1])) + : toHex(m.dat); + } else if (role == Qt::FontRole && index.column() == 1 && !has_signal) { + return QFontDatabase::systemFont(QFontDatabase::FixedFont); } return {}; } @@ -27,8 +22,8 @@ QVariant HistoryLogModel::data(const QModelIndex &index, int role) const { void HistoryLogModel::setMessage(const QString &message_id) { beginResetModel(); msg_id = message_id; - const auto msg = dbc()->msg(message_id); - column_count = msg && !msg->sigs.empty() ? msg->sigs.size() : 1; + dbc_msg = dbc()->msg(message_id); + column_count = (dbc_msg && !dbc_msg->sigs.empty() ? dbc_msg->sigs.size() : 1) + 1; row_count = 0; endResetModel(); @@ -37,18 +32,14 @@ void HistoryLogModel::setMessage(const QString &message_id) { QVariant HistoryLogModel::headerData(int section, Qt::Orientation orientation, int role) const { if (orientation == Qt::Horizontal) { - auto msg = dbc()->msg(msg_id); - if (msg && section < msg->sigs.size()) { - if (role == Qt::BackgroundRole) { - return QBrush(QColor(getColor(section))); - } else if (role == Qt::DisplayRole || role == Qt::ToolTipRole) { - return QString::fromStdString(msg->sigs[section].name); + bool has_signal = dbc_msg && !dbc_msg->sigs.empty(); + if (role == Qt::DisplayRole || role == Qt::ToolTipRole) { + if (section == 0) { + return "Time"; } - } - } else if (role == Qt::DisplayRole) { - const auto &can_msgs = can->messages(msg_id); - if (section < can_msgs.size()) { - return QString::number(can_msgs[section].ts, 'f', 2); + return has_signal ? dbc_msg->sigs[section - 1].name.c_str() : "Data"; + } else if (role == Qt::BackgroundRole && section > 0 && has_signal) { + return QBrush(QColor(getColor(section - 1))); } } return {}; @@ -69,7 +60,6 @@ void HistoryLogModel::updateState() { } if (row_count > 0) { emit dataChanged(index(0, 0), index(row_count - 1, column_count - 1), {Qt::DisplayRole}); - emit headerDataChanged(Qt::Vertical, 0, row_count - 1); } } @@ -79,17 +69,10 @@ HistoryLog::HistoryLog(QWidget *parent) : QWidget(parent) { model = new HistoryLogModel(this); table = new QTableView(this); table->setModel(model); - table->horizontalHeader()->setStretchLastSection(true); - table->setEditTriggers(QAbstractItemView::NoEditTriggers); + table->horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); + table->horizontalHeader()->setSectionResizeMode(0, QHeaderView::Fixed); + table->setColumnWidth(0, 60); + table->verticalHeader()->setVisible(false); table->setStyleSheet("QTableView::item { border:0px; padding-left:5px; padding-right:5px; }"); - table->verticalHeader()->setStyleSheet("QHeaderView::section {padding-left: 5px; padding-right: 5px;min-width:40px;}"); main_layout->addWidget(table); } - -void HistoryLog::setMessage(const QString &message_id) { - model->setMessage(message_id); -} - -void HistoryLog::updateState() { - model->updateState(); -} diff --git a/tools/cabana/historylog.h b/tools/cabana/historylog.h index f3a9046bfa..bc6d1f9376 100644 --- a/tools/cabana/historylog.h +++ b/tools/cabana/historylog.h @@ -6,21 +6,22 @@ #include "tools/cabana/dbcmanager.h" class HistoryLogModel : public QAbstractTableModel { -Q_OBJECT + Q_OBJECT public: HistoryLogModel(QObject *parent) : QAbstractTableModel(parent) {} void setMessage(const QString &message_id); void updateState(); QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const override; - int columnCount(const QModelIndex &parent = QModelIndex()) const override { return column_count; } - QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const; + QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const override; int rowCount(const QModelIndex &parent = QModelIndex()) const override { return row_count; } + int columnCount(const QModelIndex &parent = QModelIndex()) const override { return column_count; } private: QString msg_id; int row_count = 0; - int column_count = 0; + int column_count = 2; + const Msg *dbc_msg = nullptr; }; class HistoryLog : public QWidget { @@ -28,8 +29,8 @@ class HistoryLog : public QWidget { public: HistoryLog(QWidget *parent); - void setMessage(const QString &message_id); - void updateState(); + void setMessage(const QString &message_id) { model->setMessage(message_id); } + void updateState() { model->updateState(); } private: QTableView *table; From 99b16151fcc621832d573b9f7858eb5020f6503a Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 18 Oct 2022 08:19:41 +0800 Subject: [PATCH 086/101] Cabana: show MSB/LSB of signals in the BinaryView (#26103) * dispaly msb and lsb in binary view * draw at bottom * move binaryview to seperate files * increase the width of vertical header * re-draw changed cells only * correct lsb/msb position * check bounds * todo --- tools/cabana/SConscript | 2 +- tools/cabana/binaryview.cc | 184 +++++++++++++++++++++++++++++++++++ tools/cabana/binaryview.h | 72 ++++++++++++++ tools/cabana/canmessages.h | 1 + tools/cabana/detailwidget.cc | 98 +------------------ tools/cabana/detailwidget.h | 26 +---- tools/cabana/signaledit.cc | 3 + 7 files changed, 265 insertions(+), 121 deletions(-) create mode 100644 tools/cabana/binaryview.cc create mode 100644 tools/cabana/binaryview.h diff --git a/tools/cabana/SConscript b/tools/cabana/SConscript index 8dbd4f1d1c..fd44ecd138 100644 --- a/tools/cabana/SConscript +++ b/tools/cabana/SConscript @@ -12,5 +12,5 @@ else: qt_libs = ['qt_util', 'Qt5Charts'] + base_libs cabana_libs = [widgets, cereal, messaging, visionipc, replay_lib, opendbc,'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv'] + qt_libs -qt_env.Program('_cabana', ['cabana.cc', 'mainwin.cc', 'chartswidget.cc', 'historylog.cc', 'videowidget.cc', 'signaledit.cc', 'dbcmanager.cc', +qt_env.Program('_cabana', ['cabana.cc', 'mainwin.cc', 'binaryview.cc', 'chartswidget.cc', 'historylog.cc', 'videowidget.cc', 'signaledit.cc', 'dbcmanager.cc', 'canmessages.cc', 'messageswidget.cc', 'detailwidget.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks) diff --git a/tools/cabana/binaryview.cc b/tools/cabana/binaryview.cc new file mode 100644 index 0000000000..3b962b6de1 --- /dev/null +++ b/tools/cabana/binaryview.cc @@ -0,0 +1,184 @@ +#include "tools/cabana/binaryview.h" + +#include +#include +#include + +#include "tools/cabana/canmessages.h" + +// BinaryView + +const int CELL_HEIGHT = 35; + +BinaryView::BinaryView(QWidget *parent) : QTableView(parent) { + model = new BinaryViewModel(this); + setModel(model); + setItemDelegate(new BinaryItemDelegate(this)); + horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); + horizontalHeader()->hide(); + verticalHeader()->setSectionResizeMode(QHeaderView::Stretch); + setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + + // replace selection model + auto old_model = selectionModel(); + setSelectionModel(new BinarySelectionModel(model)); + delete old_model; + + QObject::connect(model, &QAbstractItemModel::modelReset, [this]() { + setFixedHeight((CELL_HEIGHT + 1) * std::min(model->rowCount(), 8) + 2); + }); +} + +void BinaryView::mouseReleaseEvent(QMouseEvent *event) { + QTableView::mouseReleaseEvent(event); + + if (auto indexes = selectedIndexes(); !indexes.isEmpty()) { + int start_bit = indexes.first().row() * 8 + indexes.first().column(); + int size = indexes.back().row() * 8 + indexes.back().column() - start_bit + 1; + emit cellsSelected(start_bit, size); + } +} + +void BinaryView::setMessage(const QString &message_id) { + msg_id = message_id; + model->setMessage(message_id); + resizeRowsToContents(); + clearSelection(); + updateState(); +} + +void BinaryView::updateState() { + model->updateState(); +} + +// BinaryViewModel + +void BinaryViewModel::setMessage(const QString &message_id) { + msg_id = message_id; + + beginResetModel(); + items.clear(); + row_count = 0; + + dbc_msg = dbc()->msg(msg_id); + if (dbc_msg) { + row_count = dbc_msg->size; + items.resize(row_count * column_count); + for (int i = 0; i < dbc_msg->sigs.size(); ++i) { + const auto &sig = dbc_msg->sigs[i]; + const int start = sig.is_little_endian ? sig.start_bit : bigEndianBitIndex(sig.start_bit); + const int end = start + sig.size - 1; + for (int j = start; j <= end; ++j) { + int idx = column_count * (j / 8) + j % 8; + if (idx >= items.size()) { + qWarning() << "signal " << sig.name.c_str() << "out of bounds.start_bit:" << sig.start_bit << "size:" << sig.size; + break; + } + if (j == start) { + sig.is_little_endian ? items[idx].is_lsb = true : items[idx].is_msb = true; + } else if (j == end) { + sig.is_little_endian ? items[idx].is_msb = true : items[idx].is_lsb = true; + } + items[idx].bg_color = QColor(getColor(i)); + } + } + } + + endResetModel(); +} + +QModelIndex BinaryViewModel::index(int row, int column, const QModelIndex &parent) const { + return createIndex(row, column, (void *)&items[row * column_count + column]); +} + +Qt::ItemFlags BinaryViewModel::flags(const QModelIndex &index) const { + return (index.column() == column_count - 1) ? Qt::ItemIsEnabled : Qt::ItemIsEnabled | Qt::ItemIsSelectable; +} + +void BinaryViewModel::updateState() { + auto prev_items = items; + + const auto &binary = can->lastMessage(msg_id).dat; + // data size may changed. + if (!dbc_msg && binary.size() != row_count) { + beginResetModel(); + row_count = binary.size(); + items.clear(); + items.resize(row_count * column_count); + endResetModel(); + } + + char hex[3] = {'\0'}; + for (int i = 0; i < std::min(binary.size(), row_count); ++i) { + for (int j = 0; j < column_count - 1; ++j) { + items[i * column_count + j].val = QChar((binary[i] >> (7 - j)) & 1 ? '1' : '0'); + } + hex[0] = toHex(binary[i] >> 4); + hex[1] = toHex(binary[i] & 0xf); + items[i * column_count + 8].val = hex; + } + + for (int i = 0; i < items.size(); ++i) { + if (i >= prev_items.size() || prev_items[i].val != items[i].val) { + auto idx = index(i / column_count, i % column_count); + emit dataChanged(idx, idx); + } + } +} + +QVariant BinaryViewModel::headerData(int section, Qt::Orientation orientation, int role) const { + if (orientation == Qt::Vertical) { + switch (role) { + case Qt::DisplayRole: return section + 1; + case Qt::SizeHintRole: return QSize(30, CELL_HEIGHT); + case Qt::TextAlignmentRole: return Qt::AlignCenter; + } + } + return {}; +} + +// BinarySelectionModel + +void BinarySelectionModel::select(const QItemSelection &selection, QItemSelectionModel::SelectionFlags command) { + QItemSelection new_selection = selection; + if (auto indexes = selection.indexes(); !indexes.isEmpty()) { + auto [begin_idx, end_idx] = (QModelIndex[]){indexes.first(), indexes.back()}; + for (int row = begin_idx.row(); row <= end_idx.row(); ++row) { + int left_col = (row == begin_idx.row()) ? begin_idx.column() : 0; + int right_col = (row == end_idx.row()) ? end_idx.column() : 7; + new_selection.merge({model()->index(row, left_col), model()->index(row, right_col)}, command); + } + } + QItemSelectionModel::select(new_selection, command); +} + +// BinaryItemDelegate + +BinaryItemDelegate::BinaryItemDelegate(QObject *parent) : QStyledItemDelegate(parent) { + // cache fonts and color + small_font.setPointSize(7); + bold_font.setBold(true); + highlight_color = QApplication::style()->standardPalette().color(QPalette::Active, QPalette::Highlight); +} + +QSize BinaryItemDelegate::sizeHint(const QStyleOptionViewItem &option, const QModelIndex &index) const { + QSize sz = QStyledItemDelegate::sizeHint(option, index); + return {sz.width(), CELL_HEIGHT}; +} + +void BinaryItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const { + auto item = (const BinaryViewModel::Item *)index.internalPointer(); + painter->save(); + // TODO: highlight signal cells on mouse over + painter->fillRect(option.rect, option.state & QStyle::State_Selected ? highlight_color : item->bg_color); + if (index.column() == 8) { + painter->setFont(bold_font); + } + painter->drawText(option.rect, Qt::AlignCenter, item->val); + if (item->is_msb || item->is_lsb) { + painter->setFont(small_font); + painter->drawText(option.rect, Qt::AlignHCenter | Qt::AlignBottom, item->is_msb ? "MSB" : "LSB"); + } + + painter->restore(); +} diff --git a/tools/cabana/binaryview.h b/tools/cabana/binaryview.h new file mode 100644 index 0000000000..631797ca48 --- /dev/null +++ b/tools/cabana/binaryview.h @@ -0,0 +1,72 @@ +#pragma once + +#include +#include + +#include "tools/cabana/dbcmanager.h" + +class BinaryItemDelegate : public QStyledItemDelegate { + Q_OBJECT + +public: + BinaryItemDelegate(QObject *parent); + void paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const override; + QSize sizeHint(const QStyleOptionViewItem &option, const QModelIndex &index) const override; + +private: + QFont small_font, bold_font; + QColor highlight_color; +}; + +class BinaryViewModel : public QAbstractTableModel { + Q_OBJECT + +public: + BinaryViewModel(QObject *parent) : QAbstractTableModel(parent) {} + void setMessage(const QString &message_id); + void updateState(); + Qt::ItemFlags flags(const QModelIndex &index) const; + QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const override; + QModelIndex index(int row, int column, const QModelIndex &parent = QModelIndex()) const; + QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const { return {}; } + int rowCount(const QModelIndex &parent = QModelIndex()) const override { return row_count; } + int columnCount(const QModelIndex &parent = QModelIndex()) const override { return column_count; } + + struct Item { + QColor bg_color = QColor(Qt::white); + bool is_msb = false; + bool is_lsb = false; + QString val = "0"; + }; + +private: + QString msg_id; + const Msg *dbc_msg; + int row_count = 0; + const int column_count = 9; + std::vector items; +}; + +// the default QItemSelectionModel does not support our selection mode. +class BinarySelectionModel : public QItemSelectionModel { + public: + BinarySelectionModel(QAbstractItemModel *model = nullptr) : QItemSelectionModel(model) {} + void select(const QItemSelection &selection, QItemSelectionModel::SelectionFlags command) override; +}; + +class BinaryView : public QTableView { + Q_OBJECT + +public: + BinaryView(QWidget *parent = nullptr); + void mouseReleaseEvent(QMouseEvent *event) override; + void setMessage(const QString &message_id); + void updateState(); + +signals: + void cellsSelected(int start_bit, int size); + +private: + QString msg_id; + BinaryViewModel *model; +}; diff --git a/tools/cabana/canmessages.h b/tools/cabana/canmessages.h index 7f6955369b..fe71840d74 100644 --- a/tools/cabana/canmessages.h +++ b/tools/cabana/canmessages.h @@ -91,6 +91,7 @@ inline char toHex(uint value) { } inline const QString &getColor(int i) { + // TODO: add more colors static const QString SIGNAL_COLORS[] = {"#9FE2BF", "#40E0D0", "#6495ED", "#CCCCFF", "#FF7F50", "#FFBF00"}; return SIGNAL_COLORS[i % std::size(SIGNAL_COLORS)]; } diff --git a/tools/cabana/detailwidget.cc b/tools/cabana/detailwidget.cc index a9899ec650..60d0632d4c 100644 --- a/tools/cabana/detailwidget.cc +++ b/tools/cabana/detailwidget.cc @@ -1,13 +1,13 @@ #include "tools/cabana/detailwidget.h" #include -#include #include -#include #include -#include #include +#include "tools/cabana/canmessages.h" +#include "tools/cabana/dbcmanager.h" + // DetailWidget DetailWidget::DetailWidget(QWidget *parent) : QWidget(parent) { @@ -141,98 +141,6 @@ void DetailWidget::removeSignal() { } } -// BinaryView - -BinaryView::BinaryView(QWidget *parent) : QTableWidget(parent) { - horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); - verticalHeader()->setSectionResizeMode(QHeaderView::Stretch); - horizontalHeader()->hide(); - setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); - setColumnCount(9); - - // replace selection model - auto old_model = selectionModel(); - setSelectionModel(new BinarySelectionModel(model())); - delete old_model; -} - -void BinaryView::mouseReleaseEvent(QMouseEvent *event) { - QTableWidget::mouseReleaseEvent(event); - - if (auto items = selectedItems(); !items.isEmpty()) { - int start_bit = items.first()->row() * 8 + items.first()->column(); - int size = items.back()->row() * 8 + items.back()->column() - start_bit + 1; - emit cellsSelected(start_bit, size); - } -} - -void BinaryView::setMessage(const QString &message_id) { - msg_id = message_id; - if (msg_id.isEmpty()) return; - - const Msg *msg = dbc()->msg(msg_id); - int row_count = msg ? msg->size : can->lastMessage(msg_id).dat.size(); - setRowCount(row_count); - setColumnCount(9); - for (int i = 0; i < rowCount(); ++i) { - for (int j = 0; j < columnCount(); ++j) { - auto item = new QTableWidgetItem(); - item->setFlags(item->flags() ^ Qt::ItemIsEditable); - item->setTextAlignment(Qt::AlignCenter); - if (j == 8) { - QFont font = QFontDatabase::systemFont(QFontDatabase::FixedFont); - font.setBold(true); - item->setFont(font); - item->setFlags(item->flags() ^ Qt::ItemIsSelectable); - } - setItem(i, j, item); - } - } - - // set background color - if (msg) { - for (int i = 0; i < msg->sigs.size(); ++i) { - const auto &sig = msg->sigs[i]; - int start = sig.is_little_endian ? sig.start_bit : bigEndianBitIndex(sig.start_bit); - for (int j = start; j <= std::min(start + sig.size - 1, rowCount() * columnCount() - 1); ++j) { - item(j / 8, j % 8)->setBackground(QColor(getColor(i))); - } - } - } - - setFixedHeight(rowHeight(0) * std::min(row_count, 8) + 2); - clearSelection(); - updateState(); -} - -void BinaryView::updateState() { - const auto &binary = can->lastMessage(msg_id).dat; - setUpdatesEnabled(false); - char hex[3] = {'\0'}; - for (int i = 0; i < binary.size(); ++i) { - for (int j = 0; j < 8; ++j) { - item(i, j)->setText(QChar((binary[i] >> (7 - j)) & 1 ? '1' : '0')); - } - hex[0] = toHex(binary[i] >> 4); - hex[1] = toHex(binary[i] & 0xf); - item(i, 8)->setText(hex); - } - setUpdatesEnabled(true); -} - -void BinarySelectionModel::select(const QItemSelection &selection, QItemSelectionModel::SelectionFlags command) { - QItemSelection new_selection = selection; - if (auto indexes = selection.indexes(); !indexes.isEmpty()) { - auto [begin_idx, end_idx] = (QModelIndex[]){indexes.first(), indexes.back()}; - for (int row = begin_idx.row(); row <= end_idx.row(); ++row) { - int left_col = (row == begin_idx.row()) ? begin_idx.column() : 0; - int right_col = (row == end_idx.row()) ? end_idx.column() : 7; - new_selection.merge({model()->index(row, left_col), model()->index(row, right_col)}, command); - } - } - QItemSelectionModel::select(new_selection, command); -} - // EditMessageDialog EditMessageDialog::EditMessageDialog(const QString &msg_id, const QString &title, int size, QWidget *parent) : QDialog(parent) { diff --git a/tools/cabana/detailwidget.h b/tools/cabana/detailwidget.h index db174873f7..9d3b81dcb0 100644 --- a/tools/cabana/detailwidget.h +++ b/tools/cabana/detailwidget.h @@ -1,35 +1,11 @@ #pragma once #include -#include -#include "opendbc/can/common.h" -#include "opendbc/can/common_dbc.h" -#include "tools/cabana/canmessages.h" -#include "tools/cabana/dbcmanager.h" +#include "tools/cabana/binaryview.h" #include "tools/cabana/historylog.h" #include "tools/cabana/signaledit.h" -class BinarySelectionModel : public QItemSelectionModel { -public: - BinarySelectionModel(QAbstractItemModel *model = nullptr) : QItemSelectionModel(model) {} - void select(const QItemSelection &selection, QItemSelectionModel::SelectionFlags command) override; -}; - -class BinaryView : public QTableWidget { - Q_OBJECT -public: - BinaryView(QWidget *parent = nullptr); - void mouseReleaseEvent(QMouseEvent *event) override; - void setMessage(const QString &message_id); - void updateState(); -signals: - void cellsSelected(int start_bit, int size); - -private: - QString msg_id; -}; - class EditMessageDialog : public QDialog { Q_OBJECT diff --git a/tools/cabana/signaledit.cc b/tools/cabana/signaledit.cc index 2da3e2eec2..b52f83dab6 100644 --- a/tools/cabana/signaledit.cc +++ b/tools/cabana/signaledit.cc @@ -23,6 +23,9 @@ SignalForm::SignalForm(const Signal &sig, QWidget *parent) : start_bit(sig.start endianness->setCurrentIndex(sig.is_little_endian ? 0 : 1); form_layout->addRow(tr("Endianness"), endianness); + form_layout->addRow(tr("lsb"), new QLabel(QString::number(sig.lsb))); + form_layout->addRow(tr("msb"), new QLabel(QString::number(sig.msb))); + sign = new QComboBox(); sign->addItems({"Signed", "Unsigned"}); sign->setCurrentIndex(sig.is_signed ? 0 : 1); From c782e4d796e0981b3717222cb5551911fe40cb7a Mon Sep 17 00:00:00 2001 From: Jake Poznanski Date: Mon, 17 Oct 2022 17:22:47 -0700 Subject: [PATCH 087/101] loggerd: fix length of ArrayPtr in handle_encoder_msg (#26077) --- selfdrive/loggerd/loggerd.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index e0892e68b4..9beb3c3bf1 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -55,7 +55,7 @@ int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct int bytes_count = 0; // extract the message - capnp::FlatArrayMessageReader cmsg(kj::ArrayPtr((capnp::word *)msg->getData(), msg->getSize())); + capnp::FlatArrayMessageReader cmsg(kj::ArrayPtr((capnp::word *)msg->getData(), msg->getSize() / sizeof(capnp::word))); auto event = cmsg.getRoot(); auto edata = (name == "driverEncodeData") ? event.getDriverEncodeData() : ((name == "wideRoadEncodeData") ? event.getWideRoadEncodeData() : From baca1cae1f71c70162374c887cf36d5cf828f2f3 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Mon, 17 Oct 2022 18:18:01 -0700 Subject: [PATCH 088/101] UI Onroad widget renames (#26124) Consistent widget naming --- selfdrive/ui/qt/offroad/driverview.cc | 4 +-- selfdrive/ui/qt/offroad/driverview.h | 2 +- selfdrive/ui/qt/onroad.cc | 45 ++++++++++++----------- selfdrive/ui/qt/onroad.h | 6 ++-- selfdrive/ui/qt/widgets/cameraview.cc | 26 +++++++------- selfdrive/ui/qt/widgets/cameraview.h | 6 ++-- selfdrive/ui/translations/main_ar.ts | 2 +- selfdrive/ui/translations/main_ja.ts | 46 ++++++++++++------------ selfdrive/ui/translations/main_ko.ts | 46 ++++++++++++------------ selfdrive/ui/translations/main_nl.ts | 2 +- selfdrive/ui/translations/main_pl.ts | 2 +- selfdrive/ui/translations/main_pt-BR.ts | 46 ++++++++++++------------ selfdrive/ui/translations/main_th.ts | 2 +- selfdrive/ui/translations/main_zh-CHS.ts | 46 ++++++++++++------------ selfdrive/ui/translations/main_zh-CHT.ts | 46 ++++++++++++------------ selfdrive/ui/watch3.cc | 8 ++--- tools/cabana/videowidget.cc | 6 ++-- tools/cabana/videowidget.h | 2 +- 18 files changed, 173 insertions(+), 170 deletions(-) diff --git a/selfdrive/ui/qt/offroad/driverview.cc b/selfdrive/ui/qt/offroad/driverview.cc index be8b84d45e..0ff786fb91 100644 --- a/selfdrive/ui/qt/offroad/driverview.cc +++ b/selfdrive/ui/qt/offroad/driverview.cc @@ -12,11 +12,11 @@ DriverViewWindow::DriverViewWindow(QWidget* parent) : QWidget(parent) { layout = new QStackedLayout(this); layout->setStackingMode(QStackedLayout::StackAll); - cameraView = new CameraViewWidget("camerad", VISION_STREAM_DRIVER, true, this); + cameraView = new CameraWidget("camerad", VISION_STREAM_DRIVER, true, this); layout->addWidget(cameraView); scene = new DriverViewScene(this); - connect(cameraView, &CameraViewWidget::vipcThreadFrameReceived, scene, &DriverViewScene::frameUpdated); + connect(cameraView, &CameraWidget::vipcThreadFrameReceived, scene, &DriverViewScene::frameUpdated); layout->addWidget(scene); layout->setCurrentWidget(scene); } diff --git a/selfdrive/ui/qt/offroad/driverview.h b/selfdrive/ui/qt/offroad/driverview.h index 5d090ad772..255857970d 100644 --- a/selfdrive/ui/qt/offroad/driverview.h +++ b/selfdrive/ui/qt/offroad/driverview.h @@ -42,7 +42,7 @@ protected: void mouseReleaseEvent(QMouseEvent* e) override; private: - CameraViewWidget *cameraView; + CameraWidget *cameraView; DriverViewScene *scene; QStackedLayout *layout; }; diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 66bc38dbfc..1f677fc92d 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -18,7 +18,7 @@ OnroadWindow::OnroadWindow(QWidget *parent) : QWidget(parent) { stacked_layout->setStackingMode(QStackedLayout::StackAll); main_layout->addLayout(stacked_layout); - nvg = new NvgWindow(VISION_STREAM_ROAD, this); + nvg = new AnnotatedCameraWidget(VISION_STREAM_ROAD, this); QWidget * split_wrapper = new QWidget; split = new QHBoxLayout(split_wrapper); @@ -27,7 +27,7 @@ OnroadWindow::OnroadWindow(QWidget *parent) : QWidget(parent) { split->addWidget(nvg); if (getenv("DUAL_CAMERA_VIEW")) { - CameraViewWidget *arCam = new CameraViewWidget("camerad", VISION_STREAM_ROAD, true, this); + CameraWidget *arCam = new CameraWidget("camerad", VISION_STREAM_ROAD, true, this); split->insertWidget(0, arCam); } @@ -173,16 +173,15 @@ void OnroadAlerts::paintEvent(QPaintEvent *event) { } } -// NvgWindow -NvgWindow::NvgWindow(VisionStreamType type, QWidget* parent) : fps_filter(UI_FREQ, 3, 1. / UI_FREQ), CameraViewWidget("camerad", type, true, parent) { +AnnotatedCameraWidget::AnnotatedCameraWidget(VisionStreamType type, QWidget* parent) : fps_filter(UI_FREQ, 3, 1. / UI_FREQ), CameraWidget("camerad", type, true, parent) { pm = std::make_unique>({"uiDebug"}); engage_img = loadPixmap("../assets/img_chffr_wheel.png", {img_size, img_size}); dm_img = loadPixmap("../assets/img_driver_face.png", {img_size, img_size}); } -void NvgWindow::updateState(const UIState &s) { +void AnnotatedCameraWidget::updateState(const UIState &s) { const int SET_SPEED_NA = 255; const SubMaster &sm = *(s.sm); @@ -234,13 +233,13 @@ void NvgWindow::updateState(const UIState &s) { } if (s.scene.calibration_valid) { - CameraViewWidget::updateCalibration(s.scene.view_from_calib); + CameraWidget::updateCalibration(s.scene.view_from_calib); } else { - CameraViewWidget::updateCalibration(DEFAULT_CALIBRATION); + CameraWidget::updateCalibration(DEFAULT_CALIBRATION); } } -void NvgWindow::drawHud(QPainter &p) { +void AnnotatedCameraWidget::drawHud(QPainter &p) { p.save(); // Header gradient @@ -402,7 +401,11 @@ void NvgWindow::drawHud(QPainter &p) { p.restore(); } -void NvgWindow::drawText(QPainter &p, int x, int y, const QString &text, int alpha) { + +// Window that shows camera view and variety of +// info drawn on top + +void AnnotatedCameraWidget::drawText(QPainter &p, int x, int y, const QString &text, int alpha) { QRect real_rect = getTextRect(p, 0, text); real_rect.moveCenter({x, y - real_rect.height() / 2}); @@ -410,7 +413,7 @@ void NvgWindow::drawText(QPainter &p, int x, int y, const QString &text, int alp p.drawText(real_rect.x(), real_rect.bottom(), text); } -void NvgWindow::drawIcon(QPainter &p, int x, int y, QPixmap &img, QBrush bg, float opacity) { +void AnnotatedCameraWidget::drawIcon(QPainter &p, int x, int y, QPixmap &img, QBrush bg, float opacity) { p.setPen(Qt::NoPen); p.setBrush(bg); p.drawEllipse(x - radius / 2, y - radius / 2, radius, radius); @@ -419,8 +422,8 @@ void NvgWindow::drawIcon(QPainter &p, int x, int y, QPixmap &img, QBrush bg, flo } -void NvgWindow::initializeGL() { - CameraViewWidget::initializeGL(); +void AnnotatedCameraWidget::initializeGL() { + CameraWidget::initializeGL(); qInfo() << "OpenGL version:" << QString((const char*)glGetString(GL_VERSION)); qInfo() << "OpenGL vendor:" << QString((const char*)glGetString(GL_VENDOR)); qInfo() << "OpenGL renderer:" << QString((const char*)glGetString(GL_RENDERER)); @@ -430,8 +433,8 @@ void NvgWindow::initializeGL() { setBackgroundColor(bg_colors[STATUS_DISENGAGED]); } -void NvgWindow::updateFrameMat() { - CameraViewWidget::updateFrameMat(); +void AnnotatedCameraWidget::updateFrameMat() { + CameraWidget::updateFrameMat(); UIState *s = uiState(); int w = width(), h = height(); @@ -448,7 +451,7 @@ void NvgWindow::updateFrameMat() { .translate(-intrinsic_matrix.v[2], -intrinsic_matrix.v[5]); } -void NvgWindow::drawLaneLines(QPainter &painter, const UIState *s) { +void AnnotatedCameraWidget::drawLaneLines(QPainter &painter, const UIState *s) { painter.save(); const UIScene &scene = s->scene; @@ -507,7 +510,7 @@ void NvgWindow::drawLaneLines(QPainter &painter, const UIState *s) { painter.restore(); } -void NvgWindow::drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV3::Reader &lead_data, const QPointF &vd) { +void AnnotatedCameraWidget::drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV3::Reader &lead_data, const QPointF &vd) { painter.save(); const float speedBuff = 10.; @@ -543,13 +546,13 @@ void NvgWindow::drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV painter.restore(); } -void NvgWindow::paintGL() { +void AnnotatedCameraWidget::paintGL() { const double start_draw_t = millis_since_boot(); UIState *s = uiState(); const cereal::ModelDataV2::Reader &model = (*s->sm)["modelV2"].getModelV2(); - CameraViewWidget::setFrameId(model.getFrameId()); - CameraViewWidget::paintGL(); + CameraWidget::setFrameId(model.getFrameId()); + CameraWidget::paintGL(); QPainter painter(this); painter.setRenderHint(QPainter::Antialiasing); @@ -587,8 +590,8 @@ void NvgWindow::paintGL() { pm->send("uiDebug", msg); } -void NvgWindow::showEvent(QShowEvent *event) { - CameraViewWidget::showEvent(event); +void AnnotatedCameraWidget::showEvent(QShowEvent *event) { + CameraWidget::showEvent(event); ui_update_params(uiState()); prev_draw_t = millis_since_boot(); diff --git a/selfdrive/ui/qt/onroad.h b/selfdrive/ui/qt/onroad.h index 7ed2c9cc4a..2a663185f4 100644 --- a/selfdrive/ui/qt/onroad.h +++ b/selfdrive/ui/qt/onroad.h @@ -25,7 +25,7 @@ private: }; // container window for the NVG UI -class NvgWindow : public CameraViewWidget { +class AnnotatedCameraWidget : public CameraWidget { Q_OBJECT Q_PROPERTY(float speed MEMBER speed); Q_PROPERTY(QString speedUnit MEMBER speedUnit); @@ -43,7 +43,7 @@ class NvgWindow : public CameraViewWidget { Q_PROPERTY(int status MEMBER status); public: - explicit NvgWindow(VisionStreamType type, QWidget* parent = 0); + explicit AnnotatedCameraWidget(VisionStreamType type, QWidget* parent = 0); void updateState(const UIState &s); private: @@ -98,7 +98,7 @@ private: void paintEvent(QPaintEvent *event); void mousePressEvent(QMouseEvent* e) override; OnroadAlerts *alerts; - NvgWindow *nvg; + AnnotatedCameraWidget *nvg; QColor bg = bg_colors[STATUS_DISENGAGED]; QWidget *map = nullptr; QHBoxLayout* split; diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 63d15660a0..200257235d 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -93,14 +93,14 @@ mat4 get_fit_view_transform(float widget_aspect_ratio, float frame_aspect_ratio) } // namespace -CameraViewWidget::CameraViewWidget(std::string stream_name, VisionStreamType type, bool zoom, QWidget* parent) : +CameraWidget::CameraWidget(std::string stream_name, VisionStreamType type, bool zoom, QWidget* parent) : stream_name(stream_name), stream_type(type), zoomed_view(zoom), QOpenGLWidget(parent) { setAttribute(Qt::WA_OpaquePaintEvent); - connect(this, &CameraViewWidget::vipcThreadConnected, this, &CameraViewWidget::vipcConnected, Qt::BlockingQueuedConnection); - connect(this, &CameraViewWidget::vipcThreadFrameReceived, this, &CameraViewWidget::vipcFrameReceived); + connect(this, &CameraWidget::vipcThreadConnected, this, &CameraWidget::vipcConnected, Qt::BlockingQueuedConnection); + connect(this, &CameraWidget::vipcThreadFrameReceived, this, &CameraWidget::vipcFrameReceived); } -CameraViewWidget::~CameraViewWidget() { +CameraWidget::~CameraWidget() { makeCurrent(); if (isValid()) { glDeleteVertexArrays(1, &frame_vao); @@ -111,7 +111,7 @@ CameraViewWidget::~CameraViewWidget() { doneCurrent(); } -void CameraViewWidget::initializeGL() { +void CameraWidget::initializeGL() { initializeOpenGLFunctions(); program = std::make_unique(context()); @@ -161,7 +161,7 @@ void CameraViewWidget::initializeGL() { #endif } -void CameraViewWidget::showEvent(QShowEvent *event) { +void CameraWidget::showEvent(QShowEvent *event) { frames.clear(); if (!vipc_thread) { vipc_thread = new QThread(); @@ -171,7 +171,7 @@ void CameraViewWidget::showEvent(QShowEvent *event) { } } -void CameraViewWidget::hideEvent(QHideEvent *event) { +void CameraWidget::hideEvent(QHideEvent *event) { if (vipc_thread) { vipc_thread->requestInterruption(); vipc_thread->quit(); @@ -180,7 +180,7 @@ void CameraViewWidget::hideEvent(QHideEvent *event) { } } -void CameraViewWidget::updateFrameMat() { +void CameraWidget::updateFrameMat() { int w = width(), h = height(); if (zoomed_view) { @@ -224,12 +224,12 @@ void CameraViewWidget::updateFrameMat() { } } -void CameraViewWidget::updateCalibration(const mat3 &calib) { +void CameraWidget::updateCalibration(const mat3 &calib) { calibration = calib; updateFrameMat(); } -void CameraViewWidget::paintGL() { +void CameraWidget::paintGL() { glClearColor(bg.redF(), bg.greenF(), bg.blueF(), bg.alphaF()); glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); @@ -286,7 +286,7 @@ void CameraViewWidget::paintGL() { glPixelStorei(GL_UNPACK_ROW_LENGTH, 0); } -void CameraViewWidget::vipcConnected(VisionIpcClient *vipc_client) { +void CameraWidget::vipcConnected(VisionIpcClient *vipc_client) { makeCurrent(); frames.clear(); stream_width = vipc_client->buffers[0].width; @@ -339,7 +339,7 @@ void CameraViewWidget::vipcConnected(VisionIpcClient *vipc_client) { updateFrameMat(); } -void CameraViewWidget::vipcFrameReceived(VisionBuf *buf, uint32_t frame_id) { +void CameraWidget::vipcFrameReceived(VisionBuf *buf, uint32_t frame_id) { frames.push_back(std::make_pair(frame_id, buf)); while (frames.size() > FRAME_BUFFER_SIZE) { frames.pop_front(); @@ -347,7 +347,7 @@ void CameraViewWidget::vipcFrameReceived(VisionBuf *buf, uint32_t frame_id) { update(); } -void CameraViewWidget::vipcThread() { +void CameraWidget::vipcThread() { VisionStreamType cur_stream_type = stream_type; std::unique_ptr vipc_client; VisionIpcBufExtra meta_main = {0}; diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index 081483b649..9bcad935c0 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -23,13 +23,13 @@ const int FRAME_BUFFER_SIZE = 5; static_assert(FRAME_BUFFER_SIZE <= YUV_BUFFER_COUNT); -class CameraViewWidget : public QOpenGLWidget, protected QOpenGLFunctions { +class CameraWidget : public QOpenGLWidget, protected QOpenGLFunctions { Q_OBJECT public: using QOpenGLWidget::QOpenGLWidget; - explicit CameraViewWidget(std::string stream_name, VisionStreamType stream_type, bool zoom, QWidget* parent = nullptr); - ~CameraViewWidget(); + explicit CameraWidget(std::string stream_name, VisionStreamType stream_type, bool zoom, QWidget* parent = nullptr); + ~CameraWidget(); void setStreamType(VisionStreamType type) { stream_type = type; } void setBackgroundColor(const QColor &color) { bg = color; } void setFrameId(int frame_id) { draw_frame_id = frame_id; } diff --git a/selfdrive/ui/translations/main_ar.ts b/selfdrive/ui/translations/main_ar.ts index 284208720b..a94d2fbc05 100644 --- a/selfdrive/ui/translations/main_ar.ts +++ b/selfdrive/ui/translations/main_ar.ts @@ -493,7 +493,7 @@ location set - NvgWindow + AnnotatedCameraWidget km/h diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index b39c83c098..314a6b8338 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -67,6 +67,29 @@ + + AnnotatedCameraWidget + + km/h + km/h + + + mph + mph + + + MAX + 最高速度 + + + SPEED + 速度 + + + LIMIT + 制限速度 + + ConfirmationDialog @@ -406,29 +429,6 @@ location set パスワードが間違っています - - NvgWindow - - km/h - km/h - - - mph - mph - - - MAX - 最高速度 - - - SPEED - 速度 - - - LIMIT - 制限速度 - - OffroadHome diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index f84797eb60..021243595e 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -67,6 +67,29 @@ 데이터 요금제 연결 시 대용량 데이터 업로드 방지 + + AnnotatedCameraWidget + + km/h + km/h + + + mph + mph + + + MAX + MAX + + + SPEED + SPEED + + + LIMIT + LIMIT + + ConfirmationDialog @@ -406,29 +429,6 @@ location set 비밀번호가 틀렸습니다 - - NvgWindow - - km/h - km/h - - - mph - mph - - - MAX - MAX - - - SPEED - SPEED - - - LIMIT - LIMIT - - OffroadHome diff --git a/selfdrive/ui/translations/main_nl.ts b/selfdrive/ui/translations/main_nl.ts index 99646ed749..21bb66d356 100644 --- a/selfdrive/ui/translations/main_nl.ts +++ b/selfdrive/ui/translations/main_nl.ts @@ -489,7 +489,7 @@ ingesteld - NvgWindow + AnnotatedCameraWidget km/h diff --git a/selfdrive/ui/translations/main_pl.ts b/selfdrive/ui/translations/main_pl.ts index 8593d68261..92902d04a9 100644 --- a/selfdrive/ui/translations/main_pl.ts +++ b/selfdrive/ui/translations/main_pl.ts @@ -490,7 +490,7 @@ nie zostało ustawione - NvgWindow + AnnotatedCameraWidget km/h diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 8f59bf4715..2afdaf3388 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -67,6 +67,29 @@ Evite grandes uploads de dados quando estiver em uma conexão limitada + + AnnotatedCameraWidget + + km/h + km/h + + + mph + mph + + + MAX + LIMITE + + + SPEED + MAX + + + LIMIT + VELO + + ConfirmationDialog @@ -407,29 +430,6 @@ trabalho definido Senha incorreta - - NvgWindow - - km/h - km/h - - - mph - mph - - - MAX - LIMITE - - - SPEED - MAX - - - LIMIT - VELO - - OffroadHome diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts index 7e7fcf2788..d502c3fce1 100644 --- a/selfdrive/ui/translations/main_th.ts +++ b/selfdrive/ui/translations/main_th.ts @@ -488,7 +488,7 @@ location set - NvgWindow + AnnotatedCameraWidget km/h diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 1d942387e0..9e7c354444 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -67,6 +67,29 @@ + + AnnotatedCameraWidget + + km/h + km/h + + + mph + mph + + + MAX + 最高定速 + + + SPEED + SPEED + + + LIMIT + LIMIT + + ConfirmationDialog @@ -404,29 +427,6 @@ location set 密码错误 - - NvgWindow - - km/h - km/h - - - mph - mph - - - MAX - 最高定速 - - - SPEED - SPEED - - - LIMIT - LIMIT - - OffroadHome diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 816d4fd3cc..513135c7f4 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -67,6 +67,29 @@ + + AnnotatedCameraWidget + + km/h + km/h + + + mph + mph + + + MAX + 最高 + + + SPEED + 速度 + + + LIMIT + 速限 + + ConfirmationDialog @@ -406,29 +429,6 @@ location set 密碼錯誤 - - NvgWindow - - km/h - km/h - - - mph - mph - - - MAX - 最高 - - - SPEED - 速度 - - - LIMIT - 速限 - - OffroadHome diff --git a/selfdrive/ui/watch3.cc b/selfdrive/ui/watch3.cc index d6b5cc67a7..ec35c29b6b 100644 --- a/selfdrive/ui/watch3.cc +++ b/selfdrive/ui/watch3.cc @@ -19,15 +19,15 @@ int main(int argc, char *argv[]) { { QHBoxLayout *hlayout = new QHBoxLayout(); layout->addLayout(hlayout); - hlayout->addWidget(new CameraViewWidget("navd", VISION_STREAM_MAP, false)); - hlayout->addWidget(new CameraViewWidget("camerad", VISION_STREAM_ROAD, false)); + hlayout->addWidget(new CameraWidget("navd", VISION_STREAM_MAP, false)); + hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_ROAD, false)); } { QHBoxLayout *hlayout = new QHBoxLayout(); layout->addLayout(hlayout); - hlayout->addWidget(new CameraViewWidget("camerad", VISION_STREAM_DRIVER, false)); - hlayout->addWidget(new CameraViewWidget("camerad", VISION_STREAM_WIDE_ROAD, false)); + hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_DRIVER, false)); + hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_WIDE_ROAD, false)); } return a.exec(); diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc index b6fe8de3e2..bb90d56570 100644 --- a/tools/cabana/videowidget.cc +++ b/tools/cabana/videowidget.cc @@ -16,8 +16,8 @@ inline QString formatTime(int seconds) { VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) { QVBoxLayout *main_layout = new QVBoxLayout(this); - // TODO: figure out why the CameraViewWidget crashed occasionally. - cam_widget = new CameraViewWidget("camerad", VISION_STREAM_ROAD, false, this); + // TODO: figure out why the CameraWidget crashed occasionally. + cam_widget = new CameraWidget("camerad", VISION_STREAM_ROAD, false, this); cam_widget->setFixedSize(parent->width(), parent->width() / 1.596); main_layout->addWidget(cam_widget); @@ -60,7 +60,7 @@ VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) { QObject::connect(can, &CANMessages::updated, this, &VideoWidget::updateState); QObject::connect(slider, &QSlider::sliderReleased, [this]() { can->seekTo(slider->value() / 1000.0); }); QObject::connect(slider, &QSlider::valueChanged, [=](int value) { time_label->setText(formatTime(value / 1000)); }); - QObject::connect(cam_widget, &CameraViewWidget::clicked, [this]() { pause(!can->isPaused()); }); + QObject::connect(cam_widget, &CameraWidget::clicked, [this]() { pause(!can->isPaused()); }); QObject::connect(play_btn, &QPushButton::clicked, [=]() { pause(!can->isPaused()); }); } diff --git a/tools/cabana/videowidget.h b/tools/cabana/videowidget.h index fd896f1e11..d6d036c461 100644 --- a/tools/cabana/videowidget.h +++ b/tools/cabana/videowidget.h @@ -32,7 +32,7 @@ protected: void updateState(); void pause(bool pause); - CameraViewWidget *cam_widget; + CameraWidget *cam_widget; QLabel *end_time_label; QPushButton *play_btn; Slider *slider; From 755a6c0a46f07cdadb06821ced904af458fbf4e3 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 17 Oct 2022 19:15:21 -0700 Subject: [PATCH 089/101] Revert "tools/replay: reduce test running time (#26110)" This reverts commit 6d07268ee5b385010961eab206b0b42a0ae6b5f8. --- tools/replay/tests/test_replay.cc | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/tools/replay/tests/test_replay.cc b/tools/replay/tests/test_replay.cc index 3fd410bb6e..5b61b6b6f2 100644 --- a/tools/replay/tests/test_replay.cc +++ b/tools/replay/tests/test_replay.cc @@ -207,7 +207,8 @@ void TestReplay::test_seek() { } TEST_CASE("Replay") { - TestReplay replay(DEMO_ROUTE, (uint8_t)REPLAY_FLAG_NO_VIPC); + auto flag = GENERATE(REPLAY_FLAG_NO_FILE_CACHE, REPLAY_FLAG_NONE); + TestReplay replay(DEMO_ROUTE, flag); REQUIRE(replay.load()); replay.test_seek(); } From d522492ba0b80928adc475c1f37b995834c31a90 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Mon, 17 Oct 2022 19:40:06 -0700 Subject: [PATCH 090/101] DM: add use of e2e preds (#26078) * try ml * de56 * j914ef75a * jd1124586 * jd1124586 * d112 * oops * set * update ref * use offset * bump DM power usage * new ref --- .../modeld/models/dmonitoring_model.current | 4 ++-- .../modeld/models/dmonitoring_model.onnx | 4 ++-- .../modeld/models/dmonitoring_model_q.dlc | 4 ++-- selfdrive/monitoring/driver_monitor.py | 21 +++++++++---------- .../process_replay/model_replay_ref_commit | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- system/hardware/tici/test_power_draw.py | 2 +- 7 files changed, 19 insertions(+), 20 deletions(-) diff --git a/selfdrive/modeld/models/dmonitoring_model.current b/selfdrive/modeld/models/dmonitoring_model.current index d1e7d1136f..065bc7d489 100644 --- a/selfdrive/modeld/models/dmonitoring_model.current +++ b/selfdrive/modeld/models/dmonitoring_model.current @@ -1,2 +1,2 @@ -ee8f830b-d6a1-42ef-9b1b-50fd0b2faae4 -cac8f7b69d420506707ff7a19d573d5011ef2533 \ No newline at end of file +d1124586-761e-4e18-a771-6b5ef35124fe +6fec774f513a19e44d4316e46ad38277197d45ea \ No newline at end of file diff --git a/selfdrive/modeld/models/dmonitoring_model.onnx b/selfdrive/modeld/models/dmonitoring_model.onnx index 4cbd6bb7dd..f8bf94c061 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:932e589e5cce66e5d9f48492426a33c74cd7f352a870d3ddafcede3e9156f30d -size 9157561 +oid sha256:517262fa9f1ad3cc8049ad3722903f40356d87ea423ee5cf011226fb6cfc3d5b +size 16072278 diff --git a/selfdrive/modeld/models/dmonitoring_model_q.dlc b/selfdrive/modeld/models/dmonitoring_model_q.dlc index 94632030ed..e4e6fb3347 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:3587976a8b7e3be274fa86c2e2233e3e464cad713f5077c4394cd1ddd3c7c6c5 -size 2636965 +oid sha256:64b94659226a1e3c6594a13c2e5d029465d5803a5c3005121ec7217acdbbef20 +size 4443461 diff --git a/selfdrive/monitoring/driver_monitor.py b/selfdrive/monitoring/driver_monitor.py index 9ff3125c15..30781f4d1b 100644 --- a/selfdrive/monitoring/driver_monitor.py +++ b/selfdrive/monitoring/driver_monitor.py @@ -29,10 +29,10 @@ class DRIVER_MONITOR_SETTINGS(): self._FACE_THRESHOLD = 0.7 self._EYE_THRESHOLD = 0.65 self._SG_THRESHOLD = 0.9 - self._BLINK_THRESHOLD = 0.87 + self._BLINK_THRESHOLD = 0.895 - self._EE_THRESH11 = 0.75 - self._EE_THRESH12 = 3.25 + self._EE_THRESH11 = 0.275 + self._EE_THRESH12 = 3.0 self._EE_THRESH21 = 0.01 self._EE_THRESH22 = 0.35 @@ -207,11 +207,11 @@ class DriverStatus(): ee1_dist = self.eev1 > self.ee1_offseter.filtered_stat.M * self.settings._EE_THRESH12 else: ee1_dist = self.eev1 > self.settings._EE_THRESH11 - if self.ee2_calibrated: - ee2_dist = self.eev2 < self.ee2_offseter.filtered_stat.M * self.settings._EE_THRESH22 - else: - ee2_dist = self.eev2 < self.settings._EE_THRESH21 - if ee1_dist or ee2_dist: + # if self.ee2_calibrated: + # ee2_dist = self.eev2 < self.ee2_offseter.filtered_stat.M * self.settings._EE_THRESH22 + # else: + # ee2_dist = self.eev2 < self.settings._EE_THRESH21 + if ee1_dist: distracted_types.append(DistractedType.DISTRACTED_E2E) return distracted_types @@ -257,12 +257,11 @@ class DriverStatus(): 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.eev1 = driver_data.notReadyProb[0] 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 \ + self.driver_distracted = (DistractedType.DISTRACTED_E2E in self.distracted_types or 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 self.driver_distraction_filter.update(self.driver_distracted) diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index b3e9c8c488..5bb045ec29 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -bfb0a2a52212d2aa1619d999aaae97fa7f7ff788 +865885fc49b2766326568e5cc7ec06be8a3f6fad diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 864b7019a0..998bf4e756 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -e5a86c14e2318f2dd218b3985cdbea6f875f7d83 +6bb7d8baae51d88dd61f0baf561e386664ddd266 \ No newline at end of file diff --git a/system/hardware/tici/test_power_draw.py b/system/hardware/tici/test_power_draw.py index 4830975917..2460152998 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.15, atol=0.2), - Proc('dmonitoringmodeld', 0.35), + Proc('dmonitoringmodeld', 0.4), Proc('encoderd', 0.23), ] From 988fede1858486ec0679f208540a88533e9296e3 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 18 Oct 2022 12:00:07 +0800 Subject: [PATCH 091/101] cabana: reduce the padding in DetailsView (#26126) --- tools/cabana/binaryview.cc | 4 ++-- tools/cabana/signaledit.cc | 5 ++--- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/tools/cabana/binaryview.cc b/tools/cabana/binaryview.cc index 3b962b6de1..71175e783e 100644 --- a/tools/cabana/binaryview.cc +++ b/tools/cabana/binaryview.cc @@ -8,7 +8,7 @@ // BinaryView -const int CELL_HEIGHT = 35; +const int CELL_HEIGHT = 30; BinaryView::BinaryView(QWidget *parent) : QTableView(parent) { model = new BinaryViewModel(this); @@ -156,7 +156,7 @@ void BinarySelectionModel::select(const QItemSelection &selection, QItemSelectio BinaryItemDelegate::BinaryItemDelegate(QObject *parent) : QStyledItemDelegate(parent) { // cache fonts and color - small_font.setPointSize(7); + small_font.setPointSize(6); bold_font.setBold(true); highlight_color = QApplication::style()->standardPalette().color(QPalette::Active, QPalette::Highlight); } diff --git a/tools/cabana/signaledit.cc b/tools/cabana/signaledit.cc index b52f83dab6..7cace48402 100644 --- a/tools/cabana/signaledit.cc +++ b/tools/cabana/signaledit.cc @@ -85,18 +85,17 @@ SignalEdit::SignalEdit(int index, const QString &msg_id, const Signal &sig, QWid // title bar QHBoxLayout *title_layout = new QHBoxLayout(); icon = new QLabel(">"); - icon->setFixedSize(15, 30); icon->setStyleSheet("font-weight:bold"); title_layout->addWidget(icon); title = new ElidedLabel(this); title->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::MinimumExpanding); title->setText(QString("%1. %2").arg(index + 1).arg(sig_name)); title->setStyleSheet(QString("font-weight:bold; color:%1").arg(getColor(index))); - title_layout->addWidget(title); + title_layout->addWidget(title, 1); QPushButton *plot_btn = new QPushButton("📈"); plot_btn->setToolTip(tr("Show Plot")); - plot_btn->setFixedSize(30, 30); + plot_btn->setFixedSize(20, 20); QObject::connect(plot_btn, &QPushButton::clicked, this, &SignalEdit::showChart); title_layout->addWidget(plot_btn); main_layout->addLayout(title_layout); From b89b881bdccb0fb844c597e9d26b64d36ba4af99 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 18 Oct 2022 12:00:20 +0800 Subject: [PATCH 092/101] cabana: sort DBC list alphabetically (#26127) --- tools/cabana/messageswidget.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/tools/cabana/messageswidget.cc b/tools/cabana/messageswidget.cc index 3c9af67ea6..878a852e13 100644 --- a/tools/cabana/messageswidget.cc +++ b/tools/cabana/messageswidget.cc @@ -21,6 +21,7 @@ MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) { for (const auto &name : dbc_names) { combo->addItem(QString::fromStdString(name)); } + combo->model()->sort(0); combo->setEditable(true); combo->setCurrentText(QString()); combo->setInsertPolicy(QComboBox::NoInsert); From 544526edeb343d4b6f9c7c6f2521659c34d37012 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 18 Oct 2022 12:00:36 +0800 Subject: [PATCH 093/101] cabana: fix chart margins (#26125) --- tools/cabana/chartswidget.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index 3652720e12..811eae68cb 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -184,6 +184,7 @@ ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent) font.setBold(true); chart->setTitleFont(font); chart->setMargins({0, 0, 0, 0}); + chart->layout()->setContentsMargins(0, 0, 0, 0); track_line = new QGraphicsLineItem(chart); track_line->setPen(QPen(Qt::gray, 1, Qt::DashLine)); From 60fc7274eb631559f772ea0969e0ec28026e1426 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 17 Oct 2022 21:15:57 -0700 Subject: [PATCH 094/101] =?UTF-8?q?Hyundai=20CAN-FD:=20remove=2090=C2=B0?= =?UTF-8?q?=20steering=20lockout=20(#26045)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * bump panda * bump panda * for CAN-FD too * clean up * bump * adjust safety * fix lat active * bump panda to master * same limits * rm line * bump panda to master --- panda | 2 +- selfdrive/car/hyundai/carcontroller.py | 29 +++++++++++++------------- 2 files changed, 16 insertions(+), 15 deletions(-) diff --git a/panda b/panda index 62868c36a8..9ed3f75f67 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 62868c36a80d1f44064da7b47423f0ef331f64e9 +Subproject commit 9ed3f75f67c3e5f00f910c8d7497ebed63851b5a diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index a5d995df25..6b38297eb9 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -90,13 +90,27 @@ class CarController: addr, bus = 0x730, 5 can_sends.append([addr, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", bus]) + # >90 degree steering fault prevention + # Count up to MAX_ANGLE_FRAMES, at which point we need to cut torque to avoid a steering fault + if CC.latActive and abs(CS.out.steeringAngleDeg) >= MAX_ANGLE: + self.angle_limit_counter += 1 + else: + self.angle_limit_counter = 0 + + # Cut steer actuation bit for two frames and hold torque with induced temporary fault + torque_fault = CC.latActive and self.angle_limit_counter > MAX_ANGLE_FRAMES + lat_active = CC.latActive and not torque_fault + + if self.angle_limit_counter >= MAX_ANGLE_FRAMES + MAX_ANGLE_CONSECUTIVE_FRAMES: + self.angle_limit_counter = 0 + # CAN-FD platforms if self.CP.carFingerprint in CANFD_CAR: hda2 = self.CP.flags & HyundaiFlags.CANFD_HDA2 hda2_long = hda2 and self.CP.openpilotLongitudinalControl # steering control - can_sends.extend(hyundaicanfd.create_steering_messages(self.packer, self.CP, CC.enabled, CC.latActive, apply_steer)) + can_sends.extend(hyundaicanfd.create_steering_messages(self.packer, self.CP, CC.enabled, lat_active, apply_steer)) # disable LFA on HDA2 if self.frame % 5 == 0 and hda2: @@ -131,19 +145,6 @@ class CarController: can_sends.append(hyundaicanfd.create_buttons(self.packer, CS.buttons_counter+1, Buttons.RES_ACCEL)) self.last_button_frame = self.frame else: - # Count up to MAX_ANGLE_FRAMES, at which point we need to cut torque to avoid a steering fault - if CC.latActive and abs(CS.out.steeringAngleDeg) >= MAX_ANGLE: - self.angle_limit_counter += 1 - else: - self.angle_limit_counter = 0 - - # Cut steer actuation bit for two frames and hold torque with induced temporary fault - torque_fault = CC.latActive and self.angle_limit_counter > MAX_ANGLE_FRAMES - lat_active = CC.latActive and not torque_fault - - if self.angle_limit_counter >= MAX_ANGLE_FRAMES + MAX_ANGLE_CONSECUTIVE_FRAMES: - self.angle_limit_counter = 0 - can_sends.append(hyundaican.create_lkas11(self.packer, self.frame, self.car_fingerprint, apply_steer, lat_active, torque_fault, CS.lkas11, sys_warning, sys_state, CC.enabled, hud_control.leftLaneVisible, hud_control.rightLaneVisible, From 12058c21c73c7777e260334827b30f4d24c8313d Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 18 Oct 2022 12:44:56 +0800 Subject: [PATCH 095/101] cabana: load dbc from paste (#26098) --- opendbc | 2 +- tools/cabana/dbcmanager.cc | 12 ++++++++ tools/cabana/dbcmanager.h | 1 + tools/cabana/messageswidget.cc | 51 ++++++++++++++++++++++++++-------- tools/cabana/messageswidget.h | 13 +++++++++ 5 files changed, 66 insertions(+), 13 deletions(-) diff --git a/opendbc b/opendbc index dde0ff6f44..e37ef84f1a 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit dde0ff6f4456c167df204bf5ac1e3f2979c844c9 +Subproject commit e37ef84f1ab848e2bf37f2c755f9e56213ce14e2 diff --git a/tools/cabana/dbcmanager.cc b/tools/cabana/dbcmanager.cc index 5b1bddcabe..fc40fc58e4 100644 --- a/tools/cabana/dbcmanager.cc +++ b/tools/cabana/dbcmanager.cc @@ -1,5 +1,6 @@ #include "tools/cabana/dbcmanager.h" +#include #include DBCManager::DBCManager(QObject *parent) : QObject(parent) {} @@ -16,6 +17,17 @@ void DBCManager::open(const QString &dbc_file_name) { emit DBCFileChanged(); } +void DBCManager::open(const QString &name, const QString &content) { + this->dbc_name = name; + std::istringstream stream(content.toStdString()); + dbc = const_cast(dbc_parse_from_stream(name.toStdString(), stream)); + msg_map.clear(); + for (auto &msg : dbc->msgs) { + msg_map[msg.address] = &msg; + } + emit DBCFileChanged(); +} + void save(const QString &dbc_file_name) { // TODO: save DBC to file } diff --git a/tools/cabana/dbcmanager.h b/tools/cabana/dbcmanager.h index 1f890a39db..74d935119a 100644 --- a/tools/cabana/dbcmanager.h +++ b/tools/cabana/dbcmanager.h @@ -12,6 +12,7 @@ public: ~DBCManager(); void open(const QString &dbc_file_name); + void open(const QString &name, const QString &content); void save(const QString &dbc_file_name); void addSignal(const QString &id, const Signal &sig); diff --git a/tools/cabana/messageswidget.cc b/tools/cabana/messageswidget.cc index 878a852e13..28f79adad3 100644 --- a/tools/cabana/messageswidget.cc +++ b/tools/cabana/messageswidget.cc @@ -1,12 +1,13 @@ #include "tools/cabana/messageswidget.h" -#include #include +#include #include #include #include #include #include +#include #include #include "tools/cabana/dbcmanager.h" @@ -16,20 +17,23 @@ MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) { // DBC file selector QHBoxLayout *dbc_file_layout = new QHBoxLayout(); - QComboBox *combo = new QComboBox(this); + dbc_combo = new QComboBox(this); auto dbc_names = dbc()->allDBCNames(); for (const auto &name : dbc_names) { - combo->addItem(QString::fromStdString(name)); + dbc_combo->addItem(QString::fromStdString(name)); } - combo->model()->sort(0); - combo->setEditable(true); - combo->setCurrentText(QString()); - combo->setInsertPolicy(QComboBox::NoInsert); - combo->completer()->setCompletionMode(QCompleter::PopupCompletion); + dbc_combo->model()->sort(0); + dbc_combo->setEditable(true); + dbc_combo->setCurrentText(QString()); + dbc_combo->setInsertPolicy(QComboBox::NoInsert); + dbc_combo->completer()->setCompletionMode(QCompleter::PopupCompletion); QFont font; font.setBold(true); - combo->lineEdit()->setFont(font); - dbc_file_layout->addWidget(combo); + dbc_combo->lineEdit()->setFont(font); + dbc_file_layout->addWidget(dbc_combo); + + QPushButton *load_from_paste = new QPushButton(tr("Load from paste"), this); + dbc_file_layout->addWidget(load_from_paste); dbc_file_layout->addStretch(); QPushButton *save_btn = new QPushButton(tr("Save DBC"), this); @@ -64,7 +68,8 @@ MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) { // signals/slots QObject::connect(filter, &QLineEdit::textChanged, proxy_model, &QSortFilterProxyModel::setFilterFixedString); QObject::connect(can, &CANMessages::updated, model, &MessageListModel::updateState); - QObject::connect(combo, SIGNAL(activated(const QString &)), SLOT(dbcSelectionChanged(const QString &))); + QObject::connect(dbc_combo, SIGNAL(activated(const QString &)), SLOT(dbcSelectionChanged(const QString &))); + QObject::connect(load_from_paste, &QPushButton::clicked, this, &MessagesWidget::loadFromPaste); QObject::connect(save_btn, &QPushButton::clicked, [=]() { // TODO: save DBC to file }); @@ -75,7 +80,7 @@ MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) { }); // For test purpose - combo->setCurrentText("toyota_nodsu_pt_generated"); + dbc_combo->setCurrentText("toyota_nodsu_pt_generated"); } void MessagesWidget::dbcSelectionChanged(const QString &dbc_file) { @@ -84,6 +89,14 @@ void MessagesWidget::dbcSelectionChanged(const QString &dbc_file) { table_widget->sortByColumn(0, Qt::AscendingOrder); } +void MessagesWidget::loadFromPaste() { + LoadDBCDialog dlg(this); + if (dlg.exec()) { + dbc()->open("from paste", dlg.dbc_edit->toPlainText()); + dbc_combo->setCurrentText("loaded from paste"); + } +} + // MessageListModel QVariant MessageListModel::headerData(int section, Qt::Orientation orientation, int role) const { @@ -133,3 +146,17 @@ void MessageListModel::updateState() { emit dataChanged(index(0, 0), index(row_count - 1, 3), {Qt::DisplayRole}); } } + +LoadDBCDialog::LoadDBCDialog(QWidget *parent) : QDialog(parent) { + QVBoxLayout *main_layout = new QVBoxLayout(this); + dbc_edit = new QTextEdit(this); + dbc_edit->setAcceptRichText(false); + dbc_edit->setPlaceholderText(tr("paste DBC file here")); + main_layout->addWidget(dbc_edit); + auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); + main_layout->addWidget(buttonBox); + + setFixedWidth(640); + connect(buttonBox, &QDialogButtonBox::accepted, this, &QDialog::accept); + connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); +} diff --git a/tools/cabana/messageswidget.h b/tools/cabana/messageswidget.h index f6487ba2bd..1184772f3b 100644 --- a/tools/cabana/messageswidget.h +++ b/tools/cabana/messageswidget.h @@ -1,10 +1,21 @@ #pragma once #include +#include +#include #include +#include #include "tools/cabana/canmessages.h" +class LoadDBCDialog : public QDialog { + Q_OBJECT + +public: + LoadDBCDialog(QWidget *parent); + QTextEdit *dbc_edit; +}; + class MessageListModel : public QAbstractTableModel { Q_OBJECT @@ -28,11 +39,13 @@ public: public slots: void dbcSelectionChanged(const QString &dbc_file); + void loadFromPaste(); signals: void msgSelectionChanged(const QString &message_id); protected: QTableView *table_widget; + QComboBox *dbc_combo; MessageListModel *model; }; From dcd804e2bfe2c29287749eb5777ced5a641c5e62 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 17 Oct 2022 22:47:54 -0700 Subject: [PATCH 096/101] bump opendbc --- opendbc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc b/opendbc index e37ef84f1a..8f245e6ef5 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit e37ef84f1ab848e2bf37f2c755f9e56213ce14e2 +Subproject commit 8f245e6ef5e25814d8e6e1f096221f6dfeefe86b From 7bf70bf7d8aaccd23ad0b0a9af8235eb939a617e Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 17 Oct 2022 23:04:06 -0700 Subject: [PATCH 097/101] CAN-FD HKG: query FW versions from camera (#26063) * add adas essential ecus * add adas ecu and query * add queries * add name * after * presence of adas ecu * Revert "presence of adas ecu" (POC) This reverts commit ab88a7e7df32e1c02a175b81848bd4112b2e5c69. * no whitelist for debugging * Apply suggestions from code review * add adas response * remove adas version * temp * read pandaStates * works in debug script * only fwdCamera on tucson * fix pandaStates reading * fix test_startup * fix * simpler * use existing socket * pass in number of pandas * need to create sm using outcome of fingerprinting, which uses sm fix * move default argument * use sock * always ignore always ignore * add canfd fingerprint test * Update selfdrive/car/hyundai/tests/test_hyundai.py * set --- selfdrive/car/car_helpers.py | 8 ++-- selfdrive/car/fw_versions.py | 14 +++++-- selfdrive/car/hyundai/tests/test_hyundai.py | 29 ++++++++++++++ selfdrive/car/hyundai/values.py | 42 +++++++-------------- selfdrive/controls/controlsd.py | 30 +++++++-------- selfdrive/controls/tests/test_startup.py | 3 ++ 6 files changed, 74 insertions(+), 52 deletions(-) create mode 100755 selfdrive/car/hyundai/tests/test_hyundai.py diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 4a8fd5fbd9..61e7a3d55d 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -76,7 +76,7 @@ interfaces = load_interfaces(interface_names) # **** for use live only **** -def fingerprint(logcan, sendcan): +def fingerprint(logcan, sendcan, num_pandas): fixed_fingerprint = os.environ.get('FINGERPRINT', "") skip_fw_query = os.environ.get('SKIP_FW_QUERY', False) ecu_rx_addrs = set() @@ -100,7 +100,7 @@ def fingerprint(logcan, sendcan): cloudlog.warning("Getting VIN & FW versions") 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) + car_fw = get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs, num_pandas=num_pandas) cached = False exact_fw_match, fw_candidates = match_fw_to_car(car_fw) @@ -173,8 +173,8 @@ def fingerprint(logcan, sendcan): return car_fingerprint, finger, vin, car_fw, source, exact_match -def get_car(logcan, sendcan): - candidate, fingerprints, vin, car_fw, source, exact_match = fingerprint(logcan, sendcan) +def get_car(logcan, sendcan, num_pandas=1): + candidate, fingerprints, vin, car_fw, source, exact_match = fingerprint(logcan, sendcan, num_pandas) if candidate is None: cloudlog.warning("car doesn't match any fingerprints: %r", fingerprints) diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index d3e8eae0de..f4d92ab960 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -194,14 +194,14 @@ def get_brand_ecu_matches(ecu_rx_addrs): return brand_matches -def get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs, timeout=0.1, debug=False, progress=False): +def get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs, timeout=0.1, num_pandas=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, query_brand=brand, timeout=timeout, debug=debug, progress=progress) + car_fw = get_fw_versions(logcan, sendcan, query_brand=brand, timeout=timeout, num_pandas=num_pandas, debug=debug, progress=progress) all_car_fw.extend(car_fw) # Try to match using FW returned from this brand only matches = match_fw_to_car_exact(build_fw_dict(car_fw)) @@ -211,7 +211,7 @@ 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, query_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, num_pandas=1, debug=False, progress=False): versions = VERSIONS.copy() # Each brand can define extra ECUs to query for data collection @@ -252,6 +252,10 @@ def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1, for addr in tqdm(addrs, disable=not progress): for addr_chunk in chunks(addr): for brand, r in requests: + # Skip query if no panda available + if r.bus > num_pandas * 4 - 1: + continue + try: addrs = [(a, s) for (b, a, s) in addr_chunk if b in (brand, 'any') and (len(r.whitelist_ecus) == 0 or ecu_types[(b, a, s)] in r.whitelist_ecus)] @@ -292,6 +296,7 @@ if __name__ == "__main__": args = parser.parse_args() logcan = messaging.sub_sock('can') + pandaStates_sock = messaging.sub_sock('pandaStates') sendcan = messaging.pub_sock('sendcan') extra: Any = None @@ -305,6 +310,7 @@ if __name__ == "__main__": extra = {"any": {"debug": extra}} time.sleep(1.) + num_pandas = len(messaging.recv_one_retry(pandaStates_sock).pandaStates) t = time.time() print("Getting vin...") @@ -314,7 +320,7 @@ if __name__ == "__main__": print() t = time.time() - fw_vers = get_fw_versions(logcan, sendcan, query_brand=args.brand, extra=extra, debug=args.debug, progress=True) + fw_vers = get_fw_versions(logcan, sendcan, query_brand=args.brand, extra=extra, num_pandas=num_pandas, debug=args.debug, progress=True) _, candidates = match_fw_to_car(fw_vers) print() diff --git a/selfdrive/car/hyundai/tests/test_hyundai.py b/selfdrive/car/hyundai/tests/test_hyundai.py new file mode 100755 index 0000000000..a52027f448 --- /dev/null +++ b/selfdrive/car/hyundai/tests/test_hyundai.py @@ -0,0 +1,29 @@ +#!/usr/bin/env python3 +import unittest + +from cereal import car +from selfdrive.car.car_helpers import get_interface_attr +from selfdrive.car.fw_versions import FW_QUERY_CONFIGS +from selfdrive.car.hyundai.values import CANFD_CAR + +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 TestHyundaiFingerprint(unittest.TestCase): + def test_auxiliary_request_ecu_whitelist(self): + # Asserts only auxiliary Ecus can exist in database for CAN-FD cars + config = FW_QUERY_CONFIGS['hyundai'] + whitelisted_ecus = {ecu for r in config.requests for ecu in r.whitelist_ecus if r.bus > 3} + + for car_model in CANFD_CAR: + ecus = {fw[0] for fw in VERSIONS['hyundai'][car_model].keys()} + ecus_not_in_whitelist = ecus - whitelisted_ecus + ecu_strings = ", ".join([f'Ecu.{ECU_NAME[ecu]}' for ecu in ecus_not_in_whitelist]) + self.assertEqual(len(ecus_not_in_whitelist), 0, f'{car_model}: Car model has ECUs not in auxiliary request whitelists: {ecu_strings}') + + +if __name__ == "__main__": + unittest.main() diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 856bf1abd9..1599005d1c 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -300,6 +300,19 @@ FW_QUERY_CONFIG = FwQueryConfig( [HYUNDAI_VERSION_RESPONSE], whitelist_ecus=[Ecu.engine, Ecu.transmission, Ecu.eps, Ecu.abs, Ecu.fwdRadar], ), + # CAN-FD queries + Request( + [HYUNDAI_VERSION_REQUEST_LONG], + [HYUNDAI_VERSION_RESPONSE], + whitelist_ecus=[Ecu.fwdRadar], + bus=4, + ), + Request( + [HYUNDAI_VERSION_REQUEST_LONG], + [HYUNDAI_VERSION_RESPONSE], + whitelist_ecus=[Ecu.fwdCamera, Ecu.adas], + bus=5, + ), ], extra_ecus=[ (Ecu.adas, 0x730, None), # ADAS Driving ECU on HDA2 platforms @@ -1326,15 +1339,6 @@ FW_VERSIONS = { ], }, CAR.KIA_EV6: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00CV IEB \x02 101!\x10\x18 58520-CV100', - b'\xf1\x00CV IEB \x03 101!\x10\x18 58520-CV100', - b'\xf1\x8758520CV100\xf1\x00CV IEB \x02 101!\x10\x18 58520-CV100', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CV1 MDPS R 1.00 1.04 57700-CV000 1B30', - b'\xf1\x00CV1 MDPS R 1.00 1.05 57700-CV000 2425', - ], (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 ', b'\xf1\x8799110CV000\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 ', @@ -1346,16 +1350,6 @@ FW_VERSIONS = { ], }, CAR.IONIQ_5: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00NE1 IEB \x07 106!\x11) 58520-GI010', - b'\xf1\x8758520GI010\xf1\x00NE1 IEB \x07 106!\x11) 58520-GI010', - b'\xf1\x00NE1 IEB \x08 104!\x04\x05 58520-GI000', - b'\xf1\x8758520GI000\xf1\x00NE1 IEB \x08 104!\x04\x05 58520-GI000', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00NE MDPS R 1.00 1.06 57700GI000 4NEDR106', - b'\xf1\x8757700GI000 \xf1\x00NE MDPS R 1.00 1.06 57700GI000 4NEDR106', - ], (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00NE1_ RDR ----- 1.00 1.00 99110-GI000 ', b'\xf1\x8799110GI000\xf1\x00NE1_ RDR ----- 1.00 1.00 99110-GI000 ', @@ -1369,16 +1363,6 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9240 14Q', ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00NX4 MDPS C 1.00 1.01 56300-P0100 2228', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x87391312MND0', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x00PSBG2441 G19_Rev\x00\x00\x00SNX4T16XXHS01NS2lS\xdfa', - b'\xf1\x8795441-3D220\x00\xf1\x81G19_Rev\x00\x00\x00\xf1\x00PSBG2441 G19_Rev\x00\x00\x00SNX4T16XXHS01NS2lS\xdfa', - ], }, } diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 8abb1a02a6..cbc54eadb8 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -82,30 +82,30 @@ class Controls: self.log_sock = messaging.sub_sock('androidLog') - if CI is None: - # wait for one pandaState and one CAN packet - print("Waiting for CAN messages...") - get_one_can(self.can_sock) - - self.CI, self.CP = get_car(self.can_sock, self.pm.sock['sendcan']) - else: - self.CI, self.CP = CI, CI.CP - params = Params() - self.joystick_mode = params.get_bool("JoystickDebugMode") or (self.CP.notCar and sm is None) - joystick_packet = ['testJoystick'] if self.joystick_mode else [] - self.sm = sm if self.sm is None: - ignore = [] + ignore = ['testJoystick'] if SIMULATION: ignore += ['driverCameraState', 'managerState'] if params.get_bool('WideCameraOnly'): ignore += ['roadCameraState'] self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', 'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman', - 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters'] + self.camera_packets + joystick_packet, - ignore_alive=ignore, ignore_avg_freq=['radarState', 'longitudinalPlan']) + 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', 'testJoystick'] + self.camera_packets, + ignore_alive=ignore, ignore_avg_freq=['radarState', 'longitudinalPlan', 'testJoystick']) + + if CI is None: + # wait for one pandaState and one CAN packet + print("Waiting for CAN messages...") + get_one_can(self.can_sock) + + num_pandas = len(messaging.recv_one_retry(self.sm.sock['pandaStates']).pandaStates) + self.CI, self.CP = get_car(self.can_sock, self.pm.sock['sendcan'], num_pandas) + else: + self.CI, self.CP = CI, CI.CP + + self.joystick_mode = params.get_bool("JoystickDebugMode") or (self.CP.notCar and sm is None) # set alternative experiences from parameters self.disengage_on_accelerator = params.get_bool("DisengageOnAccelerator") diff --git a/selfdrive/controls/tests/test_startup.py b/selfdrive/controls/tests/test_startup.py index 63af4c7d95..ba2d2f5c02 100755 --- a/selfdrive/controls/tests/test_startup.py +++ b/selfdrive/controls/tests/test_startup.py @@ -94,6 +94,9 @@ class TestStartup(unittest.TestCase): time.sleep(2) # wait for controlsd to be ready + pm.send('can', can_list_to_can_capnp([[0, 0, b"", 0]])) + time.sleep(0.1) + msg = messaging.new_message('pandaStates', 1) msg.pandaStates[0].pandaType = log.PandaState.PandaType.uno pm.send('pandaStates', msg) From 5b85c2df4e2d855dc8fcb572bda33d2d456841d9 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 17 Oct 2022 23:24:34 -0700 Subject: [PATCH 098/101] Tucson Hybrid 4th gen: add missing fwdRadar (#26128) add missing fwdRadar --- selfdrive/car/hyundai/values.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 1599005d1c..f69273ba55 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1363,6 +1363,9 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9240 14Q', ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00NX4__ 1.00 1.00 99110-N9100 ', + ], }, } From a121212386c94ea5cc93de68b49971ff4e9d5674 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 19 Oct 2022 02:01:21 +0800 Subject: [PATCH 099/101] cabana: fix background refresh issue (#26134) --- tools/cabana/mainwin.cc | 2 -- 1 file changed, 2 deletions(-) diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc index 7aea8097cf..f3c3bf74ae 100644 --- a/tools/cabana/mainwin.cc +++ b/tools/cabana/mainwin.cc @@ -48,7 +48,6 @@ MainWindow::MainWindow() : QWidget() { } void MainWindow::dockCharts(bool dock) { - charts_widget->setUpdatesEnabled(false); if (dock && floating_window) { floating_window->removeEventFilter(charts_widget); r_layout->addWidget(charts_widget); @@ -62,7 +61,6 @@ void MainWindow::dockCharts(bool dock) { floating_window->setMinimumSize(QGuiApplication::primaryScreen()->size() / 2); floating_window->showMaximized(); } - charts_widget->setUpdatesEnabled(true); } void MainWindow::closeEvent(QCloseEvent *event) { From 855099eb86938d683bb58868697c038b7b7ac650 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 19 Oct 2022 02:01:38 +0800 Subject: [PATCH 100/101] cabana: display fingerprint and route on the top right (#26133) --- tools/cabana/canmessages.cc | 3 ++- tools/cabana/canmessages.h | 3 +++ tools/cabana/mainwin.cc | 11 ++++++++++- tools/cabana/videowidget.cc | 1 + 4 files changed, 16 insertions(+), 2 deletions(-) diff --git a/tools/cabana/canmessages.cc b/tools/cabana/canmessages.cc index 3cf08eaaa0..252a8c680c 100644 --- a/tools/cabana/canmessages.cc +++ b/tools/cabana/canmessages.cc @@ -26,7 +26,8 @@ static bool event_filter(const Event *e, void *opaque) { } bool CANMessages::loadRoute(const QString &route, const QString &data_dir, bool use_qcam) { - replay = new Replay(route, {"can", "roadEncodeIdx"}, {}, nullptr, use_qcam ? REPLAY_FLAG_QCAMERA : 0, data_dir, this); + routeName = route; + replay = new Replay(route, {"can", "roadEncodeIdx", "carParams"}, {}, nullptr, use_qcam ? REPLAY_FLAG_QCAMERA : 0, data_dir, this); replay->setSegmentCacheLimit(settings.cached_segment_limit); replay->installEventFilter(event_filter, this); QObject::connect(replay, &Replay::segmentsMerged, this, &CANMessages::segmentsMerged); diff --git a/tools/cabana/canmessages.h b/tools/cabana/canmessages.h index fe71840d74..58f5ad70b7 100644 --- a/tools/cabana/canmessages.h +++ b/tools/cabana/canmessages.h @@ -44,6 +44,8 @@ public: bool eventFilter(const Event *event); inline std::pair range() const { return {begin_sec, end_sec}; } + inline QString route() const { return routeName; } + inline QString carFingerprint() const { return replay->carFingerprint().c_str(); } inline double totalSeconds() const { return replay->totalSeconds(); } inline double routeStartTime() const { return replay->routeStartTime() / (double)1e9; } inline double currentSec() const { return current_sec; } @@ -80,6 +82,7 @@ protected: double event_begin_sec = 0; double event_end_sec = 0; bool is_zoomed = false; + QString routeName; Replay *replay = nullptr; }; diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc index f3c3bf74ae..50fcbc455c 100644 --- a/tools/cabana/mainwin.cc +++ b/tools/cabana/mainwin.cc @@ -30,8 +30,16 @@ MainWindow::MainWindow() : QWidget() { right_container->setFixedWidth(640); r_layout = new QVBoxLayout(right_container); + QHBoxLayout *right_hlayout = new QHBoxLayout(); + QLabel *fingerprint_label = new QLabel(this); + right_hlayout->addWidget(fingerprint_label); + + // TODO: click to select another route. + right_hlayout->addWidget(new QLabel(can->route())); QPushButton *settings_btn = new QPushButton("Settings"); - r_layout->addWidget(settings_btn, 0, Qt::AlignRight); + right_hlayout->addWidget(settings_btn, 0, Qt::AlignRight); + + r_layout->addLayout(right_hlayout); video_widget = new VideoWidget(this); r_layout->addWidget(video_widget, 0, Qt::AlignTop); @@ -45,6 +53,7 @@ MainWindow::MainWindow() : QWidget() { QObject::connect(detail_widget, &DetailWidget::showChart, charts_widget, &ChartsWidget::addChart); QObject::connect(charts_widget, &ChartsWidget::dock, this, &MainWindow::dockCharts); QObject::connect(settings_btn, &QPushButton::clicked, this, &MainWindow::setOption); + QObject::connect(can, &CANMessages::eventsMerged, [=]() { fingerprint_label->setText(can->carFingerprint() ); }); } void MainWindow::dockCharts(bool dock) { diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc index bb90d56570..78965e3e8c 100644 --- a/tools/cabana/videowidget.cc +++ b/tools/cabana/videowidget.cc @@ -15,6 +15,7 @@ inline QString formatTime(int seconds) { VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) { QVBoxLayout *main_layout = new QVBoxLayout(this); + main_layout->setContentsMargins(0, 0, 0, 0); // TODO: figure out why the CameraWidget crashed occasionally. cam_widget = new CameraWidget("camerad", VISION_STREAM_ROAD, false, this); From 826d8a8ae34bfd909535f5edff2229b8b2daf1a6 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 18 Oct 2022 11:24:13 -0700 Subject: [PATCH 101/101] GM: match panda & ECM standstill checks (#26095) * gm: match panda standstill check * fix * needs to be <= 10 to avoid a fault, fix for safety tests * fix * fix * bump panda to master --- panda | 2 +- selfdrive/car/gm/carstate.py | 4 +++- selfdrive/car/tests/test_models.py | 2 +- 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/panda b/panda index 9ed3f75f67..b95a65df58 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 9ed3f75f67c3e5f00f910c8d7497ebed63851b5a +Subproject commit b95a65df58fea89b42b7c6b4fc85289b93a0bdb2 diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index b67b97093a..f531914877 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -8,6 +8,7 @@ from selfdrive.car.gm.values import DBC, AccState, CanBus, STEER_THRESHOLD TransmissionType = car.CarParams.TransmissionType NetworkLocation = car.CarParams.NetworkLocation +STANDSTILL_THRESHOLD = 10 * 0.0311 * CV.KPH_TO_MS class CarState(CarStateBase): @@ -39,7 +40,8 @@ class CarState(CarStateBase): ) ret.vEgoRaw = mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr]) ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.vEgoRaw < 0.01 + # sample rear wheel speeds, standstill=True if ECM allows engagement with brake + ret.standstill = ret.wheelSpeeds.rl <= STANDSTILL_THRESHOLD and ret.wheelSpeeds.rr <= STANDSTILL_THRESHOLD if pt_cp.vl["ECMPRDNL2"]["ManualMode"] == 1: ret.gearShifter = self.parse_gear_shifter("T") diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index bab9f859e6..e4e141153f 100755 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -234,7 +234,7 @@ class TestCarModelBase(unittest.TestCase): checks['gasPressed'] += CS.gasPressed != self.safety.get_gas_pressed_prev() checks['cruiseState'] += CS.cruiseState.enabled and not CS.cruiseState.available - if self.CP.carName not in ("hyundai", "volkswagen", "gm", "body"): + if self.CP.carName not in ("hyundai", "volkswagen", "body"): # TODO: fix standstill mismatches for other makes checks['standstill'] += CS.standstill == self.safety.get_vehicle_moving()