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

refactor(mpc_lateral_controller): minor refactor for updateOffset #5314

Closed
Show file tree
Hide file tree
Changes from 1 commit
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 @@ -30,7 +30,7 @@ class SteeringOffsetEstimator
~SteeringOffsetEstimator() = default;

double getOffset() const;
void updateOffset(const geometry_msgs::msg::Twist & twist, const double steering);
void updateOffset(const geometry_msgs::msg::Twist & twist, const double measured_steering_angle);

private:
// parameters
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,16 +30,19 @@ SteeringOffsetEstimator::SteeringOffsetEstimator(
}

void SteeringOffsetEstimator::updateOffset(
const geometry_msgs::msg::Twist & twist, const double steering)
const geometry_msgs::msg::Twist & twist, const double measured_steering_angle)
{
const bool update_offset =
(std::abs(twist.linear.x) > update_vel_threshold_ &&
std::abs(steering) < update_steer_threshold_);
std::abs(measured_steering_angle) < update_steer_threshold_);

if (!update_offset) return;

const auto steer_angvel = std::atan2(twist.angular.z * wheelbase_, twist.linear.x);
const auto steer_offset = steering - steer_angvel;
// calculate the steering angle needed to achieve the current rate of rotation given the current
// velocity along the x-axis of the vehicle, under the below assumptions
// (i.e., no slipping, no lag in the steering mechanism, etc.).
kyoichi-sugahara marked this conversation as resolved.
Show resolved Hide resolved
const auto expected_steering_angle = std::atan2(twist.angular.z * wheelbase_, twist.linear.x);
const auto steer_offset = measured_steering_angle - expected_steering_angle;
steering_offset_storage_.push_back(steer_offset);
if (steering_offset_storage_.size() > average_num_) {
steering_offset_storage_.pop_front();
Expand Down
Loading