Skip to content

Commit b67d420

Browse files
author
M. Fatih Cırıt
committed
simplify the color transition and switch to the hsv
Signed-off-by: M. Fatih Cırıt <mfc@leodrive.ai>
1 parent 4d71c15 commit b67d420

File tree

1 file changed

+21
-29
lines changed

1 file changed

+21
-29
lines changed

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp

+21-29
Original file line numberDiff line numberDiff line change
@@ -73,37 +73,29 @@ void SpeedLimitDisplay::drawSpeedLimitIndicator(QPainter & painter, const QRectF
7373
painter.setRenderHint(QPainter::Antialiasing, true);
7474
painter.setRenderHint(QPainter::SmoothPixmapTransform, true);
7575

76-
// Convert color_min and color_max to QColor
77-
QColor colorMin = QColor("#FF9999");
78-
QColor colorMax = QColor("#FF3333");
79-
80-
// Calculate the ratio between the current speed and the speed limit
81-
double speed_to_limit_ratio = current_speed_ / current_limit;
76+
const double color_s_min = 0.4;
77+
const double color_s_max = 0.8;
78+
QColor colorMin;
79+
colorMin.setHsvF(0.0, color_s_min, 1.0);
80+
QColor colorMax;
81+
colorMax.setHsvF(0.0, color_s_max, 1.0);
8282

8383
QColor borderColor = colorMin;
84-
85-
if (speed_to_limit_ratio > 0.7 && current_limit > 0.0) {
86-
// Adjust the interpolation to start more gradually
87-
// Calculate a new factor that slows down the transition
88-
double adjusted_speed_to_limit_ratio = (speed_to_limit_ratio - 0.7) / (1.0 - 0.7);
89-
double smoothFactor =
90-
pow(adjusted_speed_to_limit_ratio, 2); // Use a power to make it interpolate slower
91-
92-
int r = std::min(
93-
std::max(
94-
0, colorMin.red() + static_cast<int>((colorMax.red() - colorMin.red()) * smoothFactor)),
95-
255);
96-
int g = std::min(
97-
std::max(
98-
0,
99-
colorMin.green() + static_cast<int>((colorMax.green() - colorMin.green()) * smoothFactor)),
100-
255);
101-
int b = std::min(
102-
std::max(
103-
0, colorMin.blue() + static_cast<int>((colorMax.blue() - colorMin.blue()) * smoothFactor)),
104-
255);
105-
106-
borderColor = QColor(r, g, b);
84+
if (current_limit > 0.0) {
85+
double speed_to_limit_ratio = current_speed_ / current_limit;
86+
const double speed_to_limit_ratio_min = 0.6;
87+
const double speed_to_limit_ratio_max = 0.9;
88+
89+
if (speed_to_limit_ratio >= speed_to_limit_ratio_max) {
90+
borderColor = colorMax;
91+
} else if (speed_to_limit_ratio > speed_to_limit_ratio_min) {
92+
double interpolation_factor = (speed_to_limit_ratio - speed_to_limit_ratio_min) /
93+
(speed_to_limit_ratio_max - speed_to_limit_ratio_min);
94+
// Interpolate between colorMin and colorMax
95+
double saturation = color_s_min + (color_s_max - color_s_min) * interpolation_factor;
96+
97+
borderColor.setHsvF(0.0, saturation, 1.0);
98+
}
10799
}
108100

109101
// Define the area for the outer circle

0 commit comments

Comments
 (0)