steering_offset.cpp 2.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778
  1. // Copyright 2018-2023 The Autoware Foundation
  2. //
  3. // Licensed under the Apache License, Version 2.0 (the "License");
  4. // you may not use this file except in compliance with the License.
  5. // You may obtain a copy of the License at
  6. //
  7. // http://www.apache.org/licenses/LICENSE-2.0
  8. //
  9. // Unless required by applicable law or agreed to in writing, software
  10. // distributed under the License is distributed on an "AS IS" BASIS,
  11. // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  12. // See the License for the specific language governing permissions and
  13. // limitations under the License.
  14. #include "mpc_lateral_controller/steering_offset/steering_offset.hpp"
  15. #include <algorithm>
  16. #include <iostream>
  17. #include <numeric>
  18. SteeringOffsetEstimator::SteeringOffsetEstimator(
  19. double wheelbase, double average_num, double vel_thres, double steer_thres, double offset_limit)
  20. : wheelbase_(wheelbase),
  21. average_num_(average_num),
  22. update_vel_threshold_(vel_thres),
  23. update_steer_threshold_(steer_thres),
  24. offset_limit_(offset_limit),
  25. steering_offset_storage_(average_num, 0.0)
  26. {
  27. }
  28. void SteeringOffsetEstimator::updateOffset(const double vel,const double yaw_v, const double steering)
  29. {
  30. const bool update_offset =
  31. (std::abs(vel) > update_vel_threshold_ &&
  32. std::abs(steering) < update_steer_threshold_);
  33. if (!update_offset) return;
  34. const auto steer_angvel = std::atan2(yaw_v * wheelbase_, vel);
  35. const auto steer_offset = steering - steer_angvel;
  36. steering_offset_storage_.push_back(steer_offset);
  37. if (steering_offset_storage_.size() > average_num_) {
  38. steering_offset_storage_.pop_front();
  39. }
  40. steering_offset_ =
  41. std::accumulate(std::begin(steering_offset_storage_), std::end(steering_offset_storage_), 0.0) /
  42. std::size(steering_offset_storage_);
  43. }
  44. //void SteeringOffsetEstimator::updateOffset(
  45. // const geometry_msgs::msg::Twist & twist, const double steering)
  46. //{
  47. // const bool update_offset =
  48. // (std::abs(twist.linear.x) > update_vel_threshold_ &&
  49. // std::abs(steering) < update_steer_threshold_);
  50. // if (!update_offset) return;
  51. // const auto steer_angvel = std::atan2(twist.angular.z * wheelbase_, twist.linear.x);
  52. // const auto steer_offset = steering - steer_angvel;
  53. // steering_offset_storage_.push_back(steer_offset);
  54. // if (steering_offset_storage_.size() > average_num_) {
  55. // steering_offset_storage_.pop_front();
  56. // }
  57. // steering_offset_ =
  58. // std::accumulate(std::begin(steering_offset_storage_), std::end(steering_offset_storage_), 0.0) /
  59. // std::size(steering_offset_storage_);
  60. //}
  61. double SteeringOffsetEstimator::getOffset() const
  62. {
  63. return std::clamp(steering_offset_, -offset_limit_, offset_limit_);
  64. }