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(accel_brake_map_calibrator): add new Recursive Least Square method #1255

Merged

Conversation

td12321
Copy link
Contributor

@td12321 td12321 commented Jul 6, 2022

Description

For accel_map_calibrator, implemented a new method to execute Recursive Least Squares on 4 points around new data.

Related links

Gabrielle Lochrie, Michael Doljevic, Mario Nona, Yongsoon Yoon, Anti-Windup Recursive Least Squares Method for Adaptive Lookup Tables with Application to Automotive Powertrain Control Systems, IFAC-PapersOnLine, Volume 54, Issue 20, 2021, Pages 840-845

Tests performed

run accel_brake_map_calibrator and play a rosbag data.

Notes for reviewers

Pre-review checklist for the PR author

The PR author must check the checkboxes below when creating the PR.

In-review checklist for the PR reviewers

The PR reviewers must check the checkboxes below before approval.

  • The PR follows the pull request guidelines.
  • The PR has been properly tested.
  • The PR has been reviewed by the code owners.

Post-review checklist for the PR author

The PR author must check the checkboxes below before merging.

  • There are no open discussions or they are tracked via tickets.
  • The PR is ready for merge.

After all checkboxes are checked, anyone who has write access can merge the PR.

@TakaHoribe TakaHoribe force-pushed the feature/improve_map_calibrator branch from c7b996d to 1d86132 Compare July 17, 2022 05:01
@TakaHoribe
Copy link
Contributor

I rebased to autowarefoundation/main. The original code was saved in my fork just for in case.
https://github.com/TakaHoribe/autoware.universe/tree/feature/improve_map_calibrator-ORIGINAL

@TakaHoribe TakaHoribe self-requested a review July 17, 2022 05:02
@codecov
Copy link

codecov bot commented Jul 17, 2022

Codecov Report

Base: 10.82% // Head: 10.36% // Decreases project coverage by -0.46% ⚠️

Coverage data is based on head (f08ea59) compared to base (e009b13).
Patch coverage: 0.00% of modified lines in pull request are covered.

Additional details and impacted files
@@            Coverage Diff             @@
##             main    #1255      +/-   ##
==========================================
- Coverage   10.82%   10.36%   -0.47%     
==========================================
  Files        1178     1170       -8     
  Lines       84624    84005     -619     
  Branches    19947    19581     -366     
==========================================
- Hits         9159     8704     -455     
- Misses      65756    65795      +39     
+ Partials     9709     9506     -203     
Flag Coverage Δ *Carryforward flag
differential 0.00% <0.00%> (?)
total 10.39% <0.00%> (-0.41%) ⬇️ Carriedforward from af09aa7

*This pull request uses carry forward flags. Click here to find out more.

Impacted Files Coverage Δ
...map_calibrator/accel_brake_map_calibrator_node.hpp 0.00% <ø> (ø)
...calibrator/src/accel_brake_map_calibrator_node.cpp 0.00% <0.00%> (ø)
...lude/freespace_planning_algorithms/reeds_shepp.hpp 50.00% <0.00%> (-50.00%) ⬇️
.../freespace_planning_algorithms/src/reeds_shepp.cpp 55.51% <0.00%> (-38.97%) ⬇️
...ehicle/raw_vehicle_cmd_converter/src/brake_map.cpp 17.85% <0.00%> (-27.31%) ⬇️
...eespace_planning_algorithms/abstract_algorithm.hpp 44.44% <0.00%> (-25.56%) ⬇️
...lude/behavior_path_planner/turn_signal_decider.hpp 25.00% <0.00%> (-25.00%) ⬇️
...ehicle/raw_vehicle_cmd_converter/src/accel_map.cpp 19.23% <0.00%> (-20.06%) ⬇️
...hicle/raw_vehicle_cmd_converter/src/csv_loader.cpp 53.84% <0.00%> (-11.07%) ⬇️
...ace_planning_algorithms/src/abstract_algorithm.cpp 78.16% <0.00%> (-5.54%) ⬇️
... and 173 more

Help us with your feedback. Take ten seconds to tell us how you rate us. Have a feature suggestion? Share it here.

☔ View full report at Codecov.
📢 Do you have feedback about the report comment? Let us know in this issue.

@@ -791,6 +829,128 @@ void AccelBrakeMapCalibrator::executeUpdate(
.emplace_back(measured_acc);
}

bool AccelBrakeMapCalibrator::updateFourCellAroundOffset(
Copy link
Contributor

@TakaHoribe TakaHoribe Jul 17, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

There are so many if-condition for accel_mode in this function.
Please define variables for the accel_mode at the top of the function, and remove the if-condition from the algorithm code, like below:

before

  const double zll = accel_mode ? update_accel_map_value_.at(accel_pedal_index).at(accel_vel_index)
                                : update_brake_map_value_.at(brake_pedal_index).at(brake_vel_index);
  const double zhl = accel_mode
                       ? update_accel_map_value_.at(accel_pedal_index + 1).at(accel_vel_index)
                       : update_brake_map_value_.at(brake_pedal_index + 1).at(brake_vel_index);
  const double zlh = accel_mode
                       ? update_accel_map_value_.at(accel_pedal_index).at(accel_vel_index + 1)
                       : update_brake_map_value_.at(brake_pedal_index).at(brake_vel_index + 1);
  const double zhh = accel_mode
                       ? update_accel_map_value_.at(accel_pedal_index + 1).at(accel_vel_index + 1)
                       : update_brake_map_value_.at(brake_pedal_index + 1).at(brake_vel_index + 1);

  ...

  if (accel_mode) {
    update_accel_map_value_.at(accel_pedal_index).at(accel_vel_index) =
      accel_map_value_.at(accel_pedal_index).at(accel_vel_index) + map_offset(0);
    update_accel_map_value_.at(accel_pedal_index + 1).at(accel_vel_index) =
      accel_map_value_.at(accel_pedal_index + 1).at(accel_vel_index) + map_offset(1);
    update_accel_map_value_.at(accel_pedal_index).at(accel_vel_index + 1) =
      accel_map_value_.at(accel_pedal_index).at(accel_vel_index + 1) + map_offset(2);
    update_accel_map_value_.at(accel_pedal_index + 1).at(accel_vel_index + 1) =
      accel_map_value_.at(accel_pedal_index + 1).at(accel_vel_index + 1) + map_offset(3);
  } else {
    update_brake_map_value_.at(brake_pedal_index).at(brake_vel_index) =
      brake_map_value_.at(brake_pedal_index).at(brake_vel_index) + map_offset(0);
    update_brake_map_value_.at(brake_pedal_index + 1).at(brake_vel_index) =
      brake_map_value_.at(brake_pedal_index + 1).at(brake_vel_index) + map_offset(1);
    update_brake_map_value_.at(brake_pedal_index).at(brake_vel_index + 1) =
      brake_map_value_.at(brake_pedal_index).at(brake_vel_index + 1) + map_offset(2);
    update_brake_map_value_.at(brake_pedal_index + 1).at(brake_vel_index + 1) =
      brake_map_value_.at(brake_pedal_index + 1).at(brake_vel_index + 1) + map_offset(3);
  }

after

  auto & update_map_value = accel_mode ? update_accel_map_value_ : update_brake_map_value_;
  const auto & map_value = accel_mode ? accel_map_value_ : brake_map_value_;
  const auto & pedal_index = accel_mode ? accel_pedal_index : brake_pedal_index;
  const auto & vel_index = accel_mode ? accel_vel_index : brake_vel_index;

  const double zll = update_map_value.at(pedal_index + 0).at(vel_index + 0);
  const double zhl = update_map_value.at(pedal_index + 1).at(vel_index + 0);
  const double zlh = update_map_value.at(pedal_index + 0).at(vel_index + 1);
  const double zhh = update_map_value.at(pedal_index + 1).at(vel_index + 1);

  ...

  update_map_value.at(pedal_index + 0).at(vel_index + 0) = map_value.at(pedal_index + 0).at(vel_index + 0) + map_offset(0);
  update_map_value.at(pedal_index + 1).at(vel_index + 0) = map_value.at(pedal_index + 1).at(vel_index + 0) + map_offset(1);
  update_map_value.at(pedal_index + 0).at(vel_index + 1) = map_value.at(pedal_index + 0).at(vel_index + 1) + map_offset(2);
  update_map_value.at(pedal_index + 1).at(vel_index + 1) = map_value.at(pedal_index + 1).at(vel_index + 1) + map_offset(3);

@stale
Copy link

stale bot commented Sep 27, 2022

This pull request has been automatically marked as stale because it has not had recent activity.

@stale stale bot added the status:stale Inactive or outdated issues. (auto-assigned) label Sep 27, 2022
@TakaHoribe TakaHoribe marked this pull request as ready for review October 13, 2022 04:09
@TakaHoribe TakaHoribe requested a review from tkimura4 as a code owner October 13, 2022 04:09
@stale stale bot removed the status:stale Inactive or outdated issues. (auto-assigned) label Oct 13, 2022
@TakaHoribe TakaHoribe force-pushed the feature/improve_map_calibrator branch from 184a8ae to d63ca87 Compare October 13, 2022 04:10
Signed-off-by: Shumpei Wakabayashi <[email protected]>
@shmpwk
Copy link
Contributor

shmpwk commented Oct 27, 2022

Signed-off-by: Shumpei Wakabayashi <[email protected]>
@shmpwk shmpwk force-pushed the feature/improve_map_calibrator branch from 3c1f6b4 to af09aa7 Compare October 27, 2022 09:12
@shmpwk
Copy link
Contributor

shmpwk commented Oct 31, 2022

LGTM!

view_plot

accel_map.csv
brake_map.csv

(For TIER IV internal infomation)
I calibrated them using the 10min rosbags (2022.10.12) from dd0a1334-760f-4ed1-84dc-9d12cf23baf5_2022-10-12-16-24-14_0.db3 to dd0a1334-760f-4ed1-84dc-9d12cf23baf5_2022-10-12-16-24-14_10.db3

@TakaHoribe TakaHoribe self-requested a review October 31, 2022 01:45
Copy link
Contributor

@tkimura4 tkimura4 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM

@TakaHoribe TakaHoribe merged commit 96dfb9e into autowarefoundation:main Oct 31, 2022
@TakaHoribe TakaHoribe deleted the feature/improve_map_calibrator branch October 31, 2022 02:13
HansRobo pushed a commit to HansRobo/autoware.universe that referenced this pull request Dec 16, 2022
…od (autowarefoundation#1255)

* Add 4-cell around Recursive Least Squares

* Add evaluation rules

* Fix index reference bug and Change implementation of covariance matrix

* Remove some dead code

* format by pre-commit

Signed-off-by: Takamasa Horibe <[email protected]>

* fix map_index bag

* add support for new calibration method to view_plot.py

* remove if-condition

* fix typo

* fix: spell miss

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix: lint

Signed-off-by: Shumpei Wakabayashi <[email protected]>

Signed-off-by: Takamasa Horibe <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>
Co-authored-by: Takamasa Horibe <[email protected]>
Co-authored-by: Shumpei Wakabayashi <[email protected]>
Co-authored-by: Shumpei Wakabayashi <[email protected]>
Signed-off-by: Kotaro Yoshimoto <[email protected]>
badai-nguyen pushed a commit to badai-nguyen/autoware.universe that referenced this pull request May 2, 2024
autowarefoundation#1255)

fix(behavior_velocity_traffic_light): do not use the timed out remaining time information

Signed-off-by: Tomohito Ando <[email protected]>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants