From 5e0919115d216e5139201299a3542e066079032d Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 25 Jul 2022 20:19:19 +0900 Subject: [PATCH] fix(vehicle_info_util): correct max_steer_angle unit (#1414) Signed-off-by: Takayuki Murooka --- .../include/vehicle_info_util/vehicle_info.hpp | 6 +++--- vehicle/vehicle_info_util/src/vehicle_info_util.cpp | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp b/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp index 8df6d4cfe04c1..0a866380685ad 100644 --- a/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp +++ b/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp @@ -31,7 +31,7 @@ struct VehicleInfo double left_overhang_m; double right_overhang_m; double vehicle_height_m; - double max_steer_angle_m; + double max_steer_angle_rad; // Derived parameters, i.e. calculated from base parameters // The offset values are relative to the base frame origin, which is located @@ -51,7 +51,7 @@ inline VehicleInfo createVehicleInfo( const double wheel_radius_m, const double wheel_width_m, const double wheel_base_m, const double wheel_tread_m, const double front_overhang_m, const double rear_overhang_m, const double left_overhang_m, const double right_overhang_m, const double vehicle_height_m, - const double max_steer_angle_m) + const double max_steer_angle_rad) { // Calculate derived parameters const double vehicle_length_m_ = front_overhang_m + wheel_base_m + rear_overhang_m; @@ -74,7 +74,7 @@ inline VehicleInfo createVehicleInfo( left_overhang_m, right_overhang_m, vehicle_height_m, - max_steer_angle_m, + max_steer_angle_rad, // Derived parameters vehicle_length_m_, vehicle_width_m_, diff --git a/vehicle/vehicle_info_util/src/vehicle_info_util.cpp b/vehicle/vehicle_info_util/src/vehicle_info_util.cpp index c295155727e61..aec820a4dca6e 100644 --- a/vehicle/vehicle_info_util/src/vehicle_info_util.cpp +++ b/vehicle/vehicle_info_util/src/vehicle_info_util.cpp @@ -49,7 +49,7 @@ VehicleInfoUtil::VehicleInfoUtil(rclcpp::Node & node) vehicle_info_.left_overhang_m = getParameter(node, "left_overhang"); vehicle_info_.right_overhang_m = getParameter(node, "right_overhang"); vehicle_info_.vehicle_height_m = getParameter(node, "vehicle_height"); - vehicle_info_.max_steer_angle_m = getParameter(node, "max_steer_angle"); + vehicle_info_.max_steer_angle_rad = getParameter(node, "max_steer_angle"); } VehicleInfo VehicleInfoUtil::getVehicleInfo() @@ -58,7 +58,7 @@ VehicleInfo VehicleInfoUtil::getVehicleInfo() vehicle_info_.wheel_radius_m, vehicle_info_.wheel_width_m, vehicle_info_.wheel_base_m, vehicle_info_.wheel_tread_m, vehicle_info_.front_overhang_m, vehicle_info_.rear_overhang_m, vehicle_info_.left_overhang_m, vehicle_info_.right_overhang_m, vehicle_info_.vehicle_height_m, - vehicle_info_.max_steer_angle_m); + vehicle_info_.max_steer_angle_rad); } } // namespace vehicle_info_util