Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: add steer tire angle gain #67

Merged
merged 2 commits into from
Sep 5, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -208,6 +208,7 @@
<param name="lookahead_gain" value="0.3"/>
<param name="lookahead_min_distance" value="4.0"/>
<param name="speed_proportional_gain" value="1.0"/>
<param name="steering_tire_angle_gain" value="1.639"/>

<remap from="input/kinematics" to="/localization/kinematic_state"/>
<remap from="input/trajectory" to="/planning/scenario_planning/trajectory"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ class SimplePurePursuit : public rclcpp::Node {
const double speed_proportional_gain_;
const bool use_external_target_vel_;
const double external_target_vel_;
const double steering_tire_angle_gain_;


private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,8 @@ SimplePurePursuit::SimplePurePursuit()
lookahead_min_distance_(declare_parameter<float>("lookahead_min_distance", 1.0)),
speed_proportional_gain_(declare_parameter<float>("speed_proportional_gain", 1.0)),
use_external_target_vel_(declare_parameter<bool>("use_external_target_vel", false)),
external_target_vel_(declare_parameter<float>("external_target_vel", 0.0))
external_target_vel_(declare_parameter<float>("external_target_vel", 0.0)),
steering_tire_angle_gain_(declare_parameter<float>("steering_tire_angle_gain", 1.0))
{
pub_cmd_ = create_publisher<AckermannControlCommand>("output/control_cmd", 1);

Expand Down Expand Up @@ -105,7 +106,7 @@ void SimplePurePursuit::onTimer()
double alpha = std::atan2(lookahead_point_y - rear_y, lookahead_point_x - rear_x) -
tf2::getYaw(odometry_->pose.pose.orientation);
cmd.lateral.steering_tire_angle =
std::atan2(2.0 * wheel_base_ * std::sin(alpha), lookahead_distance);
steering_tire_angle_gain_ * std::atan2(2.0 * wheel_base_ * std::sin(alpha), lookahead_distance);
}
pub_cmd_->publish(cmd);
}
Expand Down