This commit is contained in:
Your Name
2024-05-18 00:32:24 -05:00
parent 52b6f7abea
commit 41b4f73622
8 changed files with 194 additions and 69 deletions

View File

@@ -435,14 +435,20 @@ void AnnotatedCameraWidget::drawHud(QPainter &p) {
// QString speedLimitStr = (speedLimit > 1) ? QString::number(std::nearbyint(speedLimit)) : "";
// QString speedLimitOffsetStr = slcSpeedLimitOffset == 0 ? "" : QString::number(slcSpeedLimitOffset, 'f', 0).prepend(slcSpeedLimitOffset > 0 ? "+" : "");
// QString speedStr = QString::number(std::nearbyint(speed));
// QString setSpeedStr = is_cruise_set ? QString::number(std::nearbyint(setSpeed - cruiseAdjustment)) : "";
QString speedStr = QString::number(std::nearbyint(speed));
QString setSpeedStr = is_cruise_set ? QString::number(std::nearbyint(setSpeed - cruiseAdjustment)) : "";
p.restore();
if (!scene.hide_max_speed) {
// drawSpeedWidget(p, 60, 45, QString("MAX"), QString("33"), QColor(0xff, 0xff, 0xff));
}
// if (!scene.hide_max_speed) {
drawSpeedWidget(p, 60, 45, QString("MAX"), setSpeedStr, QColor(0xff, 0xff, 0xff));
// }
QString speedLimitStr = QString::fromStdString(paramsMemory.get());
drawSpeedWidget(p, 60, 45 + (225), QString("Limit"), CarSpeedLimitLiteral, QColor(0xff, 0xff, 0xff));
// Todo: lead speed
// Todo: Experimental speed
// Draw FrogPilot widgets
paintFrogPilotWidgets(p);
@@ -505,46 +511,46 @@ void AnnotatedCameraWidget::drawHud(QPainter &p) {
// }
void AnnotatedCameraWidget::drawSpeedWidget(QPainter &p, int x, int y, const QString &title, const QString &speedLimitStr, QColor colorSpeed) {
// Draw outer box + border to contain set speed and speed limit
const int sign_margin = 12;
const int us_sign_height = 186;
const int eu_sign_size = 176;
// Draw outer box + border to contain set speed and speed limit
const int sign_margin = 12;
const int us_sign_height = 186;
const int eu_sign_size = 176;
const QSize default_size = {172, 204};
QSize set_speed_size = default_size;
if (is_metric || has_eu_speed_limit) set_speed_size.rwidth() = 200;
if (has_us_speed_limit && speedLimitStr.size() >= 3) set_speed_size.rwidth() = 223;
const QSize default_size = {172, 204};
QSize set_speed_size = default_size;
if (is_metric || has_eu_speed_limit) set_speed_size.rwidth() = 200;
if (has_us_speed_limit && speedLimitStr.size() >= 3) set_speed_size.rwidth() = 223;
if (has_us_speed_limit) set_speed_size.rheight() += us_sign_height + sign_margin;
else if (has_eu_speed_limit) set_speed_size.rheight() += eu_sign_size + sign_margin;
if (has_us_speed_limit) set_speed_size.rheight() += us_sign_height + sign_margin;
else if (has_eu_speed_limit) set_speed_size.rheight() += eu_sign_size + sign_margin;
int top_radius = 32;
int bottom_radius = has_eu_speed_limit ? 100 : 32;
int top_radius = 32;
int bottom_radius = has_eu_speed_limit ? 100 : 32;
QRect set_speed_rect(QPoint(x + (default_size.width() - set_speed_size.width()) / 2, y), set_speed_size);
p.setPen(QPen(colorSpeed));
p.setBrush(blackColor(166));
drawRoundedRect(p, set_speed_rect, top_radius, top_radius, bottom_radius, bottom_radius);
QRect set_speed_rect(QPoint(x + (default_size.width() - set_speed_size.width()) / 2, y), set_speed_size);
p.setPen(QPen(colorSpeed));
p.setBrush(blackColor(166));
drawRoundedRect(p, set_speed_rect, top_radius, top_radius, bottom_radius, bottom_radius);
// Draw MAX
QColor max_color = QColor(0xaa, 0xaa, 0xaa, 0xff);
p.setFont(InterFont(40, QFont::DemiBold));
p.setPen(max_color);
p.drawText(set_speed_rect.adjusted(0, 27, 0, 0), Qt::AlignTop | Qt::AlignHCenter, title);
p.setFont(InterFont(90, QFont::Bold));
p.setPen(colorSpeed);
p.drawText(set_speed_rect.adjusted(0, 77, 0, 0), Qt::AlignTop | Qt::AlignHCenter, speedLimitStr);
// Draw MAX
QColor max_color = QColor(0xaa, 0xaa, 0xaa, 0xff);
p.setFont(InterFont(40, QFont::DemiBold));
p.setPen(max_color);
p.drawText(set_speed_rect.adjusted(0, 27, 0, 0), Qt::AlignTop | Qt::AlignHCenter, title);
p.setFont(InterFont(90, QFont::Bold));
p.setPen(colorSpeed);
p.drawText(set_speed_rect.adjusted(0, 77, 0, 0), Qt::AlignTop | Qt::AlignHCenter, speedLimitStr);
// // current speed
// if (!(scene.hide_speed)) {
// // CLEARPILOT changes to 120 from ~176
// // Maybe we want to hide this?
// p.setFont(InterFont(140, QFont::Bold));
// drawText(p, rect().center().x(), 210, speedStr);
// // CLEARPILOT changes to 40 from 66
// p.setFont(InterFont(50));
// drawText(p, rect().center().x(), 290, speedUnit, 200);
// }
if (!(scene.hide_speed)) {
// CLEARPILOT changes to 120 from ~176
// Maybe we want to hide this?
p.setFont(InterFont(140, QFont::Bold));
drawText(p, rect().center().x(), 210, speedStr);
// CLEARPILOT changes to 40 from 66
p.setFont(InterFont(50));
drawText(p, rect().center().x(), 290, speedUnit, 200);
}
}
void AnnotatedCameraWidget::drawText(QPainter &p, int x, int y, const QString &text, int alpha) {
@@ -608,13 +614,16 @@ void AnnotatedCameraWidget::drawLaneLines(QPainter &painter, const UIState *s) {
int is_no_lat_lane_change = paramsMemory.getInt("no_lat_lane_change");
QColor center_lane_color = is_no_lat_lane_change ?
bg_colors[CENTER_LANE_COLOR] :
bg_colors[CHANGE_LANE_PATH_COLOR];
QColor center_lane_color;
if (is_no_lat_lane_change) {
center_lane_color = bg_colors[CENTER_LANE_COLOR];
} else {
center_lane_color = bg_colors[CHANGE_LANE_PATH_COLOR];
}
QLinearGradient path_gradient(0, height(), 0, 0);
if (edgeColor != bg_colors[STATUS_DISENGAGED] || is_no_lat_lane_change) {
if (scene.acceleration_path) {
// The first half of track_vertices are the points for the right side of the path