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

Consider simulated time #883

Merged
merged 6 commits into from
Dec 7, 2021
Merged

Consider simulated time #883

merged 6 commits into from
Dec 7, 2021

Conversation

galou
Copy link
Contributor

@galou galou commented Dec 2, 2021

Consider the simulated time in
CurrentStateMonitor::waitForCurrentState().
Propagate the change in other packages and classes where necessary.

Signed-off-by: Gaël Écorchard gael.ecorchard@cvut.cz

Description

I had an issue with very slow simulated time where the robot status was not received within 1s of system time. This PR should solve the issue. The behavior with non-emulated time should not change.

Checklist

  • Required by CI: Code is auto formatted using clang-format
  • Extend the tutorials / documentation reference
  • Document API changes relevant to the user in the MIGRATION.md notes
  • Create tests, which fail without this PR reference
  • Include a screenshot if changing a GUI
  • While waiting for someone to review your request, please help review another open pull request to support the maintainers

Consider the simulated time in
`CurrentStateMonitor::waitForCurrentState()`.
Propagate the change in other packages and classes where necessary.

Signed-off-by: Gaël Écorchard <gael.ecorchard@cvut.cz>
@galou
Copy link
Contributor Author

galou commented Dec 2, 2021

Copy link
Member

@tylerjw tylerjw left a comment

Choose a reason for hiding this comment

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

This looks really good. Thank you for this change!

@@ -5,6 +5,7 @@ project(moveit_ros_planning_interface)
find_package(moveit_common REQUIRED)
moveit_package()

find_package(backward_ros)
Copy link
Member

Choose a reason for hiding this comment

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

I added this to moveit_common. I think by doing that it is already here from the moveit_package() call on line 6.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I'm sorry, I added this by mistake. I'll remove it but I first wait a bit if there is no other changes to carry out.

boost::shared_lock<boost::shared_mutex> lock(scene_update_mutex_);
rclcpp::Time prev_robot_motion_time = last_robot_motion_time_;
while (last_robot_motion_time_ < t && // Wait until the state update actually reaches the scene.
timeout > std::chrono::seconds())
timeout > rclcpp::Duration(0))
Copy link
Member

@tylerjw tylerjw Dec 3, 2021

Choose a reason for hiding this comment

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

CI is failing because of this line I believe. The rclcpp::Duration(double) constructor is deprecated. You should be able to get it to pass with this:

Suggested change
timeout > rclcpp::Duration(0))
timeout > rclcpp::Duration::from_seconds(0))

or

Suggested change
timeout > rclcpp::Duration(0))
timeout > rclcpp::Duration(0, 0))

Signed-off-by: Gaël Écorchard <gael.ecorchard@cvut.cz>
@mergify
Copy link

mergify bot commented Dec 6, 2021

This pull request is in conflict. Could you fix it @galou?

@tylerjw
Copy link
Member

tylerjw commented Dec 6, 2021

I fixed the merge conflict and re-triggered the CI jobs. I'll merge this once it passes.

@codecov
Copy link

codecov bot commented Dec 6, 2021

Codecov Report

Merging #883 (bf3672b) into main (2830dd8) will increase coverage by 0.01%.
The diff coverage is 55.00%.

Impacted file tree graph

@@            Coverage Diff             @@
##             main     #883      +/-   ##
==========================================
+ Coverage   60.81%   60.81%   +0.01%     
==========================================
  Files         271      271              
  Lines       23815    23823       +8     
==========================================
+ Hits        14481    14486       +5     
- Misses       9334     9337       +3     
Impacted Files Coverage Δ
...eit/planning_scene_monitor/current_state_monitor.h 100.00% <ø> (ø)
...it/planning_scene_monitor/planning_scene_monitor.h 25.00% <ø> (ø)
...nning_scene_monitor/src/planning_scene_monitor.cpp 46.59% <37.50%> (-0.22%) ⬇️
...anning_scene_monitor/src/current_state_monitor.cpp 75.99% <66.67%> (-1.14%) ⬇️
...e/collision_detection_fcl/src/collision_common.cpp 75.12% <0.00%> (+0.24%) ⬆️
...dl_kinematics_plugin/src/kdl_kinematics_plugin.cpp 75.93% <0.00%> (+1.12%) ⬆️

Continue to review full report at Codecov.

Legend - Click here to learn more
Δ = absolute <relative> (impact), ø = not affected, ? = missing data
Powered by Codecov. Last update 2830dd8...bf3672b. Read the comment docs.

@tylerjw tylerjw merged commit a4066b0 into moveit:main Dec 7, 2021
@galou galou deleted the sim_time_wait_state branch December 8, 2021 13:14
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