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

fix regression from #1331 #1384

Merged
merged 1 commit into from
Jun 21, 2022
Merged

fix regression from #1331 #1384

merged 1 commit into from
Jun 21, 2022

Conversation

mikeferguson
Copy link
Contributor

Description

The noted PR swapped boost::thread to std::thread - however
std::thread will cause the program to crash with a note that
TERMINATE CALLED WITHOUT ACTIVE EXCEPTION if the thread object
goes out of scope while not joinable. Detaching the thread
restores the original workflow prior to the PR and allows
users to send more than one trajectory via the motion planning
plugin in RVIZ (otherwise, it crashes on the first trajectory).

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

The noted PR swapped boost::thread to std::thread - however
std::thread will cause the program to crash with a note that
TERMINATE CALLED WITHOUT ACTIVE EXCEPTION if the thread object
goes out of scope while not joinable. Detaching the thread
restores the original workflow prior to the PR and allows
users to send more than one trajectory via the motion planning
plugin in RVIZ (otherwise, it crashes on the first trajectory).
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.

Thank you for this. I'm the future when we have jthread we could use that to fix this that way too.

@mikeferguson
Copy link
Contributor Author

@tylerjw yeah - I'm not sure this is the best way to fix this - but it's definitely the simplest way to get things back to working

@codecov
Copy link

codecov bot commented Jun 21, 2022

Codecov Report

Merging #1384 (dc0d45b) into main (038cb20) will decrease coverage by 0.02%.
The diff coverage is n/a.

@@            Coverage Diff             @@
##             main    #1384      +/-   ##
==========================================
- Coverage   61.56%   61.55%   -0.01%     
==========================================
  Files         274      274              
  Lines       24977    24977              
==========================================
- Hits        15375    15371       -4     
- Misses       9602     9606       +4     
Impacted Files Coverage Δ
...nning_scene_monitor/src/planning_scene_monitor.cpp 45.29% <0.00%> (-0.43%) ⬇️

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 038cb20...dc0d45b. Read the comment docs.

@mikeferguson mikeferguson merged commit f4fc946 into moveit:main Jun 21, 2022
@mikeferguson mikeferguson deleted the fix_abort branch June 21, 2022 02:08
@tylerjw
Copy link
Member

tylerjw commented Jun 21, 2022

@tylerjw yeah - I'm not sure this is the best way to fix this - but it's definitely the simplest way to get things back to working

I don't understand how detached threads don't create a use after scope but it seems they are fairly common in ros code. I'm ok with it until someone has time to clean it up, definitely better than the bug you experienced.

peterdavidfagan pushed a commit to peterdavidfagan/moveit2 that referenced this pull request Jul 14, 2022
The noted PR swapped boost::thread to std::thread - however
std::thread will cause the program to crash with a note that
TERMINATE CALLED WITHOUT ACTIVE EXCEPTION if the thread object
goes out of scope while not joinable. Detaching the thread
restores the original workflow prior to the PR and allows
users to send more than one trajectory via the motion planning
plugin in RVIZ (otherwise, it crashes on the first trajectory).
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.

None yet

2 participants