Skip to content
New issue

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

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

Already on GitHub? # to your account

Bug fix: RobotTrajectory append() #1813

Merged
merged 2 commits into from
Dec 20, 2022
Merged

Conversation

AndyZe
Copy link
Member

@AndyZe AndyZe commented Dec 16, 2022

Description

The first commit seems to show something unexpected - an extra timestep of 0.1s is appended at index 5. The second commit fixes it.

/home/andy/ws_ros2/src/moveit2/moveit_core/robot_trajectory/test/test_robot_trajectory.cpp:217: Failure
Expected equality of these values:
  initial_trajectory->getWayPointCount()
    Which is: 9
  10
/home/andy/ws_ros2/src/moveit2/moveit_core/robot_trajectory/test/test_robot_trajectory.cpp:219: Failure
Expected equality of these values:
  initial_trajectory->getWayPointDurationFromPrevious(5)
    Which is: 0.2
  EXPECTED_DURATION
    Which is: 0.1

@AndyZe AndyZe changed the title Bug demo: Add a test for append() Bug demo: RobotTrajectory append() Dec 16, 2022
@AndyZe AndyZe force-pushed the andyz/append_traj_test branch from b2e0cf5 to 364ca53 Compare December 16, 2022 19:55
@codecov
Copy link

codecov bot commented Dec 16, 2022

Codecov Report

Base: 50.29% // Head: 50.27% // Decreases project coverage by -0.02% ⚠️

Coverage data is based on head (0472c37) compared to base (fca8e9b).
Patch coverage: 100.00% of modified lines in pull request are covered.

Additional details and impacted files
@@            Coverage Diff             @@
##             main    #1813      +/-   ##
==========================================
- Coverage   50.29%   50.27%   -0.01%     
==========================================
  Files         374      374              
  Lines       31286    31286              
==========================================
- Hits        15733    15727       -6     
- Misses      15553    15559       +6     
Impacted Files Coverage Δ
...eit_core/robot_trajectory/src/robot_trajectory.cpp 56.65% <100.00%> (ø)
moveit_ros/moveit_servo/src/servo_calcs.cpp 65.97% <0.00%> (-1.45%) ⬇️
moveit_ros/moveit_servo/src/pose_tracking.cpp 77.11% <0.00%> (-0.46%) ⬇️
moveit_core/robot_state/src/robot_state.cpp 47.95% <0.00%> (+0.08%) ⬆️
...dl_kinematics_plugin/src/kdl_kinematics_plugin.cpp 79.93% <0.00%> (+1.14%) ⬆️

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.

@AndyZe AndyZe force-pushed the andyz/append_traj_test branch from 364ca53 to 9ad28ef Compare December 16, 2022 20:19
@AndyZe AndyZe changed the title Bug demo: RobotTrajectory append() Bug fix: RobotTrajectory append() Dec 16, 2022

// After append() we should have 10 waypoints, all with 0.1s duration
const double EXPECTED_DURATION = 0.1;
initial_trajectory->append(*traj2, 0.1, 0, 5);
Copy link
Member Author

@AndyZe AndyZe Dec 16, 2022

Choose a reason for hiding this comment

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

The 5 here doesn't make sense to me. Since the trajectory has 5 waypoints, I think the last index should be 4. But the test passes. I'm confused.

The doxygen says:

   * \param end_index - index of last traj point of the part to append from the source traj, the default is to add until
   * the end of the source traj

At a minimum, I think the comment should be updated. Any suggestions?

@AndyZe AndyZe force-pushed the andyz/append_traj_test branch from 9ad28ef to 3385acc Compare December 18, 2022 03:20
Copy link
Member

@henningkayser henningkayser left a comment

Choose a reason for hiding this comment

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

Good find! I wonder if anyone would disagree with this, but the fixed behavior looks correct to me. I was still somewhat under the impression that duration_from_previous_ would start indexing at the second waypoint since the first waypoint doesn't have a "previous" 🤔.

@henningkayser henningkayser added the backport-humble Mergify label that triggers a PR backport to Humble label Dec 20, 2022
@AndyZe AndyZe force-pushed the andyz/append_traj_test branch from 3385acc to 0472c37 Compare December 20, 2022 14:29
@AndyZe AndyZe merged commit 35bb662 into moveit:main Dec 20, 2022
@AndyZe AndyZe deleted the andyz/append_traj_test branch December 20, 2022 15:03
mergify bot pushed a commit that referenced this pull request Dec 20, 2022
* Add a test for append()

* Don't add to the timestep, rather overwrite it

(cherry picked from commit 35bb662)
AndyZe added a commit that referenced this pull request Jan 19, 2023
* Add a test for append()

* Don't add to the timestep, rather overwrite it

(cherry picked from commit 35bb662)
rhaschke pushed a commit to ubi-agni/moveit that referenced this pull request Dec 18, 2024
rr-mark pushed a commit to rivelinrobotics/rivelin_moveit that referenced this pull request Jan 7, 2025
# for free to join this conversation on GitHub. Already have an account? # to comment
Labels
backport-humble Mergify label that triggers a PR backport to Humble
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants