@@ -59,19 +59,15 @@ void SteeringWheelDisplay::updateSteeringData(
59
59
const autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr & msg)
60
60
{
61
61
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 ;
68
63
} catch (const std::exception & e) {
69
64
// Log the error
70
65
std::cerr << " Error in processMessage: " << e.what () << std::endl;
71
66
}
72
67
}
73
68
74
- void SteeringWheelDisplay::drawSteeringWheel (QPainter & painter, const QRectF & backgroundRect)
69
+ void SteeringWheelDisplay::drawSteeringWheel (
70
+ QPainter & painter, const QRectF & backgroundRect, float handle_angle_scale_)
75
71
{
76
72
// Enable Antialiasing for smoother drawing
77
73
painter.setRenderHint (QPainter::Antialiasing, true );
@@ -80,7 +76,7 @@ void SteeringWheelDisplay::drawSteeringWheel(QPainter & painter, const QRectF &
80
76
QImage wheel = coloredImage (scaledWheelImage, gray);
81
77
82
78
// 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 );
84
80
// Calculate the position
85
81
int wheelCenterX = backgroundRect.left () + wheel.width () + 54 + 54 ;
86
82
int wheelCenterY = backgroundRect.height () / 2 ;
@@ -99,7 +95,15 @@ void SteeringWheelDisplay::drawSteeringWheel(QPainter & painter, const QRectF &
99
95
// Draw the rotated image
100
96
painter.drawImage (drawPoint.x (), drawPoint.y (), rotatedWheel);
101
97
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 ());
103
107
104
108
// Draw the steering angle text
105
109
QFont steeringFont (" Quicksand" , 9 , QFont::Bold);
@@ -108,7 +112,7 @@ void SteeringWheelDisplay::drawSteeringWheel(QPainter & painter, const QRectF &
108
112
QRect steeringRect (
109
113
wheelCenterX - wheelImage.width () / 2 , wheelCenterY - wheelImage.height () / 2 ,
110
114
wheelImage.width (), wheelImage.height ());
111
- painter.drawText (steeringRect, Qt::AlignCenter, steeringAngleStringAfterModulo + " ° " );
115
+ painter.drawText (steeringRect, Qt::AlignCenter, steeringAngleString );
112
116
}
113
117
114
118
QImage SteeringWheelDisplay::coloredImage (const QImage & source, const QColor & color)
0 commit comments