Skip to content

Commit

Permalink
fix(autoware_overlay_rviz_plugin): fix clang-tidy errors (#9627)
Browse files Browse the repository at this point in the history
* fix: clang-tidy errors

Signed-off-by: kobayu858 <[email protected]>

* fix: clang-fmt

Signed-off-by: kobayu858 <[email protected]>

---------

Signed-off-by: kobayu858 <[email protected]>
  • Loading branch information
kobayu858 authored Dec 12, 2024
1 parent a1dad44 commit 1d9a2be
Show file tree
Hide file tree
Showing 4 changed files with 7 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,8 @@ void SpeedDisplay::drawSpeedDisplay(
painter.setFont(referenceFont);
QRect referenceRect = painter.fontMetrics().boundingRect("88");
QPointF referencePos(
backgroundRect.width() / 2 - referenceRect.width() / 2 - 5, backgroundRect.height() / 2);
backgroundRect.width() / 2.0 - referenceRect.width() / 2.0 - 5.0,
backgroundRect.height() / 2.0);

QString speedNumber = QString::number(current_speed_, 'f', 0);
int fontSize = 40;
Expand All @@ -96,7 +97,7 @@ void SpeedDisplay::drawSpeedDisplay(

// Center the speed number in the backgroundRect
QPointF speedPos(
backgroundRect.center().x() - speedNumberRect.width() / 2,
backgroundRect.center().x() - speedNumberRect.width() / 2.0,
backgroundRect.center().y() + speedNumberRect.bottom());
painter.setPen(color);
painter.drawText(speedPos, speedNumber);
Expand All @@ -106,7 +107,8 @@ void SpeedDisplay::drawSpeedDisplay(
QString speedUnit = "km/h";
QRect unitRect = painter.fontMetrics().boundingRect(speedUnit);
QPointF unitPos(
(backgroundRect.width() / 2 - unitRect.width() / 2), referencePos.y() + unitRect.height() + 15);
(backgroundRect.width() / 2.0 - unitRect.width() / 2.0),
referencePos.y() + unitRect.height() + 15.0);
painter.drawText(unitPos, speedUnit);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ void SteeringWheelDisplay::drawSteeringWheel(
QImage rotatedWheel = wheel.transformed(rotationTransform, Qt::SmoothTransformation);

QPointF drawPoint(
wheelCenterX - rotatedWheel.width() / 2, wheelCenterY - rotatedWheel.height() / 2);
wheelCenterX - rotatedWheel.width() / 2.0, wheelCenterY - rotatedWheel.height() / 2.0);

// Draw the rotated image
painter.drawImage(drawPoint.x(), drawPoint.y(), rotatedWheel);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,9 +83,6 @@ void TrafficDisplay::drawTrafficLightIndicator(QPainter & painter, const QRectF
painter.drawEllipse(circleRect);
break;
case 4:
painter.setBrush(tl_gray_);
painter.drawEllipse(circleRect);
break;
default:
painter.setBrush(tl_gray_);
painter.drawEllipse(circleRect);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ void TurnSignalsDisplay::drawArrows(
QImage scaledLeftArrow = arrowImage.scaled(50, 32, Qt::KeepAspectRatio, Qt::SmoothTransformation);
scaledLeftArrow = coloredImage(scaledLeftArrow, gray);
QImage scaledRightArrow = scaledLeftArrow.mirrored(true, false);
int arrowYPos = (backgroundRect.height() / 2 - scaledLeftArrow.height() / 2 - 4);
int arrowYPos = (backgroundRect.height() / 2.0 - scaledLeftArrow.height() / 2.0 - 4.0);
int leftArrowXPos = backgroundRect.left() + scaledLeftArrow.width() * 2 + 180;
int rightArrowXPos = backgroundRect.right() - scaledRightArrow.width() * 3 - 175;

Expand Down

0 comments on commit 1d9a2be

Please sign in to comment.