Skip to content

Commit 42611d6

Browse files
author
M. Fatih Cırıt
committed
clean up more
Signed-off-by: M. Fatih Cırıt <mfc@leodrive.ai>
1 parent a4c28dd commit 42611d6

File tree

3 files changed

+24
-55
lines changed

3 files changed

+24
-55
lines changed

common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp

+4-7
Original file line numberDiff line numberDiff line change
@@ -51,9 +51,7 @@ class MissionDetailsDisplay : public rviz_common::Display
5151
void onDisable() override;
5252

5353
private Q_SLOTS:
54-
void updateOverlaySize();
55-
void updateSmallOverlaySize();
56-
void updateOverlayColor();
54+
void update_size();
5755
void topic_updated_remaining_distance_time();
5856

5957
private:
@@ -66,8 +64,7 @@ private Q_SLOTS:
6664
std::unique_ptr<rviz_common::properties::RosTopicProperty>
6765
remaining_distance_time_topic_property_;
6866

69-
void drawHorizontalRoundedRectangle(QPainter & painter, const QRectF & backgroundRect);
70-
void drawVerticalRoundedRectangle(QPainter & painter, const QRectF & backgroundRect);
67+
void draw_rounded_rect(QPainter & painter, const QRectF & backgroundRect);
7168
void setupRosSubscriptions();
7269

7370
std::unique_ptr<RemainingDistanceTimeDisplay> remaining_distance_time_display_;
@@ -77,9 +74,9 @@ private Q_SLOTS:
7774

7875
std::mutex property_mutex_;
7976

80-
void updateRemainingDistanceTimeData(
77+
void cb_remaining_distance_time(
8178
const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg);
82-
void drawWidget(QImage & hud);
79+
void draw_widget(QImage & hud);
8380
};
8481
} // namespace autoware::mission_details_overlay_rviz_plugin
8582

common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp

+2-10
Original file line numberDiff line numberDiff line change
@@ -87,17 +87,9 @@ class ScopedPixelBuffer
8787
Ogre::HardwarePixelBufferSharedPtr pixel_buffer_;
8888
};
8989

90-
enum class VerticalAlignment : uint8_t {
91-
CENTER,
92-
TOP,
93-
BOTTOM
94-
};
90+
enum class VerticalAlignment : uint8_t { CENTER, TOP, BOTTOM };
9591

96-
enum class HorizontalAlignment : uint8_t {
97-
LEFT,
98-
RIGHT,
99-
CENTER
100-
};
92+
enum class HorizontalAlignment : uint8_t { LEFT, RIGHT, CENTER };
10193

10294
/**
10395
* Helper class for realizing an overlay object on top of the rviz 3D panel.

common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp

+18-38
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
#include <QFontDatabase>
1818
#include <QPainter>
19+
#include <memory>
1920
#include <rclcpp/rclcpp.hpp>
2021
#include <rviz_common/properties/ros_topic_property.hpp>
2122
#include <rviz_rendering/render_system.hpp>
@@ -32,13 +33,13 @@ namespace autoware::mission_details_overlay_rviz_plugin
3233
MissionDetailsDisplay::MissionDetailsDisplay()
3334
{
3435
property_width_ = new rviz_common::properties::IntProperty(
35-
"Width", 170, "Width of the overlay", this, SLOT(updateOverlaySize()));
36+
"Width", 170, "Width of the overlay", this, SLOT(update_size()));
3637
property_height_ = new rviz_common::properties::IntProperty(
37-
"Height", 100, "Height of the overlay", this, SLOT(updateOverlaySize()));
38+
"Height", 100, "Height of the overlay", this, SLOT(update_size()));
3839
property_right_ = new rviz_common::properties::IntProperty(
39-
"Right", 10, "Margin from the right border", this, SLOT(updateOverlaySize()));
40+
"Right", 10, "Margin from the right border", this, SLOT(update_size()));
4041
property_top_ = new rviz_common::properties::IntProperty(
41-
"Top", 10, "Margin from the top border", this, SLOT(updateOverlaySize()));
42+
"Top", 10, "Margin from the top border", this, SLOT(update_size()));
4243

4344
// Initialize the component displays
4445
remaining_distance_time_display_ = std::make_unique<RemainingDistanceTimeDisplay>();
@@ -53,9 +54,9 @@ void MissionDetailsDisplay::onInitialize()
5354
static int count = 0;
5455
std::stringstream ss;
5556
ss << "MissionDetailsDisplay" << count++;
56-
overlay_.reset(new autoware::mission_details_overlay_rviz_plugin::OverlayObject(ss.str()));
57+
overlay_ = std::make_shared<autoware::mission_details_overlay_rviz_plugin::OverlayObject>(ss.str());
5758
overlay_->show();
58-
updateOverlaySize();
59+
update_size();
5960

6061
auto rviz_ros_node = context_->getRosNodeAbstraction();
6162

@@ -78,7 +79,7 @@ void MissionDetailsDisplay::setupRosSubscriptions()
7879
remaining_distance_time_topic_property_->getTopicStd(),
7980
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
8081
[this](const autoware_internal_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) {
81-
updateRemainingDistanceTimeData(msg);
82+
cb_remaining_distance_time(msg);
8283
});
8384
}
8485

@@ -104,7 +105,7 @@ void MissionDetailsDisplay::update(float wall_dt, float ros_dt)
104105
autoware::mission_details_overlay_rviz_plugin::ScopedPixelBuffer buffer = overlay_->getBuffer();
105106
QImage hud = buffer.getQImage(*overlay_);
106107
hud.fill(Qt::transparent);
107-
drawWidget(hud);
108+
draw_widget(hud);
108109
}
109110

110111
void MissionDetailsDisplay::onEnable()
@@ -127,7 +128,7 @@ void MissionDetailsDisplay::onDisable()
127128
}
128129
}
129130

130-
void MissionDetailsDisplay::updateRemainingDistanceTimeData(
131+
void MissionDetailsDisplay::cb_remaining_distance_time(
131132
const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg)
132133
{
133134
std::lock_guard<std::mutex> lock(property_mutex_);
@@ -138,7 +139,7 @@ void MissionDetailsDisplay::updateRemainingDistanceTimeData(
138139
}
139140
}
140141

141-
void MissionDetailsDisplay::drawWidget(QImage & hud)
142+
void MissionDetailsDisplay::draw_widget(QImage & hud)
142143
{
143144
std::lock_guard<std::mutex> lock(property_mutex_);
144145

@@ -150,7 +151,7 @@ void MissionDetailsDisplay::drawWidget(QImage & hud)
150151
painter.setRenderHint(QPainter::Antialiasing, true);
151152

152153
QRectF backgroundRect(0, 0, qreal(property_width_->getInt()), qreal(property_height_->getInt()));
153-
drawHorizontalRoundedRectangle(painter, backgroundRect);
154+
draw_rounded_rect(painter, backgroundRect);
154155

155156
if (remaining_distance_time_display_) {
156157
remaining_distance_time_display_->drawRemainingDistanceTimeDisplay(painter, backgroundRect);
@@ -159,33 +160,18 @@ void MissionDetailsDisplay::drawWidget(QImage & hud)
159160
painter.end();
160161
}
161162

162-
void MissionDetailsDisplay::drawHorizontalRoundedRectangle(
163+
void MissionDetailsDisplay::draw_rounded_rect(
163164
QPainter & painter, const QRectF & backgroundRect)
164165
{
165166
painter.setRenderHint(QPainter::Antialiasing, true);
166167
QColor colorFromHSV;
167-
colorFromHSV.setHsv(0, 0, 29); // Hue, Saturation, Value
168-
colorFromHSV.setAlphaF(0.60); // Transparency
168+
colorFromHSV.setHsv(0, 0, 29);
169+
colorFromHSV.setAlphaF(0.60);
169170

170171
painter.setBrush(colorFromHSV);
171172

172173
painter.setPen(Qt::NoPen);
173-
painter.drawRoundedRect(
174-
backgroundRect, backgroundRect.height() / 2, backgroundRect.height() / 2); // Circular ends
175-
}
176-
void MissionDetailsDisplay::drawVerticalRoundedRectangle(
177-
QPainter & painter, const QRectF & backgroundRect)
178-
{
179-
painter.setRenderHint(QPainter::Antialiasing, true);
180-
QColor colorFromHSV;
181-
colorFromHSV.setHsv(0, 0, 0); // Hue, Saturation, Value
182-
colorFromHSV.setAlphaF(0.65); // Transparency
183-
184-
painter.setBrush(colorFromHSV);
185-
186-
painter.setPen(Qt::NoPen);
187-
painter.drawRoundedRect(
188-
backgroundRect, backgroundRect.width() / 2, backgroundRect.width() / 2); // Circular ends
174+
painter.drawRoundedRect(backgroundRect, backgroundRect.height() / 2, backgroundRect.height() / 2);
189175
}
190176

191177
void MissionDetailsDisplay::reset()
@@ -194,7 +180,7 @@ void MissionDetailsDisplay::reset()
194180
overlay_->hide();
195181
}
196182

197-
void MissionDetailsDisplay::updateOverlaySize()
183+
void MissionDetailsDisplay::update_size()
198184
{
199185
std::lock_guard<std::mutex> lock(mutex_);
200186
overlay_->updateTextureSize(property_width_->getInt(), property_height_->getInt());
@@ -205,12 +191,6 @@ void MissionDetailsDisplay::updateOverlaySize()
205191
queueRender();
206192
}
207193

208-
void MissionDetailsDisplay::updateOverlayColor()
209-
{
210-
std::lock_guard<std::mutex> lock(mutex_);
211-
queueRender();
212-
}
213-
214194
void MissionDetailsDisplay::topic_updated_remaining_distance_time()
215195
{
216196
// resubscribe to the topic
@@ -222,7 +202,7 @@ void MissionDetailsDisplay::topic_updated_remaining_distance_time()
222202
remaining_distance_time_topic_property_->getTopicStd(),
223203
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
224204
[this](const autoware_internal_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) {
225-
updateRemainingDistanceTimeData(msg);
205+
cb_remaining_distance_time(msg);
226206
});
227207
}
228208

0 commit comments

Comments
 (0)