Skip to content

Commit 61a1859

Browse files
author
KhalilSelyan
committed
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>
1 parent b9d07ef commit 61a1859

File tree

2 files changed

+5
-2
lines changed

2 files changed

+5
-2
lines changed

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

+1
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,7 @@ class SteeringWheelDisplay
4747
QImage wheelImage;
4848
QImage scaledWheelImage;
4949
QImage coloredImage(const QImage & source, const QColor & color);
50+
autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr last_msg_ptr_;
5051
};
5152

5253
} // namespace autoware_overlay_rviz_plugin

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

+4-2
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,8 @@ void SteeringWheelDisplay::updateSteeringData(
5959
const autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr & msg)
6060
{
6161
try {
62+
last_msg_ptr_ = msg;
63+
6264
steering_angle_ = msg->steering_tire_angle;
6365
} catch (const std::exception & e) {
6466
// Log the error
@@ -96,11 +98,11 @@ void SteeringWheelDisplay::drawSteeringWheel(
9698
painter.drawImage(drawPoint.x(), drawPoint.y(), rotatedWheel);
9799

98100
std::ostringstream steering_angle_ss;
99-
if (steering_angle_) {
101+
if (last_msg_ptr_) {
100102
steering_angle_ss << std::fixed << std::setprecision(1) << steering_angle_ * 180.0 / M_PI
101103
<< "°";
102104
} else {
103-
steering_angle_ss << "0.0°";
105+
steering_angle_ss << "N/A";
104106
}
105107

106108
QString steeringAngleString = QString::fromStdString(steering_angle_ss.str());

0 commit comments

Comments
 (0)