Skip to content

Commit fb67bab

Browse files
author
KhalilSelyan
committed
feat: add handle angle scale property to signal display
1 parent f4efb91 commit fb67bab

File tree

4 files changed

+22
-12
lines changed

4 files changed

+22
-12
lines changed

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

+2-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:

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

+14-10
Original file line numberDiff line numberDiff line change
@@ -59,19 +59,15 @@ 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+
steering_angle_ = msg->steering_tire_angle;
6863
} catch (const std::exception & e) {
6964
// Log the error
7065
std::cerr << "Error in processMessage: " << e.what() << std::endl;
7166
}
7267
}
7368

74-
void SteeringWheelDisplay::drawSteeringWheel(QPainter & painter, const QRectF & backgroundRect)
69+
void SteeringWheelDisplay::drawSteeringWheel(
70+
QPainter & painter, const QRectF & backgroundRect, float handle_angle_scale_)
7571
{
7672
// Enable Antialiasing for smoother drawing
7773
painter.setRenderHint(QPainter::Antialiasing, true);
@@ -80,7 +76,7 @@ void SteeringWheelDisplay::drawSteeringWheel(QPainter & painter, const QRectF &
8076
QImage wheel = coloredImage(scaledWheelImage, gray);
8177

8278
// Rotate the wheel
83-
float steeringAngle = steering_angle_; // No need to round here
79+
float steeringAngle = std::round(handle_angle_scale_ * (steering_angle_ / M_PI) * -180.0);
8480
// Calculate the position
8581
int wheelCenterX = backgroundRect.left() + wheel.width() + 54 + 54;
8682
int wheelCenterY = backgroundRect.height() / 2;
@@ -99,7 +95,15 @@ void SteeringWheelDisplay::drawSteeringWheel(QPainter & painter, const QRectF &
9995
// Draw the rotated image
10096
painter.drawImage(drawPoint.x(), drawPoint.y(), rotatedWheel);
10197

102-
QString steeringAngleStringAfterModulo = QString::number(fmod(steeringAngle, 360), 'f', 0);
98+
std::ostringstream steering_angle_ss;
99+
if (steering_angle_) {
100+
steering_angle_ss << std::fixed << std::setprecision(1) << steering_angle_ * 180.0 / M_PI
101+
<< "°";
102+
} else {
103+
steering_angle_ss << "Not received";
104+
}
105+
106+
QString steeringAngleString = QString::fromStdString(steering_angle_ss.str());
103107

104108
// Draw the steering angle text
105109
QFont steeringFont("Quicksand", 9, QFont::Bold);
@@ -108,7 +112,7 @@ void SteeringWheelDisplay::drawSteeringWheel(QPainter & painter, const QRectF &
108112
QRect steeringRect(
109113
wheelCenterX - wheelImage.width() / 2, wheelCenterY - wheelImage.height() / 2,
110114
wheelImage.width(), wheelImage.height());
111-
painter.drawText(steeringRect, Qt::AlignCenter, steeringAngleStringAfterModulo + "°");
115+
painter.drawText(steeringRect, Qt::AlignCenter, steeringAngleString);
112116
}
113117

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

0 commit comments

Comments
 (0)