From 42611d60dde054e5e5c758cba7be5e25c8d5b854 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Sat, 11 May 2024 01:07:26 +0300 Subject: [PATCH] clean up more MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../include/mission_details_display.hpp | 11 ++-- .../include/overlay_utils.hpp | 12 +--- .../src/mission_details_display.cpp | 56 ++++++------------- 3 files changed, 24 insertions(+), 55 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp index ddc91e1890117..ab5abfe3c3d83 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp @@ -51,9 +51,7 @@ class MissionDetailsDisplay : public rviz_common::Display void onDisable() override; private Q_SLOTS: - void updateOverlaySize(); - void updateSmallOverlaySize(); - void updateOverlayColor(); + void update_size(); void topic_updated_remaining_distance_time(); private: @@ -66,8 +64,7 @@ private Q_SLOTS: std::unique_ptr remaining_distance_time_topic_property_; - void drawHorizontalRoundedRectangle(QPainter & painter, const QRectF & backgroundRect); - void drawVerticalRoundedRectangle(QPainter & painter, const QRectF & backgroundRect); + void draw_rounded_rect(QPainter & painter, const QRectF & backgroundRect); void setupRosSubscriptions(); std::unique_ptr remaining_distance_time_display_; @@ -77,9 +74,9 @@ private Q_SLOTS: std::mutex property_mutex_; - void updateRemainingDistanceTimeData( + void cb_remaining_distance_time( const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); - void drawWidget(QImage & hud); + void draw_widget(QImage & hud); }; } // namespace autoware::mission_details_overlay_rviz_plugin diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp index 76f63e5fb74a4..a0344f872f524 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp @@ -87,17 +87,9 @@ class ScopedPixelBuffer Ogre::HardwarePixelBufferSharedPtr pixel_buffer_; }; -enum class VerticalAlignment : uint8_t { - CENTER, - TOP, - BOTTOM -}; +enum class VerticalAlignment : uint8_t { CENTER, TOP, BOTTOM }; -enum class HorizontalAlignment : uint8_t { - LEFT, - RIGHT, - CENTER -}; +enum class HorizontalAlignment : uint8_t { LEFT, RIGHT, CENTER }; /** * Helper class for realizing an overlay object on top of the rviz 3D panel. diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp index d0a3e7f6414f6..4139c24748f78 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -16,6 +16,7 @@ #include #include +#include #include #include #include @@ -32,13 +33,13 @@ namespace autoware::mission_details_overlay_rviz_plugin MissionDetailsDisplay::MissionDetailsDisplay() { property_width_ = new rviz_common::properties::IntProperty( - "Width", 170, "Width of the overlay", this, SLOT(updateOverlaySize())); + "Width", 170, "Width of the overlay", this, SLOT(update_size())); property_height_ = new rviz_common::properties::IntProperty( - "Height", 100, "Height of the overlay", this, SLOT(updateOverlaySize())); + "Height", 100, "Height of the overlay", this, SLOT(update_size())); property_right_ = new rviz_common::properties::IntProperty( - "Right", 10, "Margin from the right border", this, SLOT(updateOverlaySize())); + "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(updateOverlaySize())); + "Top", 10, "Margin from the top border", this, SLOT(update_size())); // Initialize the component displays remaining_distance_time_display_ = std::make_unique(); @@ -53,9 +54,9 @@ void MissionDetailsDisplay::onInitialize() static int count = 0; std::stringstream ss; ss << "MissionDetailsDisplay" << count++; - overlay_.reset(new autoware::mission_details_overlay_rviz_plugin::OverlayObject(ss.str())); + overlay_ = std::make_shared(ss.str()); overlay_->show(); - updateOverlaySize(); + update_size(); auto rviz_ros_node = context_->getRosNodeAbstraction(); @@ -78,7 +79,7 @@ void MissionDetailsDisplay::setupRosSubscriptions() remaining_distance_time_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), [this](const autoware_internal_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { - updateRemainingDistanceTimeData(msg); + cb_remaining_distance_time(msg); }); } @@ -104,7 +105,7 @@ void MissionDetailsDisplay::update(float wall_dt, float ros_dt) autoware::mission_details_overlay_rviz_plugin::ScopedPixelBuffer buffer = overlay_->getBuffer(); QImage hud = buffer.getQImage(*overlay_); hud.fill(Qt::transparent); - drawWidget(hud); + draw_widget(hud); } void MissionDetailsDisplay::onEnable() @@ -127,7 +128,7 @@ void MissionDetailsDisplay::onDisable() } } -void MissionDetailsDisplay::updateRemainingDistanceTimeData( +void MissionDetailsDisplay::cb_remaining_distance_time( const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg) { std::lock_guard lock(property_mutex_); @@ -138,7 +139,7 @@ void MissionDetailsDisplay::updateRemainingDistanceTimeData( } } -void MissionDetailsDisplay::drawWidget(QImage & hud) +void MissionDetailsDisplay::draw_widget(QImage & hud) { std::lock_guard lock(property_mutex_); @@ -150,7 +151,7 @@ void MissionDetailsDisplay::drawWidget(QImage & hud) painter.setRenderHint(QPainter::Antialiasing, true); QRectF backgroundRect(0, 0, qreal(property_width_->getInt()), qreal(property_height_->getInt())); - drawHorizontalRoundedRectangle(painter, backgroundRect); + draw_rounded_rect(painter, backgroundRect); if (remaining_distance_time_display_) { remaining_distance_time_display_->drawRemainingDistanceTimeDisplay(painter, backgroundRect); @@ -159,33 +160,18 @@ void MissionDetailsDisplay::drawWidget(QImage & hud) painter.end(); } -void MissionDetailsDisplay::drawHorizontalRoundedRectangle( +void MissionDetailsDisplay::draw_rounded_rect( QPainter & painter, const QRectF & backgroundRect) { painter.setRenderHint(QPainter::Antialiasing, true); QColor colorFromHSV; - colorFromHSV.setHsv(0, 0, 29); // Hue, Saturation, Value - colorFromHSV.setAlphaF(0.60); // Transparency + colorFromHSV.setHsv(0, 0, 29); + colorFromHSV.setAlphaF(0.60); painter.setBrush(colorFromHSV); painter.setPen(Qt::NoPen); - painter.drawRoundedRect( - backgroundRect, backgroundRect.height() / 2, backgroundRect.height() / 2); // Circular ends -} -void MissionDetailsDisplay::drawVerticalRoundedRectangle( - QPainter & painter, const QRectF & backgroundRect) -{ - painter.setRenderHint(QPainter::Antialiasing, true); - QColor colorFromHSV; - colorFromHSV.setHsv(0, 0, 0); // Hue, Saturation, Value - colorFromHSV.setAlphaF(0.65); // Transparency - - painter.setBrush(colorFromHSV); - - painter.setPen(Qt::NoPen); - painter.drawRoundedRect( - backgroundRect, backgroundRect.width() / 2, backgroundRect.width() / 2); // Circular ends + painter.drawRoundedRect(backgroundRect, backgroundRect.height() / 2, backgroundRect.height() / 2); } void MissionDetailsDisplay::reset() @@ -194,7 +180,7 @@ void MissionDetailsDisplay::reset() overlay_->hide(); } -void MissionDetailsDisplay::updateOverlaySize() +void MissionDetailsDisplay::update_size() { std::lock_guard lock(mutex_); overlay_->updateTextureSize(property_width_->getInt(), property_height_->getInt()); @@ -205,12 +191,6 @@ void MissionDetailsDisplay::updateOverlaySize() queueRender(); } -void MissionDetailsDisplay::updateOverlayColor() -{ - std::lock_guard lock(mutex_); - queueRender(); -} - void MissionDetailsDisplay::topic_updated_remaining_distance_time() { // resubscribe to the topic @@ -222,7 +202,7 @@ void MissionDetailsDisplay::topic_updated_remaining_distance_time() remaining_distance_time_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), [this](const autoware_internal_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { - updateRemainingDistanceTimeData(msg); + cb_remaining_distance_time(msg); }); }