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 random segmentation fault during Detach #11

Open
wants to merge 1 commit into
base: melodic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions include/gazebo_ros_link_attacher.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,12 @@ namespace gazebo
gazebo_ros_link_attacher::Attach::Response &res);
bool detach_callback(gazebo_ros_link_attacher::Attach::Request &req,
gazebo_ros_link_attacher::Attach::Response &res);
void OnUpdate();

std::vector<fixedJoint> joints;
std::vector<fixedJoint> detach_vector;

event::ConnectionPtr beforePhysicsUpdateConnection;

/// \brief The physics engine.
physics::PhysicsEnginePtr physics;
Expand Down
26 changes: 25 additions & 1 deletion src/gazebo_ros_link_attacher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,9 @@ namespace gazebo
GazeboRosLinkAttacher::GazeboRosLinkAttacher() :
nh_("link_attacher_node")
{
std::vector<fixedJoint> vect;
this->detach_vector = vect;
Comment on lines +18 to +19
Copy link

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.

this->beforePhysicsUpdateConnection = event::Events::ConnectBeforePhysicsUpdate(std::bind(&GazeboRosLinkAttacher::OnUpdate, this));
}


Expand Down Expand Up @@ -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);
Copy link

Choose a reason for hiding this comment

The 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;
}

Expand Down Expand Up @@ -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())
Copy link

Choose a reason for hiding this comment

The 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();
}
}

}