Skip to content

Commit

Permalink
fix regression from moveit#1331 (moveit#1384)
Browse files Browse the repository at this point in the history
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).
  • Loading branch information
mikeferguson authored and peterdavidfagan committed Jul 14, 2022
1 parent 99ba0f1 commit d85025c
Showing 1 changed file with 1 addition and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -239,6 +239,7 @@ void PlanningSceneDisplay::addBackgroundJob(const std::function<void()>& job, co
void PlanningSceneDisplay::spawnBackgroundJob(const std::function<void()>& job)
{
std::thread t(job);
t.detach();
}

void PlanningSceneDisplay::addMainLoopJob(const std::function<void()>& job)
Expand Down

0 comments on commit d85025c

Please sign in to comment.