14
14
15
15
#include " remaining_distance_time_display.hpp"
16
16
17
+ #include < QColor>
17
18
#include < QFontDatabase>
18
19
#include < QPainter>
19
20
#include < ament_index_cpp/get_package_share_directory.hpp>
@@ -45,12 +46,10 @@ RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay()
45
46
46
47
std::string dist_image = package_path + " /assets/path.png" ;
47
48
std::string time_image = package_path + " /assets/av_timer.png" ;
48
- distToGoalFlag.load (dist_image.c_str ());
49
- timeToGoalFlag.load (time_image.c_str ());
50
- scaledDistToGoalFlag =
51
- distToGoalFlag.scaled (32 , 32 , Qt::KeepAspectRatio, Qt::SmoothTransformation);
52
- scaledTimeToGoalFlag =
53
- timeToGoalFlag.scaled (32 , 32 , Qt::KeepAspectRatio, Qt::SmoothTransformation);
49
+ icon_dist_.load (dist_image.c_str ());
50
+ icon_time_.load (time_image.c_str ());
51
+ icon_dist_scaled_ = icon_dist_.scaled (28 , 28 , Qt::KeepAspectRatio, Qt::SmoothTransformation);
52
+ icon_time_scaled_ = icon_time_.scaled (28 , 28 , Qt::KeepAspectRatio, Qt::SmoothTransformation);
54
53
}
55
54
56
55
void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData (
@@ -63,100 +62,94 @@ void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData(
63
62
void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay (
64
63
QPainter & painter, const QRectF & backgroundRect)
65
64
{
66
- QFont referenceFont (" Quicksand" , 80 , QFont::Bold);
67
- painter.setFont (referenceFont);
68
- QRect referenceRect = painter.fontMetrics ().boundingRect (" 88" );
69
- QPointF remainingDistReferencePos (
70
- backgroundRect.width () / 2 - referenceRect.width () / 2 , backgroundRect.height () / 3 );
71
-
72
- QPointF remainingTimeReferencePos (
73
- backgroundRect.width () / 2 - referenceRect.width () / 2 , backgroundRect.height () / 1.3 );
74
-
75
- // ----------------- Remaining Distance -----------------
76
-
77
- int fontSize = 15 ;
78
- QFont remainingDistancTimeFont (" Quicksand" , fontSize, QFont::Bold);
79
- painter.setFont (remainingDistancTimeFont);
80
-
81
- // Remaining distance icon
82
- QPointF remainingDistanceIconPos (
83
- remainingDistReferencePos.x () - 25 , remainingDistReferencePos.y ());
84
- painter.drawImage (
85
- remainingDistanceIconPos.x (),
86
- remainingDistanceIconPos.y () - scaledDistToGoalFlag.height () / 2.0 , scaledDistToGoalFlag);
87
-
88
- // Remaining distance value
89
- QString remainingDistanceValue = QString::number (
90
- remaining_distance_ > 1000 ? remaining_distance_ / 1000 : remaining_distance_, ' f' , 0 );
91
- QPointF remainingDistancePos;
92
- switch (remainingDistanceValue.size ()) {
93
- case 1 :
94
- remainingDistancePos =
95
- QPointF (remainingDistReferencePos.x () + 55 , remainingDistReferencePos.y () + 10 );
96
- break ;
97
- case 2 :
98
- remainingDistancePos =
99
- QPointF (remainingDistReferencePos.x () + 50 , remainingDistReferencePos.y () + 10 );
100
- break ;
101
- case 3 :
102
- remainingDistancePos =
103
- QPointF (remainingDistReferencePos.x () + 45 , remainingDistReferencePos.y () + 10 );
104
- break ;
105
- case 4 :
106
- remainingDistancePos =
107
- QPointF (remainingDistReferencePos.x () + 40 , remainingDistReferencePos.y () + 10 );
108
- break ;
109
- default :
110
- remainingDistancePos =
111
- QPointF (remainingDistReferencePos.x () + 55 , remainingDistReferencePos.y () + 10 );
112
- break ;
65
+ const QFont font (" Quicksand" , 15 , QFont::Bold);
66
+ painter.setFont (font);
67
+
68
+ // We'll display the distance and time in two rows
69
+
70
+ auto calculate_inner_rect = [](const QRectF & outer_rect, double ratio_x, double ratio_y) {
71
+ QSizeF size_inner (outer_rect.width () * ratio_x, outer_rect.height () * ratio_y);
72
+ QPointF top_left_inner = QPointF (
73
+ outer_rect.center ().x () - size_inner.width () / 2 ,
74
+ outer_rect.center ().y () - size_inner.height () / 2 );
75
+ return QRectF (top_left_inner, size_inner);
76
+ };
77
+
78
+ const QRectF rect_inner = calculate_inner_rect (backgroundRect, 0.7 , 0.7 );
79
+
80
+ // Calculate distance row rectangle
81
+ const QSizeF distance_row_size (rect_inner.width (), rect_inner.height () / 2 );
82
+ const QPointF distance_row_top_left (rect_inner.topLeft ());
83
+ const QRectF distance_row_rect_outer (distance_row_top_left, distance_row_size);
84
+
85
+ // Calculate time row rectangle
86
+ const QSizeF time_row_size (rect_inner.width (), rect_inner.height () / 2 );
87
+ const QPointF time_row_top_left (
88
+ rect_inner.topLeft ().x (), rect_inner.topLeft ().y () + rect_inner.height () / 2 );
89
+ const QRectF time_row_rect_outer (time_row_top_left, time_row_size);
90
+
91
+ const auto rect_time = calculate_inner_rect (time_row_rect_outer, 1.0 , 0.9 );
92
+ const auto rect_dist = calculate_inner_rect (distance_row_rect_outer, 1.0 , 0.9 );
93
+
94
+ auto place_row = [&, this ](
95
+ const QRectF & rect, const QImage & icon, const QString & str_value,
96
+ const QString & str_unit) {
97
+ // order: icon, value, unit
98
+
99
+ // place the icon
100
+ QPointF icon_top_left (rect.topLeft ().x (), rect.center ().y () - icon.height () / 2.0 );
101
+ painter.drawImage (icon_top_left, icon);
102
+
103
+ // place the unit text
104
+ const float unit_width = 40.0 ;
105
+ QRectF rect_text_unit (
106
+ rect.topRight ().x () - unit_width, rect.topRight ().y (), unit_width, rect.height ());
107
+
108
+ painter.setPen (gray);
109
+ painter.drawText (rect_text_unit, Qt::AlignLeft | Qt::AlignVCenter, str_unit);
110
+
111
+ // place the value text
112
+ const double margin_x = 5.0 ; // margin around the text
113
+
114
+ const double used_width = icon.width () + rect_text_unit.width () + margin_x * 2.0 ;
115
+
116
+ QRectF rect_text (
117
+ rect.topLeft ().x () + icon.width () + margin_x, rect.topLeft ().y (), rect.width () - used_width,
118
+ rect.height ());
119
+
120
+ painter.drawText (rect_text, Qt::AlignRight | Qt::AlignVCenter, str_value);
121
+ };
122
+
123
+ // remaining_time_ is in seconds
124
+ if (remaining_time_ <= 60 ) {
125
+ place_row (rect_time, icon_time_scaled_, QString::number (remaining_time_, ' f' , 0 ), " sec" );
126
+ } else if (remaining_time_ <= 600 ) {
127
+ place_row (rect_time, icon_time_scaled_, QString::number (remaining_time_ / 60.0 , ' f' , 1 ), " min" );
128
+ } else if (remaining_time_ <= 3600 ) {
129
+ place_row (rect_time, icon_time_scaled_, QString::number (remaining_time_ / 60.0 , ' f' , 0 ), " min" );
130
+ } else if (remaining_time_ <= 36000 ) {
131
+ place_row (
132
+ rect_time, icon_time_scaled_, QString::number (remaining_time_ / 3600.0 , ' f' , 1 ), " hrs" );
133
+ } else {
134
+ place_row (
135
+ rect_time, icon_time_scaled_, QString::number (remaining_time_ / 3600.0 , ' f' , 0 ), " hrs" );
136
+ }
137
+
138
+ // remaining_distance_ is in meters
139
+ if (remaining_distance_ <= 10 ) {
140
+ place_row (rect_dist, icon_dist_scaled_, QString::number (remaining_distance_, ' f' , 1 ), " m" );
141
+ } else if (remaining_distance_ <= 1000 ) {
142
+ place_row (rect_dist, icon_dist_scaled_, QString::number (remaining_distance_, ' f' , 0 ), " m" );
143
+ } else if (remaining_distance_ <= 10000 ) {
144
+ place_row (
145
+ rect_dist, icon_dist_scaled_, QString::number (remaining_distance_ / 1000.0 , ' f' , 2 ), " km" );
146
+ } else if (remaining_distance_ <= 100000 ) {
147
+ place_row (
148
+ rect_dist, icon_dist_scaled_, QString::number (remaining_distance_ / 1000.0 , ' f' , 1 ), " km" );
149
+ } else {
150
+ place_row (
151
+ rect_dist, icon_dist_scaled_, QString::number (remaining_distance_ / 1000.0 , ' f' , 0 ), " km" );
113
152
}
114
- painter.setPen (gray);
115
- painter.drawText (remainingDistancePos, remainingDistanceValue);
116
-
117
- // Remaining distance unit
118
- QString remainingDistUnitText = remaining_distance_ > 1000 ? " km" : " meter" ;
119
- QPointF remainingDistancUnitPos (
120
- remainingDistReferencePos.x () + 80 , remainingDistReferencePos.y () + 10 );
121
- painter.drawText (remainingDistancUnitPos, remainingDistUnitText);
122
-
123
- // ----------------- Remaining Time -----------------
124
- // Remaining time icon
125
- painter.drawImage (
126
- remainingDistanceIconPos.x (),
127
- remainingDistanceIconPos.y () + scaledTimeToGoalFlag.height () / 2.0 , scaledTimeToGoalFlag);
128
-
129
- // Calculate remaining minutes and seconds
130
- double remaining_time_mod = std::fmod (remaining_time_, 3600 );
131
- uint8_t remaining_minutes = static_cast <uint8_t >(remaining_time_mod / 60.0 );
132
- uint8_t remaining_seconds = static_cast <uint8_t >(std::fmod (remaining_time_mod, 60 ));
133
-
134
- // Remaining minutes value
135
- QString remainingminutesValue =
136
- QString::number (remaining_minutes != 0 ? remaining_minutes : 0 , ' f' , 0 );
137
- QPointF remainingminutesValuePos (
138
- remainingTimeReferencePos.x () + 55 , remainingTimeReferencePos.y ());
139
- painter.setPen (gray);
140
- if (remaining_minutes > 0 ) painter.drawText (remainingminutesValuePos, remainingminutesValue);
141
- // Remaining minutes separator
142
- QString minutesSeparatorText = " m" ;
143
- QPointF minutesSeparatorTextPos (
144
- remainingTimeReferencePos.x () + 80 , remainingTimeReferencePos.y ());
145
- if (remaining_minutes > 0 ) painter.drawText (minutesSeparatorTextPos, minutesSeparatorText);
146
-
147
- // Remaining seconds value
148
- QString remainingsecondsValue =
149
- QString::number (remaining_seconds != 0 ? remaining_seconds : 0 , ' f' , 0 );
150
- QPointF remainingsecondValuePos (
151
- remainingTimeReferencePos.x () + 55 , remainingTimeReferencePos.y ());
152
- painter.setPen (gray);
153
- if (remaining_minutes <= 0 ) painter.drawText (remainingsecondValuePos, remainingsecondsValue);
154
-
155
- // Remaining seconds separator
156
- QString secondsSeparatorText = " s" ;
157
- QPointF secondsSeparatorTextPos (
158
- remainingTimeReferencePos.x () + 80 , remainingTimeReferencePos.y ());
159
- if (remaining_minutes <= 0 ) painter.drawText (secondsSeparatorTextPos, secondsSeparatorText);
160
153
}
161
154
162
155
} // namespace autoware::mission_details_overlay_rviz_plugin
0 commit comments