Skip to content

Commit

Permalink
feat(vehicle_info_util): add max_steer_angle (tier4#740)
Browse files Browse the repository at this point in the history
* feat(vehicle_info_util): add max_steer_angle

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

* applied pre-commit

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

* Added max_steer_angle in test config

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

Co-authored-by: Tomoya Kimura <tomoya.kimura@tier4.jp>
  • Loading branch information
2 people authored and boyali committed Oct 19, 2022
1 parent 1f01da9 commit 9fb0ec9
Show file tree
Hide file tree
Showing 6 changed files with 11 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -9,3 +9,4 @@
left_overhang: 0.1 # between left wheel center and vehicle left
right_overhang: 0.1 # between right wheel center and vehicle right
vehicle_height: 2.5
max_steer_angle: 0.70 # [rad]
Original file line number Diff line number Diff line change
Expand Up @@ -10,3 +10,4 @@
width_m: 2.0
front_overhang_m: 0.5
rear_overhang_m: 0.5
max_steer_angle: 0.70 # [rad]
Original file line number Diff line number Diff line change
Expand Up @@ -190,6 +190,7 @@ void declareVehicleInfoParams(rclcpp::NodeOptions & node_options)
node_options.append_parameter_override("left_overhang", 0.5);
node_options.append_parameter_override("right_overhang", 0.5);
node_options.append_parameter_override("vehicle_height", 1.5);
node_options.append_parameter_override("max_steer_angle", 0.7);
}

// Send a control command and run the simulation.
Expand Down
1 change: 1 addition & 0 deletions vehicle/vehicle_info_util/config/vehicle_info.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -9,3 +9,4 @@
left_overhang: 0.1 # between left wheel center and vehicle left
right_overhang: 0.1 # between right wheel center and vehicle right
vehicle_height: 2.5
max_steer_angle: 0.70 # [rad]
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ struct VehicleInfo
double left_overhang_m;
double right_overhang_m;
double vehicle_height_m;
double max_steer_angle_m;

// Derived parameters, i.e. calculated from base parameters
// The offset values are relative to the base frame origin, which is located
Expand All @@ -49,7 +50,8 @@ struct VehicleInfo
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 left_overhang_m, const double right_overhang_m, const double vehicle_height_m,
const double max_steer_angle_m)
{
// Calculate derived parameters
const double vehicle_length_m_ = front_overhang_m + wheel_base_m + rear_overhang_m;
Expand All @@ -72,6 +74,7 @@ inline VehicleInfo createVehicleInfo(
left_overhang_m,
right_overhang_m,
vehicle_height_m,
max_steer_angle_m,
// Derived parameters
vehicle_length_m_,
vehicle_width_m_,
Expand Down
4 changes: 3 additions & 1 deletion vehicle/vehicle_info_util/src/vehicle_info_util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,14 +49,16 @@ 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");
}

VehicleInfo VehicleInfoUtil::getVehicleInfo()
{
return createVehicleInfo(
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_.left_overhang_m, vehicle_info_.right_overhang_m, vehicle_info_.vehicle_height_m,
vehicle_info_.max_steer_angle_m);
}

} // namespace vehicle_info_util

0 comments on commit 9fb0ec9

Please sign in to comment.