Skip to content

Commit 6029eae

Browse files
authored
feat: add handle angle scale property to signal display (#7774)
* feat: add handle angle scale property to signal display * fix: set default steering angle to 0.0° when not received Signed-off-by: KhalilSelyan <khalil@leodrive.ai> * fix: set default steering angle to N/A when not received and check for msg_ptr instead of float value Signed-off-by: KhalilSelyan <khalil@leodrive.ai> * chore: update steering wheel font size and wheel icon center is bigger Signed-off-by: KhalilSelyan <khalil@leodrive.ai> * chore: update steering wheel display to center the steering angle text Signed-off-by: KhalilSelyan <khalil@leodrive.ai> * chore: align steering angle text in both negative and positive cases Signed-off-by: KhalilSelyan <khalil@leodrive.ai> --------- Signed-off-by: KhalilSelyan <khalil@leodrive.ai>
1 parent c1dbd5b commit 6029eae

File tree

5 files changed

+45
-16
lines changed

5 files changed

+45
-16
lines changed
Loading

Diff for: common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,7 @@ private Q_SLOTS:
7676
rviz_common::properties::IntProperty * property_left_;
7777
rviz_common::properties::IntProperty * property_top_;
7878
rviz_common::properties::ColorProperty * property_signal_color_;
79+
rviz_common::properties::FloatProperty * property_handle_angle_scale_;
7980
std::unique_ptr<rviz_common::properties::RosTopicProperty> steering_topic_property_;
8081
std::unique_ptr<rviz_common::properties::RosTopicProperty> gear_topic_property_;
8182
std::unique_ptr<rviz_common::properties::RosTopicProperty> speed_topic_property_;

Diff for: common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/steering_wheel_display.hpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,8 @@ class SteeringWheelDisplay
3636
{
3737
public:
3838
SteeringWheelDisplay();
39-
void drawSteeringWheel(QPainter & painter, const QRectF & backgroundRect);
39+
void drawSteeringWheel(
40+
QPainter & painter, const QRectF & backgroundRect, float handle_angle_scale_);
4041
void updateSteeringData(const autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr & msg);
4142

4243
private:
@@ -46,6 +47,7 @@ class SteeringWheelDisplay
4647
QImage wheelImage;
4748
QImage scaledWheelImage;
4849
QImage coloredImage(const QImage & source, const QColor & color);
50+
autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr last_msg_ptr_;
4951
};
5052

5153
} // namespace autoware_overlay_rviz_plugin

Diff for: common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,9 @@ SignalDisplay::SignalDisplay()
4949
property_signal_color_ = new rviz_common::properties::ColorProperty(
5050
"Signal Color", QColor(QString("#00E678")), "Color of the signal arrows", this,
5151
SLOT(updateOverlayColor()));
52+
property_handle_angle_scale_ = new rviz_common::properties::FloatProperty(
53+
"Handle Angle Scale", 17.0, "Scale of the steering wheel handle angle", this,
54+
SLOT(updateOverlaySize()));
5255

5356
// Initialize the component displays
5457
steering_wheel_display_ = std::make_unique<SteeringWheelDisplay>();
@@ -285,7 +288,8 @@ void SignalDisplay::drawWidget(QImage & hud)
285288
}
286289

287290
if (steering_wheel_display_) {
288-
steering_wheel_display_->drawSteeringWheel(painter, backgroundRect);
291+
steering_wheel_display_->drawSteeringWheel(
292+
painter, backgroundRect, property_handle_angle_scale_->getFloat());
289293
}
290294

291295
if (speed_display_) {

Diff for: common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp

+36-14
Original file line numberDiff line numberDiff line change
@@ -59,19 +59,17 @@ void SteeringWheelDisplay::updateSteeringData(
5959
const autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr & msg)
6060
{
6161
try {
62-
// Assuming msg->steering_angle is the field you're interested in
63-
float steeringAngle = msg->steering_tire_angle;
64-
// we received it as a radian value, but we want to display it in degrees
65-
steering_angle_ =
66-
(steeringAngle * -180 / M_PI) *
67-
17; // 17 is the ratio between the steering wheel and the steering tire angle i assume
62+
last_msg_ptr_ = msg;
63+
64+
steering_angle_ = msg->steering_tire_angle;
6865
} catch (const std::exception & e) {
6966
// Log the error
7067
std::cerr << "Error in processMessage: " << e.what() << std::endl;
7168
}
7269
}
7370

74-
void SteeringWheelDisplay::drawSteeringWheel(QPainter & painter, const QRectF & backgroundRect)
71+
void SteeringWheelDisplay::drawSteeringWheel(
72+
QPainter & painter, const QRectF & backgroundRect, float handle_angle_scale_)
7573
{
7674
// Enable Antialiasing for smoother drawing
7775
painter.setRenderHint(QPainter::Antialiasing, true);
@@ -80,7 +78,7 @@ void SteeringWheelDisplay::drawSteeringWheel(QPainter & painter, const QRectF &
8078
QImage wheel = coloredImage(scaledWheelImage, gray);
8179

8280
// Rotate the wheel
83-
float steeringAngle = steering_angle_; // No need to round here
81+
float steeringAngle = std::round(handle_angle_scale_ * (steering_angle_ / M_PI) * -180.0);
8482
// Calculate the position
8583
int wheelCenterX = backgroundRect.left() + wheel.width() + 54 + 54;
8684
int wheelCenterY = backgroundRect.height() / 2;
@@ -99,16 +97,40 @@ void SteeringWheelDisplay::drawSteeringWheel(QPainter & painter, const QRectF &
9997
// Draw the rotated image
10098
painter.drawImage(drawPoint.x(), drawPoint.y(), rotatedWheel);
10199

102-
QString steeringAngleStringAfterModulo = QString::number(fmod(steeringAngle, 360), 'f', 0);
100+
std::ostringstream steering_angle_ss;
101+
if (last_msg_ptr_) {
102+
steering_angle_ss << std::fixed << std::setprecision(1) << steering_angle_ * 180.0 / M_PI
103+
<< "°";
104+
} else {
105+
steering_angle_ss << "N/A";
106+
}
107+
108+
QString steeringAngleString = QString::fromStdString(steering_angle_ss.str());
109+
// if the string doesn't have a negative sign, add a space to the front of the string
110+
// to align the text in both cases (negative and positive)
111+
if (steeringAngleString[0] != '-') {
112+
steeringAngleString = " " + steeringAngleString;
113+
}
103114

104115
// Draw the steering angle text
105-
QFont steeringFont("Quicksand", 9, QFont::Bold);
116+
QFont steeringFont("Quicksand", 8, QFont::Bold);
106117
painter.setFont(steeringFont);
107118
painter.setPen(QColor(0, 0, 0, 255));
108-
QRect steeringRect(
109-
wheelCenterX - wheelImage.width() / 2, wheelCenterY - wheelImage.height() / 2,
110-
wheelImage.width(), wheelImage.height());
111-
painter.drawText(steeringRect, Qt::AlignCenter, steeringAngleStringAfterModulo + "°");
119+
// QRect steeringRect(
120+
// wheelCenterX - wheelImage.width() / 2 + 1, wheelCenterY - wheelImage.height() / 2,
121+
// wheelImage.width(), wheelImage.height());
122+
// painter.drawText(steeringRect, Qt::AlignCenter, steeringAngleString);
123+
124+
// Measure the text
125+
QFontMetrics fontMetrics(steeringFont);
126+
QRect textRect = fontMetrics.boundingRect(steeringAngleString);
127+
128+
// Center the text
129+
int textX = wheelCenterX - textRect.width() / 2;
130+
int textY = wheelCenterY - textRect.height() / 2;
131+
132+
QRect steeringRect(textX, textY, textRect.width(), textRect.height());
133+
painter.drawText(steeringRect, Qt::AlignCenter, steeringAngleString);
112134
}
113135

114136
QImage SteeringWheelDisplay::coloredImage(const QImage & source, const QColor & color)

0 commit comments

Comments
 (0)