Skip to content

Commit 1ccaeb6

Browse files
committed
Fix: random segmentation fault during detach
1 parent be9ed40 commit 1ccaeb6

File tree

2 files changed

+8
-0
lines changed

2 files changed

+8
-0
lines changed

include/gazebo_ros_link_attacher.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,8 @@
77
#ifndef GAZEBO_ROS_LINK_ATTACHER_HH
88
#define GAZEBO_ROS_LINK_ATTACHER_HH
99

10+
#include <boost/thread/recursive_mutex.hpp>
11+
1012
#include <ros/ros.h>
1113

1214
#include <sdf/sdf.hh>
@@ -73,6 +75,8 @@ namespace gazebo
7375

7476
std::vector<fixedJoint> joints;
7577

78+
boost::recursive_mutex* physics_mutex;
79+
7680
/// \brief The physics engine.
7781
physics::PhysicsEnginePtr physics;
7882

src/gazebo_ros_link_attacher.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,4 @@
1+
#include <boost/thread/recursive_mutex.hpp>
12
#include <gazebo/common/Plugin.hh>
23
#include <ros/ros.h>
34
#include "gazebo_ros_link_attacher.h"
@@ -35,6 +36,8 @@ namespace gazebo
3536

3637
this->world = _world;
3738
this->physics = this->world->Physics();
39+
this->physics_mutex = this->physics->GetPhysicsUpdateMutex();
40+
3841
this->attach_service_ = this->nh_.advertiseService("attach", &GazeboRosLinkAttacher::attach_callback, this);
3942
ROS_INFO_STREAM("Attach service at: " << this->nh_.resolveName("attach"));
4043
this->detach_service_ = this->nh_.advertiseService("detach", &GazeboRosLinkAttacher::detach_callback, this);
@@ -151,6 +154,7 @@ namespace gazebo
151154
// search for the instance of joint and do detach
152155
fixedJoint j;
153156
if(this->getJoint(model1, link1, model2, link2, j)){
157+
boost::recursive_mutex::scoped_lock lock(*this->physics_mutex);
154158
j.joint->Detach();
155159
return true;
156160
}

0 commit comments

Comments
 (0)