-
Notifications
You must be signed in to change notification settings - Fork 68
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 random segmentation fault during Detach #11
base: melodic-devel
Are you sure you want to change the base?
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -15,6 +15,9 @@ namespace gazebo | |
GazeboRosLinkAttacher::GazeboRosLinkAttacher() : | ||
nh_("link_attacher_node") | ||
{ | ||
std::vector<fixedJoint> vect; | ||
this->detach_vector = vect; | ||
this->beforePhysicsUpdateConnection = event::Events::ConnectBeforePhysicsUpdate(std::bind(&GazeboRosLinkAttacher::OnUpdate, this)); | ||
} | ||
|
||
|
||
|
@@ -151,7 +154,8 @@ namespace gazebo | |
// search for the instance of joint and do detach | ||
fixedJoint j; | ||
if(this->getJoint(model1, link1, model2, link2, j)){ | ||
j.joint->Detach(); | ||
this->detach_vector.push_back(j); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I believe this operation should be protected by a mutex. If I understand correctly, the cause of the crash is that sometimes the detach operation was called during the physics update loop, that's why you must postpone it and do it in later in the update callback. Then it is possible that you are both reading and writing on the vector at the same time, and should be protected by a mutex. |
||
ROS_INFO_STREAM("Detach joint request pushed in the detach vector"); | ||
return true; | ||
} | ||
|
||
|
@@ -210,4 +214,24 @@ namespace gazebo | |
return true; | ||
} | ||
|
||
// thanks to https://answers.gazebosim.org/question/12118/intermittent-segmentation-fault-possibly-by-custom-worldplugin-attaching-and-detaching-child/?answer=24271#post-id-24271 | ||
void GazeboRosLinkAttacher::OnUpdate() | ||
{ | ||
if(!this->detach_vector.empty()) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This should also be protected by a mutex for the reason above. |
||
{ | ||
ROS_INFO_STREAM("Received before physics update callback... Detaching joints"); | ||
std::vector<fixedJoint>::iterator it; | ||
it = this->detach_vector.begin(); | ||
fixedJoint j; | ||
while (it != this->detach_vector.end()) | ||
{ | ||
j = *it; | ||
j.joint->Detach(); | ||
ROS_INFO_STREAM("Joint detached !"); | ||
++it; | ||
} | ||
detach_vector.clear(); | ||
} | ||
} | ||
|
||
} |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I don't think this is necessary.