From 159f53d20c25640b48c6a08d873ecde7ebad5a4f Mon Sep 17 00:00:00 2001 From: FrogAi <91348155+FrogAi@users.noreply.github.com> Date: Sun, 12 May 2024 20:29:13 -0700 Subject: [PATCH] Visuals - Custom Onroad UI - Steering Wheel Icon - Live Rotation --- selfdrive/ui/qt/onroad.cc | 18 +++++++++++++++--- selfdrive/ui/qt/onroad.h | 3 +++ selfdrive/ui/ui.cc | 2 ++ selfdrive/ui/ui.h | 2 ++ 4 files changed, 22 insertions(+), 3 deletions(-) diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 245a460..a39b7e0 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -18,15 +18,19 @@ #include "selfdrive/ui/qt/maps/map_panel.h" #endif -static void drawIcon(QPainter &p, const QPoint ¢er, const QPixmap &img, const QBrush &bg, float opacity) { +static void drawIcon(QPainter &p, const QPoint ¢er, const QPixmap &img, const QBrush &bg, float opacity, const int angle = 0) { p.setRenderHint(QPainter::Antialiasing); p.setOpacity(1.0); // bg dictates opacity of ellipse p.setPen(Qt::NoPen); p.setBrush(bg); p.drawEllipse(center, btn_size / 2, btn_size / 2); + p.save(); + p.translate(center); + p.rotate(angle); p.setOpacity(opacity); - p.drawPixmap(center - QPoint(img.width() / 2, img.height() / 2), img); + p.drawPixmap(-QPoint(img.width() / 2, img.height() / 2), img); p.setOpacity(1.0); + p.restore(); } OnroadWindow::OnroadWindow(QWidget *parent) : QWidget(parent), scene(uiState()->scene) { @@ -318,7 +322,15 @@ void ExperimentalButton::updateState(const UIState &s) { } // FrogPilot variables + rotatingWheel = scene.rotating_wheel; wheelIcon = scene.wheel_icon; + + if (rotatingWheel && steeringAngleDeg != scene.steering_angle_deg) { + update(); + steeringAngleDeg = scene.steering_angle_deg; + } else if (!rotatingWheel) { + steeringAngleDeg = 0; + } } void ExperimentalButton::paintEvent(QPaintEvent *event) { @@ -338,7 +350,7 @@ void ExperimentalButton::paintEvent(QPaintEvent *event) { (scene.navigate_on_openpilot ? bg_colors[STATUS_NAVIGATION_ACTIVE] : QColor(0, 0, 0, 166)))))) : QColor(0, 0, 0, 166); - drawIcon(p, QPoint(btn_size / 2, btn_size / 2), img, QColor(0, 0, 0, 166), (isDown() || !engageable) ? 0.6 : 1.0); + drawIcon(p, QPoint(btn_size / 2, btn_size / 2), img, QColor(0, 0, 0, 166), (isDown() || !engageable) ? 0.6 : 1.0, steeringAngleDeg); } diff --git a/selfdrive/ui/qt/onroad.h b/selfdrive/ui/qt/onroad.h index 3ed13ea..e7553fe 100644 --- a/selfdrive/ui/qt/onroad.h +++ b/selfdrive/ui/qt/onroad.h @@ -107,6 +107,9 @@ private: QMap wheelImages; + bool rotatingWheel; + + int steeringAngleDeg; int wheelIcon; }; diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index ffdfb6b..52cd70a 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -224,6 +224,7 @@ static void update_state(UIState *s) { scene.blind_spot_right = carState.getRightBlindspot(); scene.parked = carState.getGearShifter() == cereal::CarState::GearShifter::PARK; scene.standstill = carState.getStandstill(); + scene.steering_angle_deg = -carState.getSteeringAngleDeg(); } if (sm.updated("controlsState")) { auto controlsState = sm["controlsState"].getControlsState(); @@ -310,6 +311,7 @@ void ui_update_frogpilot_params(UIState *s) { scene.dynamic_pedals_on_ui = scene.pedals_on_ui && params.getBool("DynamicPedalsOnUI"); scene.static_pedals_on_ui = scene.pedals_on_ui && params.getBool("StaticPedalsOnUI"); scene.road_name_ui = custom_onroad_ui && params.getBool("RoadNameUI"); + scene.rotating_wheel = custom_onroad_ui && params.getBool("RotatingWheel"); scene.wheel_icon = custom_onroad_ui ? params.getInt("WheelIcon") : 0; scene.disable_smoothing_mtsc = params.getBool("MTSCEnabled") && params.getBool("DisableMTSCSmoothing"); diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index 665f382..6153e76 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -211,6 +211,7 @@ typedef struct UIScene { bool reverse_cruise_ui; bool right_hand_drive; bool road_name_ui; + bool rotating_wheel; bool show_aol_status_bar; bool show_cem_status_bar; bool show_slc_offset; @@ -242,6 +243,7 @@ typedef struct UIScene { int conditional_speed; int conditional_speed_lead; int conditional_status; + int steering_angle_deg; int wheel_icon; QPolygonF track_adjacent_vertices[6];