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(motion_utils): add option to use slerp for orientation #1575

Merged

Conversation

TomohitoAndo
Copy link
Contributor

@TomohitoAndo TomohitoAndo commented Aug 12, 2022

Description

Added option to use spherical interpolation to calculate the orientation.

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.

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.

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

@codecov
Copy link

codecov bot commented Aug 12, 2022

Codecov Report

Merging #1575 (f7bf15a) into main (4296138) will increase coverage by 0.49%.
The diff coverage is 37.12%.

@@            Coverage Diff             @@
##             main    #1575      +/-   ##
==========================================
+ Coverage   10.73%   11.23%   +0.49%     
==========================================
  Files        1115     1115              
  Lines       78829    84421    +5592     
  Branches    18562    22065    +3503     
==========================================
+ Hits         8465     9484    +1019     
- Misses      61505    65227    +3722     
- Partials     8859     9710     +851     
Flag Coverage Δ *Carryforward flag
differential 10.98% <32.97%> (?)
total 10.72% <23.86%> (ø) Carriedforward from 4296138

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

Impacted Files Coverage Δ
...tion_utils/test/src/trajectory/test_trajectory.cpp 30.88% <35.65%> (+5.27%) ⬆️
...ils/include/motion_utils/trajectory/trajectory.hpp 82.14% <100.00%> (+4.03%) ⬆️
...city_planner/include/utilization/arc_lane_util.hpp 28.35% <0.00%> (-12.07%) ⬇️
...ene_module/occlusion_spot/occlusion_spot_utils.cpp 8.33% <0.00%> (-0.33%) ⬇️
planning/obstacle_stop_planner/src/node.cpp 0.00% <0.00%> (ø)
planning/obstacle_avoidance_planner/src/node.cpp 0.00% <0.00%> (ø)
...lanning/obstacle_stop_planner/src/debug_marker.cpp 0.00% <0.00%> (ø)
...nning/behavior_path_planner/src/path_utilities.cpp 0.00% <0.00%> (ø)
...ning/behavior_path_planner/src/debug_utilities.cpp 0.00% <0.00%> (ø)
.../behavior_path_planner/src/turn_signal_decider.cpp 0.00% <0.00%> (ø)
... and 57 more

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

@satoshi-ota
Copy link
Contributor

@TomohitoAndo Nice PR 👍
Could you write unit tests for use_slerp_for_orientation = true ?

@TomohitoAndo
Copy link
Contributor Author

@satoshi-ota
Thanks!
Okay, I will write the unit test 👍

@TomohitoAndo
Copy link
Contributor Author

@satoshi-ota
I added the tests. Could you check? 🙏
The result of colcon_test is here.

colcon test --packages-select motion_utils --event-handlers console_direct+
Starting >>> motion_utils
UpdateCTestConfiguration  from :/home/tomohitoando/workspace/autoware/build/motion_utils/CTestConfiguration.ini
Parse Config file:/home/tomohitoando/workspace/autoware/build/motion_utils/CTestConfiguration.ini
   Site: npc2103053
   Build name: (empty)
 Add coverage exclude regular expressions.
SetCTestConfiguration:CMakeCommand:/usr/bin/cmake
Create new tag: 20220818-1014 - Experimental
UpdateCTestConfiguration  from :/home/tomohitoando/workspace/autoware/build/motion_utils/CTestConfiguration.ini
Parse Config file:/home/tomohitoando/workspace/autoware/build/motion_utils/CTestConfiguration.ini
Test project /home/tomohitoando/workspace/autoware/build/motion_utils
Constructing a list of tests
Done constructing a list of tests
Updating test list for fixtures
Added 0 tests to meet fixture requirements
Checking test dependency graph...
Checking test dependency graph end
test 1
    Start 1: test_motion_utils

1: Test command: /usr/bin/python3 "-u" "/opt/ros/galactic/share/ament_cmake_ros/cmake/run_test_isolated.py" "/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/test_motion_utils.gtest.xml" "--package-name" "motion_utils" "--output-file" "/home/tomohitoando/workspace/autoware/build/motion_utils/ament_cmake_gtest/test_motion_utils.txt" "--command" "/home/tomohitoando/workspace/autoware/build/motion_utils/test_motion_utils" "--gtest_output=xml:/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/test_motion_utils.gtest.xml"
1: Test timeout computed to be: 60
1: Running with ROS_DOMAIN_ID 1            
1: -- run_test.py: invoking following command in '/home/tomohitoando/workspace/autoware/build/motion_utils':
1:  - /home/tomohitoando/workspace/autoware/build/motion_utils/test_motion_utils --gtest_output=xml:/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/test_motion_utils.gtest.xml
1: [==========] Running 61 tests from 7 test suites.
1: [----------] Global test environment set-up.
1: [----------] 4 tests from resample_path_with_lane_id
1: [ RUN      ] resample_path_with_lane_id.resample_path_by_vector
1: [motion_utils]: input path size or input path length is wrong
1: [motion_utils]: input path size or input path length is wrong
1: [motion_utils]: resampled path length is longer than input path length
1: [       OK ] resample_path_with_lane_id.resample_path_by_vector (0 ms)
1: [ RUN      ] resample_path_with_lane_id.resample_path_by_vector_backward
1: [       OK ] resample_path_with_lane_id.resample_path_by_vector_backward (0 ms)
1: [ RUN      ] resample_path_with_lane_id.resample_path_by_vector_non_default
1: [       OK ] resample_path_with_lane_id.resample_path_by_vector_non_default (0 ms)
1: [ RUN      ] resample_path_with_lane_id.resample_path_by_same_interval
1: [motion_utils]: input trajectory size or resample interval is invalid
1: [motion_utils]: input trajectory size or resample interval is invalid
1: [motion_utils]: input trajectory size or resample interval is invalid
1: [       OK ] resample_path_with_lane_id.resample_path_by_same_interval (0 ms)
1: [----------] 4 tests from resample_path_with_lane_id (0 ms total)
1: 
1: [----------] 4 tests from resample_path
1: [ RUN      ] resample_path.resample_path_by_vector
1: [motion_utils]: input path size, input path length or resampled arclength is wrong
1: [motion_utils]: input path size, input path length or resampled arclength is wrong
1: [motion_utils]: input path size, input path length or resampled arclength is wrong
1: [       OK ] resample_path.resample_path_by_vector (0 ms)
1: [ RUN      ] resample_path.resample_path_by_vector_backward
1: [       OK ] resample_path.resample_path_by_vector_backward (0 ms)
1: [ RUN      ] resample_path.resample_path_by_vector_non_default
1: [       OK ] resample_path.resample_path_by_vector_non_default (0 ms)
1: [ RUN      ] resample_path.resample_trajectory_by_vector
1: [motion_utils]: input trajectory size, input trajectory length or resampled arclength is wrong
1: [motion_utils]: input trajectory size, input trajectory length or resampled arclength is wrong
1: [motion_utils]: input trajectory size, input trajectory length or resampled arclength is wrong
1: [       OK ] resample_path.resample_trajectory_by_vector (0 ms)
1: [----------] 4 tests from resample_path (0 ms total)
1: 
1: [----------] 2 tests from resample_trajectory
1: [ RUN      ] resample_trajectory.resample_trajectory_by_vector_non_default
1: [       OK ] resample_trajectory.resample_trajectory_by_vector_non_default (0 ms)
1: [ RUN      ] resample_trajectory.resample_trajectory_by_same_interval
1: [motion_utils]: input trajectory size, input_trajectory length or resample interval is invalid
1: [motion_utils]: input trajectory size, input_trajectory length or resample interval is invalid
1: [motion_utils]: input trajectory size, input_trajectory length or resample interval is invalid
1: [       OK ] resample_trajectory.resample_trajectory_by_same_interval (1 ms)
1: [----------] 2 tests from resample_trajectory (1 ms total)
1: 
1: [----------] 2 tests from path_with_lane_id
1: [ RUN      ] path_with_lane_id.getPathIndexRangeWithLaneId
1: [       OK ] path_with_lane_id.getPathIndexRangeWithLaneId (0 ms)
1: [ RUN      ] path_with_lane_id.findNearestIndexFromLaneId
1: [       OK ] path_with_lane_id.findNearestIndexFromLaneId (0 ms)
1: [----------] 2 tests from path_with_lane_id (0 ms total)
1: 
1: [----------] 46 tests from trajectory
1: [ RUN      ] trajectory.validateNonEmpty
1: [       OK ] trajectory.validateNonEmpty (0 ms)
1: [ RUN      ] trajectory.validateNonSharpAngle_DefaultThreshold
1: [       OK ] trajectory.validateNonSharpAngle_DefaultThreshold (0 ms)
1: [ RUN      ] trajectory.validateNonSharpAngle_SetThreshold
1: [       OK ] trajectory.validateNonSharpAngle_SetThreshold (0 ms)
1: [ RUN      ] trajectory.searchZeroVelocityIndex
1: Points is empty.
1: [       OK ] trajectory.searchZeroVelocityIndex (0 ms)
1: [ RUN      ] trajectory.findNearestIndex_Pos_StraightTrajectory
1: [       OK ] trajectory.findNearestIndex_Pos_StraightTrajectory (0 ms)
1: [ RUN      ] trajectory.findNearestIndex_Pos_CurvedTrajectory
1: [       OK ] trajectory.findNearestIndex_Pos_CurvedTrajectory (0 ms)
1: [ RUN      ] trajectory.findNearestIndex_Pose_NoThreshold
1: Points is empty.
1: [       OK ] trajectory.findNearestIndex_Pose_NoThreshold (0 ms)
1: [ RUN      ] trajectory.findNearestIndex_Pose_DistThreshold
1: [       OK ] trajectory.findNearestIndex_Pose_DistThreshold (0 ms)
1: [ RUN      ] trajectory.findNearestIndex_Pose_YawThreshold
1: [       OK ] trajectory.findNearestIndex_Pose_YawThreshold (0 ms)
1: [ RUN      ] trajectory.findNearestIndex_Pose_DistAndYawThreshold
1: [       OK ] trajectory.findNearestIndex_Pose_DistAndYawThreshold (0 ms)
1: [ RUN      ] trajectory.findNearestSegmentIndex
1: [       OK ] trajectory.findNearestSegmentIndex (0 ms)
1: [ RUN      ] trajectory.calcLongitudinalOffsetToSegment_StraightTrajectory
1: [       OK ] trajectory.calcLongitudinalOffsetToSegment_StraightTrajectory (0 ms)
1: [ RUN      ] trajectory.calcLongitudinalOffsetToSegment_CurveTrajectory
1: [       OK ] trajectory.calcLongitudinalOffsetToSegment_CurveTrajectory (0 ms)
1: [ RUN      ] trajectory.calcLateralOffset
1: [       OK ] trajectory.calcLateralOffset (0 ms)
1: [ RUN      ] trajectory.calcLateralOffset_CurveTrajectory
1: [       OK ] trajectory.calcLateralOffset_CurveTrajectory (0 ms)
1: [ RUN      ] trajectory.calcSignedArcLengthFromIndexToIndex
1: Points is empty.
1: [       OK ] trajectory.calcSignedArcLengthFromIndexToIndex (0 ms)
1: [ RUN      ] trajectory.calcSignedArcLengthFromPointToIndex
1: Points is empty.
1: [       OK ] trajectory.calcSignedArcLengthFromPointToIndex (0 ms)
1: [ RUN      ] trajectory.calcSignedArcLengthFromPoseToIndex_DistThreshold
1: [       OK ] trajectory.calcSignedArcLengthFromPoseToIndex_DistThreshold (0 ms)
1: [ RUN      ] trajectory.calcSignedArcLengthFromPoseToIndex_YawThreshold
1: [       OK ] trajectory.calcSignedArcLengthFromPoseToIndex_YawThreshold (0 ms)
1: [ RUN      ] trajectory.calcSignedArcLengthFromIndexToPoint
1: Points is empty.
1: [       OK ] trajectory.calcSignedArcLengthFromIndexToPoint (0 ms)
1: [ RUN      ] trajectory.calcSignedArcLengthFromPointToPoint
1: Points is empty.
1: [       OK ] trajectory.calcSignedArcLengthFromPointToPoint (0 ms)
1: [ RUN      ] trajectory.calcArcLength
1: Points is empty.
1: [       OK ] trajectory.calcArcLength (0 ms)
1: [ RUN      ] trajectory.convertToTrajectory
1: [       OK ] trajectory.convertToTrajectory (2 ms)
1: [ RUN      ] trajectory.convertToTrajectoryPointArray
1: [       OK ] trajectory.convertToTrajectoryPointArray (0 ms)
1: [ RUN      ] trajectory.calcDistanceToForwardStopPointFromIndex
1: Points is empty.
1: [       OK ] trajectory.calcDistanceToForwardStopPointFromIndex (0 ms)
1: [ RUN      ] trajectory.calcDistanceToForwardStopPointFromPose
1: Points is empty.
1: [       OK ] trajectory.calcDistanceToForwardStopPointFromPose (0 ms)
1: [ RUN      ] trajectory.calcDistanceToForwardStopPoint_DistThreshold
1: [       OK ] trajectory.calcDistanceToForwardStopPoint_DistThreshold (0 ms)
1: [ RUN      ] trajectory.calcDistanceToForwardStopPoint_YawThreshold
1: [       OK ] trajectory.calcDistanceToForwardStopPoint_YawThreshold (0 ms)
1: [ RUN      ] trajectory.calcLongitudinalOffsetPointFromIndex
1: Points is empty.
1: Invalid source index
1: Invalid source index
1: [       OK ] trajectory.calcLongitudinalOffsetPointFromIndex (0 ms)
1: [ RUN      ] trajectory.calcLongitudinalOffsetPointFromPoint
1: Points is empty.
1: Segment index is invalid.
1: [       OK ] trajectory.calcLongitudinalOffsetPointFromPoint (6 ms)
1: [ RUN      ] trajectory.calcLongitudinalOffsetPoseFromIndex
1: Points is empty.
1: Invalid source index
1: Invalid source index
1: [       OK ] trajectory.calcLongitudinalOffsetPoseFromIndex (0 ms)
1: [ RUN      ] trajectory.calcLongitudinalOffsetPoseFromIndex_quatInterpolation
1: [       OK ] trajectory.calcLongitudinalOffsetPoseFromIndex_quatInterpolation (0 ms)
1: [ RUN      ] trajectory.calcLongitudinalOffsetPoseFromIndex_quatSphericalInterpolation
1: [       OK ] trajectory.calcLongitudinalOffsetPoseFromIndex_quatSphericalInterpolation (0 ms)
1: [ RUN      ] trajectory.calcLongitudinalOffsetPoseFromPoint
1: Points is empty.
1: Segment index is invalid.
1: [       OK ] trajectory.calcLongitudinalOffsetPoseFromPoint (6 ms)
1: [ RUN      ] trajectory.calcLongitudinalOffsetPoseFromPoint_quatInterpolation
1: [       OK ] trajectory.calcLongitudinalOffsetPoseFromPoint_quatInterpolation (0 ms)
1: [ RUN      ] trajectory.calcLongitudinalOffsetPoseFromPoint_quatSphericalInterpolation
1: [       OK ] trajectory.calcLongitudinalOffsetPoseFromPoint_quatSphericalInterpolation (0 ms)
1: [ RUN      ] trajectory.insertTargetPoint
1: Points is empty.
1: [       OK ] trajectory.insertTargetPoint (0 ms)
1: [ RUN      ] trajectory.insertTargetPoint_Reverse
1: [       OK ] trajectory.insertTargetPoint_Reverse (0 ms)
1: [ RUN      ] trajectory.insertTargetPoint_OverlapThreshold
1: [       OK ] trajectory.insertTargetPoint_OverlapThreshold (0 ms)
1: [ RUN      ] trajectory.insertTargetPoint_Length
1: [       OK ] trajectory.insertTargetPoint_Length (0 ms)
1: [ RUN      ] trajectory.insertTargetPoint_Length_Without_Target_Point
1: [       OK ] trajectory.insertTargetPoint_Length_Without_Target_Point (0 ms)
1: [ RUN      ] trajectory.insertTargetPoint_Length_Without_Target_Point_Non_Zero_Start_Idx
1: [       OK ] trajectory.insertTargetPoint_Length_Without_Target_Point_Non_Zero_Start_Idx (0 ms)
1: [ RUN      ] trajectory.insertTargetPoint_Length_from_a_pose
1: [       OK ] trajectory.insertTargetPoint_Length_from_a_pose (0 ms)
1: [ RUN      ] trajectory.insertStopPoint_from_a_source_index
1: [       OK ] trajectory.insertStopPoint_from_a_source_index (0 ms)
1: [ RUN      ] trajectory.insertStopPoint_from_a_pose
1: [       OK ] trajectory.insertStopPoint_from_a_pose (1 ms)
1: [ RUN      ] trajectory.findFirstNearestIndexWithSoftConstraints
1: [       OK ] trajectory.findFirstNearestIndexWithSoftConstraints (0 ms)
1: [----------] 46 tests from trajectory (16 ms total)
1: 
1: [----------] 1 test from vehicle_stop_checker
1: [ RUN      ] vehicle_stop_checker.isVehicleStopped
1: [       OK ] vehicle_stop_checker.isVehicleStopped (2558 ms)
1: [----------] 1 test from vehicle_stop_checker (2558 ms total)
1: 
1: [----------] 2 tests from vehicle_arrival_checker
1: [ RUN      ] vehicle_arrival_checker.isVehicleStopped
1: [       OK ] vehicle_arrival_checker.isVehicleStopped (2541 ms)
1: [ RUN      ] vehicle_arrival_checker.isVehicleStoppedAtStopPoint
1: [       OK ] vehicle_arrival_checker.isVehicleStoppedAtStopPoint (1531 ms)
1: [----------] 2 tests from vehicle_arrival_checker (4073 ms total)
1: 
1: [----------] Global test environment tear-down
1: [==========] 61 tests from 7 test suites ran. (6648 ms total)
1: [  PASSED  ] 61 tests.
1: -- run_test.py: return code 0
1: -- run_test.py: inject classname prefix into gtest result file '/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/test_motion_utils.gtest.xml'
1: -- run_test.py: verify result file '/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/test_motion_utils.gtest.xml'
1/5 Test #1: test_motion_utils ................   Passed    6.75 sec
test 2
    Start 2: copyright

2: Test command: /usr/bin/python3 "-u" "/opt/ros/galactic/share/ament_cmake_test/cmake/run_test.py" "/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/copyright.xunit.xml" "--package-name" "motion_utils" "--output-file" "/home/tomohitoando/workspace/autoware/build/motion_utils/ament_copyright/copyright.txt" "--command" "/opt/ros/galactic/bin/ament_copyright" "--xunit-file" "/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/copyright.xunit.xml"
2: Test timeout computed to be: 120
2: -- run_test.py: invoking following command in '/home/tomohitoando/workspace/autoware/src/universe/autoware.universe/common/motion_utils':
2:  - /opt/ros/galactic/bin/ament_copyright --xunit-file /home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/copyright.xunit.xml
2: No problems found, checked 17 files     
2: -- run_test.py: return code 0           
2: -- run_test.py: verify result file '/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/copyright.xunit.xml'
2/5 Test #2: copyright ........................   Passed    2.43 sec
test 3
    Start 3: cppcheck

3: Test command: /usr/bin/python3 "-u" "/opt/ros/galactic/share/ament_cmake_test/cmake/run_test.py" "/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/cppcheck.xunit.xml" "--package-name" "motion_utils" "--output-file" "/home/tomohitoando/workspace/autoware/build/motion_utils/ament_cppcheck/cppcheck.txt" "--command" "/opt/ros/galactic/bin/ament_cppcheck" "--xunit-file" "/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/cppcheck.xunit.xml" "--include_dirs" "/home/tomohitoando/workspace/autoware/src/universe/autoware.universe/common/motion_utils/include"
3: Test timeout computed to be: 300
3: -- run_test.py: invoking following command in '/home/tomohitoando/workspace/autoware/src/universe/autoware.universe/common/motion_utils':
3:  - /opt/ros/galactic/bin/ament_cppcheck --xunit-file /home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/cppcheck.xunit.xml --include_dirs /home/tomohitoando/workspace/autoware/src/universe/autoware.universe/common/motion_utils/include
3: No problems found                        
3: -- run_test.py: return code 0             
3: -- run_test.py: verify result file '/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/cppcheck.xunit.xml'
3/5 Test #3: cppcheck .........................   Passed    0.70 sec
test 4
    Start 4: lint_cmake

4: Test command: /usr/bin/python3 "-u" "/opt/ros/galactic/share/ament_cmake_test/cmake/run_test.py" "/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/lint_cmake.xunit.xml" "--package-name" "motion_utils" "--output-file" "/home/tomohitoando/workspace/autoware/build/motion_utils/ament_lint_cmake/lint_cmake.txt" "--command" "/opt/ros/galactic/bin/ament_lint_cmake" "--xunit-file" "/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/lint_cmake.xunit.xml"
4: Test timeout computed to be: 60
4: -- run_test.py: invoking following command in '/home/tomohitoando/workspace/autoware/src/universe/autoware.universe/common/motion_utils':
4:  - /opt/ros/galactic/bin/ament_lint_cmake --xunit-file /home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/lint_cmake.xunit.xml
4:                                           
4: No problems found
4: -- run_test.py: return code 0
4: -- run_test.py: verify result file '/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/lint_cmake.xunit.xml'
4/5 Test #4: lint_cmake .......................   Passed    0.35 sec
test 5
    Start 5: xmllint

5: Test command: /usr/bin/python3 "-u" "/opt/ros/galactic/share/ament_cmake_test/cmake/run_test.py" "/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/xmllint.xunit.xml" "--package-name" "motion_utils" "--output-file" "/home/tomohitoando/workspace/autoware/build/motion_utils/ament_xmllint/xmllint.txt" "--command" "/opt/ros/galactic/bin/ament_xmllint" "--xunit-file" "/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/xmllint.xunit.xml"
5: Test timeout computed to be: 60
5: -- run_test.py: invoking following command in '/home/tomohitoando/workspace/autoware/src/universe/autoware.universe/common/motion_utils':
5:  - /opt/ros/galactic/bin/ament_xmllint --xunit-file /home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/xmllint.xunit.xml
5: File 'package.xml' is valid               
5: 
5: No problems found
5: -- run_test.py: return code 0
5: -- run_test.py: verify result file '/home/tomohitoando/workspace/autoware/build/motion_utils/test_results/motion_utils/xmllint.xunit.xml'
5/5 Test #5: xmllint ..........................   Passed    1.52 sec

100% tests passed, 0 tests failed out of 5

Label Time Summary:
copyright     =   2.43 sec*proc (1 test)
cppcheck      =   0.70 sec*proc (1 test)
gtest         =   6.75 sec*proc (1 test)
lint_cmake    =   0.35 sec*proc (1 test)
linter        =   5.01 sec*proc (4 tests)
xmllint       =   1.52 sec*proc (1 test)

Total Test time (real) =  11.77 sec
Finished <<< motion_utils [11.9s]            

Summary: 1 package finished [12.5s]

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
…lation

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
@TomohitoAndo
Copy link
Contributor Author

force pushed to fix DCO.

@satoshi-ota satoshi-ota self-requested a review August 21, 2022 23:13
Copy link
Contributor

@satoshi-ota satoshi-ota left a comment

Choose a reason for hiding this comment

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

LGTM 👍

@TomohitoAndo TomohitoAndo merged commit 31d9c65 into autowarefoundation:main Aug 22, 2022
@TomohitoAndo TomohitoAndo deleted the feat/slerp-orientation branch August 22, 2022 06:08
boyali pushed a commit to boyali/autoware.universe that referenced this pull request Sep 28, 2022
…foundation#1575)

* feat(motion_utils): add option to use slerp for orientation

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* test: add tests for calcLongitudinalOffsetPose with spherical interpolation

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* test: modify ratio to be more consitent

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* chore: use common flag name

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
boyali pushed a commit to boyali/autoware.universe that referenced this pull request Oct 3, 2022
…foundation#1575)

* feat(motion_utils): add option to use slerp for orientation

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* test: add tests for calcLongitudinalOffsetPose with spherical interpolation

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* test: modify ratio to be more consitent

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* chore: use common flag name

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
boyali pushed a commit to boyali/autoware.universe that referenced this pull request Oct 3, 2022
…foundation#1575)

* feat(motion_utils): add option to use slerp for orientation

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* test: add tests for calcLongitudinalOffsetPose with spherical interpolation

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* test: modify ratio to be more consitent

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* chore: use common flag name

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
yukke42 pushed a commit to tzhong518/autoware.universe that referenced this pull request Oct 14, 2022
…foundation#1575)

* feat(motion_utils): add option to use slerp for orientation

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* test: add tests for calcLongitudinalOffsetPose with spherical interpolation

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* test: modify ratio to be more consitent

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* chore: use common flag name

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
boyali pushed a commit to boyali/autoware.universe that referenced this pull request Oct 19, 2022
…foundation#1575)

* feat(motion_utils): add option to use slerp for orientation

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* test: add tests for calcLongitudinalOffsetPose with spherical interpolation

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* test: modify ratio to be more consitent

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* chore: use common flag name

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
TomohitoAndo added a commit to TomohitoAndo/autoware.universe that referenced this pull request Nov 25, 2022
…foundation#1575)

* feat(motion_utils): add option to use slerp for orientation

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* test: add tests for calcLongitudinalOffsetPose with spherical interpolation

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* test: modify ratio to be more consitent

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* chore: use common flag name

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
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.

2 participants