Skip to content

Commit ca36fa7

Browse files
KhalilSelyankarishma1911
authored andcommitted
feat: update rviz2 overlay (autowarefoundation#6883)
Signed-off-by: KhalilSelyan <khalil@leodrive.ai>
1 parent e39282d commit ca36fa7

File tree

8 files changed

+54
-50
lines changed

8 files changed

+54
-50
lines changed

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/turn_signals_display.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ class TurnSignalsDisplay
4747

4848
private:
4949
QImage arrowImage;
50-
QColor gray = QColor(46, 46, 46);
50+
QColor gray = QColor(79, 79, 79);
5151

5252
int current_turn_signal_; // Internal variable to store turn signal state
5353
int current_hazard_lights_; // Internal variable to store hazard lights state

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/gear_display.cpp

+7-6
Original file line numberDiff line numberDiff line change
@@ -81,18 +81,19 @@ void GearDisplay::drawGearIndicator(QPainter & painter, const QRectF & backgroun
8181
break;
8282
}
8383

84-
QFont gearFont("Quicksand", 16, QFont::Bold);
84+
QFont gearFont("Quicksand", 12, QFont::Bold);
8585
painter.setFont(gearFont);
8686
QPen borderPen(gray);
87-
borderPen.setWidth(4);
87+
borderPen.setWidth(1);
8888
painter.setPen(borderPen);
8989

90-
int gearBoxSize = 30;
91-
int gearX = backgroundRect.left() + 30 + gearBoxSize;
92-
int gearY = backgroundRect.height() - gearBoxSize - 20;
90+
double gearBoxSize = 37.5;
91+
double gearX = backgroundRect.left() + 54;
92+
double gearY = backgroundRect.height() / 2 - gearBoxSize / 2;
9393
QRect gearRect(gearX, gearY, gearBoxSize, gearBoxSize);
94-
painter.setBrush(QColor(0, 0, 0, 0));
94+
painter.setBrush(gray);
9595
painter.drawRoundedRect(gearRect, 10, 10);
96+
painter.setPen(Qt::black);
9697
painter.drawText(gearRect, Qt::AlignCenter, QString::fromStdString(gearString));
9798
}
9899

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp

+16-18
Original file line numberDiff line numberDiff line change
@@ -39,11 +39,11 @@ namespace autoware_overlay_rviz_plugin
3939
SignalDisplay::SignalDisplay()
4040
{
4141
property_width_ = new rviz_common::properties::IntProperty(
42-
"Width", 517, "Width of the overlay", this, SLOT(updateOverlaySize()));
42+
"Width", 550, "Width of the overlay", this, SLOT(updateOverlaySize()));
4343
property_height_ = new rviz_common::properties::IntProperty(
44-
"Height", 175, "Height of the overlay", this, SLOT(updateOverlaySize()));
44+
"Height", 100, "Height of the overlay", this, SLOT(updateOverlaySize()));
4545
property_left_ = new rviz_common::properties::IntProperty(
46-
"Left", 10, "Left position of the overlay", this, SLOT(updateOverlayPosition()));
46+
"Left", 0, "Left position of the overlay", this, SLOT(updateOverlayPosition()));
4747
property_top_ = new rviz_common::properties::IntProperty(
4848
"Top", 10, "Top position of the overlay", this, SLOT(updateOverlayPosition()));
4949
property_signal_color_ = new rviz_common::properties::ColorProperty(
@@ -325,35 +325,31 @@ void SignalDisplay::drawWidget(QImage & hud)
325325
QPainter painter(&hud);
326326
painter.setRenderHint(QPainter::Antialiasing, true);
327327

328-
QRectF backgroundRect(0, 0, 322, hud.height());
328+
QRectF backgroundRect(0, 0, 550, hud.height());
329329
drawHorizontalRoundedRectangle(painter, backgroundRect);
330330

331331
// Draw components
332-
if (steering_wheel_display_) {
333-
steering_wheel_display_->drawSteeringWheel(painter, backgroundRect);
334-
}
335332
if (gear_display_) {
336333
gear_display_->drawGearIndicator(painter, backgroundRect);
337334
}
335+
336+
if (steering_wheel_display_) {
337+
steering_wheel_display_->drawSteeringWheel(painter, backgroundRect);
338+
}
339+
338340
if (speed_display_) {
339341
speed_display_->drawSpeedDisplay(painter, backgroundRect);
340342
}
341343
if (turn_signals_display_) {
342344
turn_signals_display_->drawArrows(painter, backgroundRect, property_signal_color_->getColor());
343345
}
344346

345-
// a 27px space between the two halves of the HUD
346-
347-
QRectF smallerBackgroundRect(340, 0, 190.0 / 2, hud.height());
348-
349-
drawVerticalRoundedRectangle(painter, smallerBackgroundRect);
350-
351347
if (traffic_display_) {
352-
traffic_display_->drawTrafficLightIndicator(painter, smallerBackgroundRect);
348+
traffic_display_->drawTrafficLightIndicator(painter, backgroundRect);
353349
}
354350

355351
if (speed_limit_display_) {
356-
speed_limit_display_->drawSpeedLimitIndicator(painter, smallerBackgroundRect);
352+
speed_limit_display_->drawSpeedLimitIndicator(painter, backgroundRect);
357353
}
358354

359355
painter.end();
@@ -364,8 +360,8 @@ void SignalDisplay::drawHorizontalRoundedRectangle(
364360
{
365361
painter.setRenderHint(QPainter::Antialiasing, true);
366362
QColor colorFromHSV;
367-
colorFromHSV.setHsv(0, 0, 0); // Hue, Saturation, Value
368-
colorFromHSV.setAlphaF(0.65); // Transparency
363+
colorFromHSV.setHsv(0, 0, 29); // Hue, Saturation, Value
364+
colorFromHSV.setAlphaF(0.60); // Transparency
369365

370366
painter.setBrush(colorFromHSV);
371367

@@ -404,7 +400,9 @@ void SignalDisplay::updateOverlaySize()
404400
void SignalDisplay::updateOverlayPosition()
405401
{
406402
std::lock_guard<std::mutex> lock(mutex_);
407-
overlay_->setPosition(property_left_->getInt(), property_top_->getInt());
403+
overlay_->setPosition(
404+
property_left_->getInt(), property_top_->getInt(), HorizontalAlignment::CENTER,
405+
VerticalAlignment::TOP);
408406
queueRender();
409407
}
410408

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp

+5-4
Original file line numberDiff line numberDiff line change
@@ -85,7 +85,7 @@ void SpeedDisplay::drawSpeedDisplay(QPainter & painter, const QRectF & backgroun
8585
backgroundRect.width() / 2 - referenceRect.width() / 2 - 5, backgroundRect.height() / 2);
8686

8787
QString speedNumber = QString::number(current_speed_, 'f', 0);
88-
int fontSize = 60;
88+
int fontSize = 40;
8989
QFont speedFont("Quicksand", fontSize);
9090
painter.setFont(speedFont);
9191

@@ -94,16 +94,17 @@ void SpeedDisplay::drawSpeedDisplay(QPainter & painter, const QRectF & backgroun
9494

9595
// Center the speed number in the backgroundRect
9696
QPointF speedPos(
97-
backgroundRect.center().x() - speedNumberRect.width() / 2, backgroundRect.center().y());
97+
backgroundRect.center().x() - speedNumberRect.width() / 2,
98+
backgroundRect.center().y() + speedNumberRect.bottom());
9899
painter.setPen(gray);
99100
painter.drawText(speedPos, speedNumber);
100101

101-
QFont unitFont("Quicksand", 14);
102+
QFont unitFont("Quicksand", 8, QFont::DemiBold);
102103
painter.setFont(unitFont);
103104
QString speedUnit = "km/h";
104105
QRect unitRect = painter.fontMetrics().boundingRect(speedUnit);
105106
QPointF unitPos(
106-
(backgroundRect.width() / 2 - unitRect.width() / 2), referencePos.y() + unitRect.height());
107+
(backgroundRect.width() / 2 - unitRect.width() / 2), referencePos.y() + unitRect.height() + 15);
107108
painter.drawText(unitPos, speedUnit);
108109
}
109110

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp

+15-9
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
#include <OgreTechnique.h>
2525
#include <OgreTexture.h>
2626
#include <OgreTextureManager.h>
27+
#include <qobject.h>
2728

2829
#include <algorithm>
2930
#include <cmath>
@@ -99,10 +100,9 @@ void SpeedLimitDisplay::drawSpeedLimitIndicator(QPainter & painter, const QRectF
99100
}
100101

101102
// Define the area for the outer circle
102-
QRectF outerCircleRect = backgroundRect;
103-
outerCircleRect.setWidth(backgroundRect.width() - 30);
104-
outerCircleRect.setHeight(backgroundRect.width() - 30);
105-
outerCircleRect.moveTopLeft(QPointF(backgroundRect.left() + 15, backgroundRect.top() + 10));
103+
QRectF outerCircleRect = QRectF(45, 45, 45, 45);
104+
outerCircleRect.moveTopRight(
105+
QPointF(backgroundRect.right() - 44, backgroundRect.top() + outerCircleRect.height() / 2 + 5));
106106

107107
// Now use borderColor for drawing
108108
painter.setPen(QPen(borderColor, 2, Qt::SolidLine, Qt::RoundCap, Qt::RoundJoin));
@@ -112,24 +112,30 @@ void SpeedLimitDisplay::drawSpeedLimitIndicator(QPainter & painter, const QRectF
112112

113113
// Define the area for the inner circle
114114
QRectF innerCircleRect = outerCircleRect;
115-
innerCircleRect.setWidth(outerCircleRect.width() / 1.25);
116-
innerCircleRect.setHeight(outerCircleRect.height() / 1.25);
115+
innerCircleRect.setWidth(outerCircleRect.width() / 1.09);
116+
innerCircleRect.setHeight(outerCircleRect.height() / 1.09);
117117
innerCircleRect.moveCenter(outerCircleRect.center());
118118

119+
QRectF innerCircleRect2 = innerCircleRect;
120+
119121
painter.setRenderHint(QPainter::Antialiasing, true);
120122
QColor colorFromHSV;
121-
colorFromHSV.setHsv(0, 0, 0); // Hue, Saturation, Value
122-
123+
colorFromHSV.setHsv(0, 0, 29); // Hue, Saturation, Value
124+
colorFromHSV.setAlphaF(0.60); // Transparency
123125
painter.setBrush(colorFromHSV);
124126
painter.drawEllipse(innerCircleRect);
125127

128+
// Add a second inner circle as a mask to make the speed limit indicator look like a ring
129+
// and follow the rest of the background color as close as possible
130+
painter.drawEllipse(innerCircleRect2);
131+
126132
int current_limit_int = std::round(current_limit * 3.6);
127133

128134
// Define the text to be drawn
129135
QString text = QString::number(current_limit_int);
130136

131137
// Set the font and color for the text
132-
QFont font = QFont("Quicksand", 24, QFont::Bold);
138+
QFont font = QFont("Quicksand", 16, QFont::Bold);
133139

134140
painter.setFont(font);
135141
// #C2C2C2

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -82,8 +82,8 @@ void SteeringWheelDisplay::drawSteeringWheel(QPainter & painter, const QRectF &
8282
// Rotate the wheel
8383
float steeringAngle = steering_angle_; // No need to round here
8484
// Calculate the position
85-
int wheelCenterX = backgroundRect.right() - wheel.width() - 17.5;
86-
int wheelCenterY = backgroundRect.height() - wheel.height() + 15;
85+
int wheelCenterX = backgroundRect.left() + wheel.width() + 54 + 54;
86+
int wheelCenterY = backgroundRect.height() / 2;
8787

8888
// Rotate the wheel image
8989
QTransform rotationTransform;

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp

+4-6
Original file line numberDiff line numberDiff line change
@@ -62,12 +62,10 @@ void TrafficDisplay::drawTrafficLightIndicator(QPainter & painter, const QRectF
6262
painter.setBrush(QBrush(tl_gray_, Qt::SolidPattern));
6363
painter.setPen(Qt::NoPen);
6464
// Define the area for the circle (background)
65-
QRectF circleRect = backgroundRect;
66-
circleRect.setWidth(backgroundRect.width() - 30);
67-
circleRect.setHeight(backgroundRect.width() - 30);
65+
QRectF circleRect = QRectF(50, 50, 50, 50);
6866
circleRect.moveTopRight(QPointF(
69-
backgroundRect.left() + circleRect.width() + 15,
70-
backgroundRect.top() + circleRect.height() + 30));
67+
backgroundRect.right() - circleRect.width() - 75,
68+
backgroundRect.top() + circleRect.height() / 2));
7169
painter.drawEllipse(circleRect);
7270

7371
if (!current_traffic_.elements.empty()) {
@@ -96,7 +94,7 @@ void TrafficDisplay::drawTrafficLightIndicator(QPainter & painter, const QRectF
9694
}
9795

9896
// Scaling factor (e.g., 1.5 for 150% size)
99-
float scaleFactor = 1.00;
97+
float scaleFactor = 0.75;
10098

10199
// Calculate the scaled size
102100
QSize scaledSize = traffic_light_image_.size() * scaleFactor;

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -72,12 +72,12 @@ void TurnSignalsDisplay::updateHazardLightsData(
7272
void TurnSignalsDisplay::drawArrows(
7373
QPainter & painter, const QRectF & backgroundRect, const QColor & color)
7474
{
75-
QImage scaledLeftArrow = arrowImage.scaled(64, 43, Qt::KeepAspectRatio, Qt::SmoothTransformation);
75+
QImage scaledLeftArrow = arrowImage.scaled(50, 32, Qt::KeepAspectRatio, Qt::SmoothTransformation);
7676
scaledLeftArrow = coloredImage(scaledLeftArrow, gray);
7777
QImage scaledRightArrow = scaledLeftArrow.mirrored(true, false);
78-
int arrowYPos = (backgroundRect.height() / 3 - scaledLeftArrow.height() / 2);
79-
int leftArrowXPos = backgroundRect.width() / 4 - scaledLeftArrow.width(); // Adjust as needed
80-
int rightArrowXPos = backgroundRect.width() * 3 / 4; // Adjust as needed
78+
int arrowYPos = (backgroundRect.height() / 2 - scaledLeftArrow.height() / 2 - 4);
79+
int leftArrowXPos = backgroundRect.left() + scaledLeftArrow.width() * 2 + 180;
80+
int rightArrowXPos = backgroundRect.right() - scaledRightArrow.width() * 3 - 175;
8181

8282
bool leftActive =
8383
(current_turn_signal_ == autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::ENABLE_LEFT ||

0 commit comments

Comments
 (0)