Skip to content

Commit

Permalink
feat: add color customization to gear speed mission speed limit and t…
Browse files Browse the repository at this point in the history
…raffic displays (autowarefoundation#8142)

feat: Add color customization to gear, speed, mission,speedlimit and traffic displays
  • Loading branch information
KhalilSelyan authored Jul 23, 2024
1 parent 8e9cc35 commit 1ee7511
Show file tree
Hide file tree
Showing 13 changed files with 93 additions and 47 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,10 @@ private Q_SLOTS:
rviz_common::properties::IntProperty * property_height_;
rviz_common::properties::IntProperty * property_right_;
rviz_common::properties::IntProperty * property_top_;
rviz_common::properties::ColorProperty * property_bg_color_;
rviz_common::properties::FloatProperty * property_bg_alpha_;
rviz_common::properties::ColorProperty * property_text_color_;

std::unique_ptr<rviz_common::properties::RosTopicProperty>
remaining_distance_time_topic_property_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,16 +36,15 @@ class RemainingDistanceTimeDisplay
{
public:
RemainingDistanceTimeDisplay();
void drawRemainingDistanceTimeDisplay(QPainter & painter, const QRectF & backgroundRect);
void drawRemainingDistanceTimeDisplay(
QPainter & painter, const QRectF & backgroundRect, const QColor & text_color);
void updateRemainingDistanceTimeData(
const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg);

private:
double remaining_distance_; // Internal variable to store remaining distance
double remaining_time_; // Internal variable to store remaining time

QColor gray = QColor(194, 194, 194);

QImage icon_dist_;
QImage icon_dist_scaled_;
QImage icon_time_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,12 @@ MissionDetailsDisplay::MissionDetailsDisplay()
"Right", 10, "Margin from the right border", this, SLOT(update_size()));
property_top_ = new rviz_common::properties::IntProperty(
"Top", 10, "Margin from the top border", this, SLOT(update_size()));
property_bg_alpha_ = new rviz_common::properties::FloatProperty(
"Background Alpha", 0.3, "Background Alpha", this, SLOT(update_size()));
property_bg_color_ = new rviz_common::properties::ColorProperty(
"Background Color", QColor(0, 0, 0), "Background Color", this, SLOT(update_size()));
property_text_color_ = new rviz_common::properties::ColorProperty(
"Text Color", QColor(194, 194, 194), "Text Color", this, SLOT(update_size()));

// Initialize the component displays
remaining_distance_time_display_ = std::make_unique<RemainingDistanceTimeDisplay>();
Expand Down Expand Up @@ -154,7 +160,8 @@ void MissionDetailsDisplay::draw_widget(QImage & hud)
draw_rounded_rect(painter, backgroundRect);

if (remaining_distance_time_display_) {
remaining_distance_time_display_->drawRemainingDistanceTimeDisplay(painter, backgroundRect);
remaining_distance_time_display_->drawRemainingDistanceTimeDisplay(
painter, backgroundRect, property_text_color_->getColor());
}

painter.end();
Expand All @@ -164,8 +171,10 @@ void MissionDetailsDisplay::draw_rounded_rect(QPainter & painter, const QRectF &
{
painter.setRenderHint(QPainter::Antialiasing, true);
QColor colorFromHSV;
colorFromHSV.setHsv(0, 0, 29);
colorFromHSV.setAlphaF(0.60);
colorFromHSV.setHsv(
property_bg_color_->getColor().hue(), property_bg_color_->getColor().saturation(),
property_bg_color_->getColor().value());
colorFromHSV.setAlphaF(property_bg_alpha_->getFloat());

painter.setBrush(colorFromHSV);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData(
}

void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay(
QPainter & painter, const QRectF & backgroundRect)
QPainter & painter, const QRectF & backgroundRect, const QColor & text_color)
{
const QFont font("Quicksand", 15, QFont::Bold);
painter.setFont(font);
Expand Down Expand Up @@ -107,7 +107,7 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay(
QRectF rect_text_unit(
rect.topRight().x() - unit_width, rect.topRight().y(), unit_width, rect.height());

painter.setPen(gray);
painter.setPen(text_color);
painter.drawText(rect_text_unit, Qt::AlignLeft | Qt::AlignVCenter, str_unit);

// place the value text
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,9 @@ class GearDisplay
{
public:
GearDisplay();
void drawGearIndicator(QPainter & painter, const QRectF & backgroundRect);
void drawGearIndicator(
QPainter & painter, const QRectF & backgroundRect, const QColor & color,
const QColor & bg_color);
void updateGearData(const autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr & msg);

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,12 @@ private Q_SLOTS:
rviz_common::properties::IntProperty * property_top_;
rviz_common::properties::ColorProperty * property_signal_color_;
rviz_common::properties::FloatProperty * property_handle_angle_scale_;
rviz_common::properties::ColorProperty * property_background_color_;
rviz_common::properties::FloatProperty * property_background_alpha_;
rviz_common::properties::ColorProperty * property_primary_color_;
rviz_common::properties::ColorProperty * property_light_limit_color_;
rviz_common::properties::ColorProperty * property_dark_limit_color_;

std::unique_ptr<rviz_common::properties::RosTopicProperty> steering_topic_property_;
std::unique_ptr<rviz_common::properties::RosTopicProperty> gear_topic_property_;
std::unique_ptr<rviz_common::properties::RosTopicProperty> speed_topic_property_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,12 +36,11 @@ class SpeedDisplay
{
public:
SpeedDisplay();
void drawSpeedDisplay(QPainter & painter, const QRectF & backgroundRect);
void drawSpeedDisplay(QPainter & painter, const QRectF & backgroundRect, const QColor & color);
void updateSpeedData(const autoware_vehicle_msgs::msg::VelocityReport::ConstSharedPtr & msg);

private:
float current_speed_; // Internal variable to store current speed
QColor gray = QColor(194, 194, 194);
};

} // namespace autoware_overlay_rviz_plugin
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,14 +37,16 @@ class SpeedLimitDisplay
{
public:
SpeedLimitDisplay();
void drawSpeedLimitIndicator(QPainter & painter, const QRectF & backgroundRect);
void drawSpeedLimitIndicator(
QPainter & painter, const QRectF & backgroundRect, const QColor & color,
const QColor & light_color, const QColor & dark_color, const QColor & bg_color,
const float bg_alpha);
void updateSpeedLimitData(const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg);
void updateSpeedData(const autoware_vehicle_msgs::msg::VelocityReport::ConstSharedPtr & msg);

private:
float current_limit; // Internal variable to store current gear
float current_speed_; // Internal variable to store current speed
QColor gray = QColor(194, 194, 194);
};

} // namespace autoware_overlay_rviz_plugin
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,8 @@ void GearDisplay::updateGearData(const autoware_vehicle_msgs::msg::GearReport::C
current_gear_ = msg->report; // Assuming msg->report contains the gear information
}

void GearDisplay::drawGearIndicator(QPainter & painter, const QRectF & backgroundRect)
void GearDisplay::drawGearIndicator(
QPainter & painter, const QRectF & backgroundRect, const QColor & color, const QColor & bg_color)
{
// we deal with the different gears here
std::string gearString;
Expand Down Expand Up @@ -90,9 +91,9 @@ void GearDisplay::drawGearIndicator(QPainter & painter, const QRectF & backgroun
double gearX = backgroundRect.left() + 54;
double gearY = backgroundRect.height() / 2 - gearBoxSize / 2;
QRect gearRect(gearX, gearY, gearBoxSize, gearBoxSize);
painter.setBrush(gray);
painter.setBrush(color);
painter.drawRoundedRect(gearRect, 10, 10);
painter.setPen(Qt::black);
painter.setPen(bg_color);
painter.drawText(gearRect, Qt::AlignCenter, QString::fromStdString(gearString));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,20 @@ SignalDisplay::SignalDisplay()
property_handle_angle_scale_ = new rviz_common::properties::FloatProperty(
"Handle Angle Scale", 17.0, "Scale of the steering wheel handle angle", this,
SLOT(updateOverlaySize()));
property_background_color_ = new rviz_common::properties::ColorProperty(
"Background Color", QColor(0, 0, 0), "Color of the signal arrows", this,
SLOT(updateOverlayColor()));
property_background_alpha_ = new rviz_common::properties::FloatProperty(
"Background Alpha", 0.3, "Background Color Alpha", this, SLOT(updateOverlayColor()));
property_primary_color_ = new rviz_common::properties::ColorProperty(
"Primary Color", QColor(174, 174, 174), "Color of the signal arrows", this,
SLOT(updateOverlayColor()));
property_light_limit_color_ = new rviz_common::properties::ColorProperty(
"Light Traffic Color", QColor(255, 153, 153), "Color of the signal arrows", this,
SLOT(updateOverlayColor()));
property_dark_limit_color_ = new rviz_common::properties::ColorProperty(
"Dark Traffic Color", QColor(255, 51, 51), "Color of the signal arrows", this,
SLOT(updateOverlayColor()));

// Initialize the component displays
steering_wheel_display_ = std::make_unique<SteeringWheelDisplay>();
Expand Down Expand Up @@ -280,12 +294,14 @@ void SignalDisplay::drawWidget(QImage & hud)
QPainter painter(&hud);
painter.setRenderHint(QPainter::Antialiasing, true);

QRectF backgroundRect(0, 0, 550, hud.height());
QRectF backgroundRect(0, 0, hud.width(), hud.height());
drawHorizontalRoundedRectangle(painter, backgroundRect);

// Draw components
if (gear_display_) {
gear_display_->drawGearIndicator(painter, backgroundRect);
gear_display_->drawGearIndicator(
painter, backgroundRect, property_primary_color_->getColor(),
property_background_color_->getColor());
}

if (steering_wheel_display_) {
Expand All @@ -294,7 +310,7 @@ void SignalDisplay::drawWidget(QImage & hud)
}

if (speed_display_) {
speed_display_->drawSpeedDisplay(painter, backgroundRect);
speed_display_->drawSpeedDisplay(painter, backgroundRect, property_primary_color_->getColor());
}
if (turn_signals_display_) {
turn_signals_display_->drawArrows(painter, backgroundRect, property_signal_color_->getColor());
Expand All @@ -305,7 +321,10 @@ void SignalDisplay::drawWidget(QImage & hud)
}

if (speed_limit_display_) {
speed_limit_display_->drawSpeedLimitIndicator(painter, backgroundRect);
speed_limit_display_->drawSpeedLimitIndicator(
painter, backgroundRect, property_primary_color_->getColor(),
property_light_limit_color_->getColor(), property_dark_limit_color_->getColor(),
property_background_color_->getColor(), property_background_alpha_->getFloat());
}

painter.end();
Expand All @@ -316,9 +335,11 @@ void SignalDisplay::drawHorizontalRoundedRectangle(
{
painter.setRenderHint(QPainter::Antialiasing, true);
QColor colorFromHSV;
colorFromHSV.setHsv(0, 0, 29); // Hue, Saturation, Value
colorFromHSV.setAlphaF(0.60); // Transparency

colorFromHSV.setHsv(
property_background_color_->getColor().hue(),
property_background_color_->getColor().saturation(),
property_background_color_->getColor().value());
colorFromHSV.setAlphaF(property_background_alpha_->getFloat());
painter.setBrush(colorFromHSV);

painter.setPen(Qt::NoPen);
Expand All @@ -329,8 +350,11 @@ void SignalDisplay::drawVerticalRoundedRectangle(QPainter & painter, const QRect
{
painter.setRenderHint(QPainter::Antialiasing, true);
QColor colorFromHSV;
colorFromHSV.setHsv(0, 0, 0); // Hue, Saturation, Value
colorFromHSV.setAlphaF(0.65); // Transparency
colorFromHSV.setHsv(
property_background_color_->getColor().hue(),
property_background_color_->getColor().saturation(),
property_background_color_->getColor().value());
colorFromHSV.setAlphaF(property_background_alpha_->getFloat());

painter.setBrush(colorFromHSV);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,8 @@ void SpeedDisplay::updateSpeedData(
// }
// }

void SpeedDisplay::drawSpeedDisplay(QPainter & painter, const QRectF & backgroundRect)
void SpeedDisplay::drawSpeedDisplay(
QPainter & painter, const QRectF & backgroundRect, const QColor & color)
{
QFont referenceFont("Quicksand", 80, QFont::Bold);
painter.setFont(referenceFont);
Expand All @@ -96,7 +97,7 @@ void SpeedDisplay::drawSpeedDisplay(QPainter & painter, const QRectF & backgroun
QPointF speedPos(
backgroundRect.center().x() - speedNumberRect.width() / 2,
backgroundRect.center().y() + speedNumberRect.bottom());
painter.setPen(gray);
painter.setPen(color);
painter.drawText(speedPos, speedNumber);

QFont unitFont("Quicksand", 8, QFont::DemiBold);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,41 +68,41 @@ void SpeedLimitDisplay::updateSpeedData(
}
}

void SpeedLimitDisplay::drawSpeedLimitIndicator(QPainter & painter, const QRectF & backgroundRect)
void SpeedLimitDisplay::drawSpeedLimitIndicator(
QPainter & painter, const QRectF & backgroundRect, const QColor & color,
const QColor & light_color, const QColor & dark_color, const QColor & bg_color,
const float bg_alpha)
{
// Enable Antialiasing for smoother drawing
painter.setRenderHint(QPainter::Antialiasing, true);
painter.setRenderHint(QPainter::SmoothPixmapTransform, true);

const double color_s_min = 0.4;
const double color_s_max = 0.8;
QColor colorMin;
colorMin.setHsvF(0.0, color_s_min, 1.0);
QColor colorMax;
colorMax.setHsvF(0.0, color_s_max, 1.0);
QColor borderColor = light_color;

QColor borderColor = colorMin;
if (current_limit > 0.0) {
double speed_to_limit_ratio = current_speed_ / current_limit;
const double speed_to_limit_ratio_min = 0.6;
const double speed_to_limit_ratio_max = 0.9;

if (speed_to_limit_ratio >= speed_to_limit_ratio_max) {
borderColor = colorMax;
borderColor = dark_color;
} else if (speed_to_limit_ratio > speed_to_limit_ratio_min) {
double interpolation_factor = (speed_to_limit_ratio - speed_to_limit_ratio_min) /
(speed_to_limit_ratio_max - speed_to_limit_ratio_min);
// Interpolate between colorMin and colorMax
double saturation = color_s_min + (color_s_max - color_s_min) * interpolation_factor;

borderColor.setHsvF(0.0, saturation, 1.0);
// Interpolate between light_color and dark_color
int red = light_color.red() + (dark_color.red() - light_color.red()) * interpolation_factor;
int green =
light_color.green() + (dark_color.green() - light_color.green()) * interpolation_factor;
int blue =
light_color.blue() + (dark_color.blue() - light_color.blue()) * interpolation_factor;
borderColor = QColor(red, green, blue);
}
}

// Define the area for the outer circle
QRectF outerCircleRect = QRectF(45, 45, 45, 45);
outerCircleRect.moveTopRight(
QPointF(backgroundRect.right() - 44, backgroundRect.top() + outerCircleRect.height() / 2 + 5));
outerCircleRect.moveTopRight(QPointF(
backgroundRect.right() - 44, backgroundRect.height() / 2 - outerCircleRect.height() / 2));

// Now use borderColor for drawing
painter.setPen(QPen(borderColor, 2, Qt::SolidLine, Qt::RoundCap, Qt::RoundJoin));
Expand All @@ -120,8 +120,8 @@ void SpeedLimitDisplay::drawSpeedLimitIndicator(QPainter & painter, const QRectF

painter.setRenderHint(QPainter::Antialiasing, true);
QColor colorFromHSV;
colorFromHSV.setHsv(0, 0, 29); // Hue, Saturation, Value
colorFromHSV.setAlphaF(0.60); // Transparency
colorFromHSV.setHsv(bg_color.hue(), bg_color.saturation(), bg_color.value());
colorFromHSV.setAlphaF(bg_alpha);
painter.setBrush(colorFromHSV);
painter.drawEllipse(innerCircleRect);

Expand All @@ -138,8 +138,7 @@ void SpeedLimitDisplay::drawSpeedLimitIndicator(QPainter & painter, const QRectF
QFont font = QFont("Quicksand", 16, QFont::Bold);

painter.setFont(font);
// #C2C2C2
painter.setPen(QPen(gray, 2, Qt::SolidLine, Qt::RoundCap, Qt::RoundJoin));
painter.setPen(QPen(color, 2, Qt::SolidLine, Qt::RoundCap, Qt::RoundJoin));

// Draw the text in the center of the circle
painter.drawText(innerCircleRect, Qt::AlignCenter, text);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ void TrafficDisplay::drawTrafficLightIndicator(QPainter & painter, const QRectF
QRectF circleRect = QRectF(50, 50, 50, 50);
circleRect.moveTopRight(QPointF(
backgroundRect.right() - circleRect.width() - 75,
backgroundRect.top() + circleRect.height() / 2));
backgroundRect.height() / 2 - circleRect.height() / 2));
painter.drawEllipse(circleRect);

if (!current_traffic_.elements.empty()) {
Expand Down

0 comments on commit 1ee7511

Please sign in to comment.