Skip to content

Commit

Permalink
fix(vehicle_info_util): correct max_steer_angle unit (#1414)
Browse files Browse the repository at this point in the history
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
  • Loading branch information
takayuki5168 authored Jul 25, 2022
1 parent b217a20 commit 5e09191
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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;
Expand All @@ -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_,
Expand Down
4 changes: 2 additions & 2 deletions vehicle/vehicle_info_util/src/vehicle_info_util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ VehicleInfoUtil::VehicleInfoUtil(rclcpp::Node & node)
vehicle_info_.left_overhang_m = getParameter<double>(node, "left_overhang");
vehicle_info_.right_overhang_m = getParameter<double>(node, "right_overhang");
vehicle_info_.vehicle_height_m = getParameter<double>(node, "vehicle_height");
vehicle_info_.max_steer_angle_m = getParameter<double>(node, "max_steer_angle");
vehicle_info_.max_steer_angle_rad = getParameter<double>(node, "max_steer_angle");
}

VehicleInfo VehicleInfoUtil::getVehicleInfo()
Expand All @@ -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

0 comments on commit 5e09191

Please sign in to comment.