Skip to content

Commit

Permalink
Fix deletion of model in Gazebo 8
Browse files Browse the repository at this point in the history
Streamlining of the disconnection event: simply resetting the
Connection shared pointer is enough to disconnect an event
since at least Gazebo 2. So the code was cleaned up from all
the call to the Disconnect* functions are all the unnecessary
check if a connection pointer is valid before resetting it.

Fix robotology#282 .
  • Loading branch information
traversaro committed Feb 28, 2017
1 parent fa35c8d commit 487becf
Show file tree
Hide file tree
Showing 13 changed files with 22 additions and 67 deletions.
3 changes: 1 addition & 2 deletions plugins/camera/src/CameraDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,8 +148,7 @@ bool GazeboYarpCameraDriver::close()
{
if (this->m_updateConnection.get())
{
m_camera->DisconnectNewImageFrame(this->m_updateConnection);
this->m_updateConnection = gazebo::event::ConnectionPtr();
this->m_updateConnection.reset();
m_parentSensor = NULL;
}

Expand Down
17 changes: 4 additions & 13 deletions plugins/clock/src/Clock.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,15 +40,9 @@ namespace gazebo

void GazeboYarpClock::cleanup()
{
if (m_worldCreatedEvent.get()) {
gazebo::event::Events::DisconnectWorldCreated(m_worldCreatedEvent);
m_worldCreatedEvent = gazebo::event::ConnectionPtr(); //resetting the pointer to NULL. I don't know if boost does it automatically with the above call
}
if (m_timeUpdateEvent.get()) {
gazebo::event::Events::DisconnectWorldUpdateBegin(m_timeUpdateEvent);
m_timeUpdateEvent = gazebo::event::ConnectionPtr();
}

m_worldCreatedEvent.reset();
m_timeUpdateEvent.reset();

if (m_clockPort) {
m_clockPort->close();
delete m_clockPort; m_clockPort = 0;
Expand Down Expand Up @@ -99,10 +93,7 @@ namespace gazebo

void GazeboYarpClock::gazeboYarpClockLoad(std::string world_name)
{
if (m_worldCreatedEvent.get()) {
gazebo::event::Events::DisconnectWorldCreated(m_worldCreatedEvent);
m_worldCreatedEvent = gazebo::event::ConnectionPtr();
}
m_worldCreatedEvent.reset();

//Create ports
m_clockPort = new yarp::os::BufferedPort<yarp::os::Bottle>();
Expand Down
6 changes: 1 addition & 5 deletions plugins/controlboard/src/ControlBoardDriverDeviceDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,11 +33,7 @@ bool GazeboYarpControlBoardDriver::open(yarp::os::Searchable& config)

bool GazeboYarpControlBoardDriver::close()
{
//unbinding events
if (this->m_updateConnection.get()) {
gazebo::event::Events::DisconnectWorldUpdateBegin (this->m_updateConnection);
this->m_updateConnection = gazebo::event::ConnectionPtr();
}
this->m_updateConnection.reset();

delete [] m_controlMode;
delete [] m_interactionMode;
Expand Down
23 changes: 4 additions & 19 deletions plugins/depthCamera/src/DepthCameraDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,36 +107,21 @@ bool GazeboYarpDepthCameraDriver::open(yarp::os::Searchable &config)

m_colorFrameMutex.post();



//Connect the driver to the gazebo simulation
auto imageConnectionBind = boost::bind(&GazeboYarpDepthCameraDriver::OnNewImageFrame, this, _1, _2, _3, _4, _5);
auto depthConnectionBind = boost::bind(&GazeboYarpDepthCameraDriver::OnNewDepthFrame, this, _1, _2, _3, _4, _5);

this->m_updateImageFrame_Connection = m_depthCameraPtr->ConnectNewImageFrame(imageConnectionBind);
this->m_updateDepthFrame_Connection = m_depthCameraPtr->ConnectNewDepthFrame(depthConnectionBind);

return true;
}

bool GazeboYarpDepthCameraDriver::close()
{
if (this->m_updateImageFrame_Connection.get())
{
m_depthCameraPtr->DisconnectNewImageFrame(this->m_updateImageFrame_Connection);
this->m_updateImageFrame_Connection = gazebo::event::ConnectionPtr();
}

if (this->m_updateRGBPointCloud_Connection.get())
{
m_depthCameraPtr->DisconnectNewImageFrame(this->m_updateRGBPointCloud_Connection);
this->m_updateRGBPointCloud_Connection = gazebo::event::ConnectionPtr();
}

if (this->m_updateDepthFrame_Connection.get())
{
m_depthCameraPtr->DisconnectNewImageFrame(this->m_updateDepthFrame_Connection);
this->m_updateDepthFrame_Connection = gazebo::event::ConnectionPtr();
}
this->m_updateImageFrame_Connection.reset();
this->m_updateRGBPointCloud_Connection.reset();
this->m_updateDepthFrame_Connection.reset();

m_depthCameraSensorPtr = NULL;

Expand Down
2 changes: 1 addition & 1 deletion plugins/externalwrench/src/ApplyExternalWrench.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ ApplyExternalWrench::ApplyExternalWrench()
ApplyExternalWrench::~ApplyExternalWrench()
{
m_rpcThread.stop();
gazebo::event::Events::DisconnectWorldUpdateBegin ( this->m_updateConnection );
this->m_updateConnection.reset();
}

void ApplyExternalWrench::UpdateChild()
Expand Down
5 changes: 1 addition & 4 deletions plugins/forcetorque/src/ForceTorqueDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,10 +86,7 @@ bool GazeboYarpForceTorqueDriver::open(yarp::os::Searchable& config)

bool GazeboYarpForceTorqueDriver::close()
{
if (this->m_updateConnection.get()) {
gazebo::event::Events::DisconnectWorldUpdateBegin(this->m_updateConnection);
this->m_updateConnection = gazebo::event::ConnectionPtr();
}
this->m_updateConnection.reset();
return true;
}

Expand Down
5 changes: 1 addition & 4 deletions plugins/imu/src/IMUDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,10 +95,7 @@ bool GazeboYarpIMUDriver::open(yarp::os::Searchable& config)

bool GazeboYarpIMUDriver::close()
{
if (this->m_updateConnection.get()) {
gazebo::event::Events::DisconnectWorldUpdateBegin(this->m_updateConnection);
this->m_updateConnection = gazebo::event::ConnectionPtr();
}
this->m_updateConnection.reset();
return true;
}

Expand Down
2 changes: 1 addition & 1 deletion plugins/jointsensors/src/JointSensorsDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,7 @@ bool GazeboYarpJointSensorsDriver::setJointSensorsType(yarp::os::Property & plug

bool GazeboYarpJointSensorsDriver::close()
{
gazebo::event::Events::DisconnectWorldUpdateBegin(this->updateConnection);
this->updateConnection.reset();
return true;
}

Expand Down
7 changes: 2 additions & 5 deletions plugins/lasersensor/src/LaserSensorDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,11 +144,8 @@ bool GazeboYarpLaserSensorDriver::open(yarp::os::Searchable& config)

bool GazeboYarpLaserSensorDriver::close()
{
if (this->m_updateConnection.get())
{
gazebo::event::Events::DisconnectWorldUpdateBegin(this->m_updateConnection);
this->m_updateConnection = gazebo::event::ConnectionPtr();
}
this->m_updateConnection.reset();

return true;
}

Expand Down
6 changes: 1 addition & 5 deletions plugins/maissensor/src/MaisSensorDeviceDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,7 @@ bool GazeboYarpMaisSensorDriver::open(yarp::os::Searchable& config)

bool GazeboYarpMaisSensorDriver::close()
{
//unbinding events
if (this->m_updateConnection.get()) {
gazebo::event::Events::DisconnectWorldUpdateBegin (this->m_updateConnection);
this->m_updateConnection = gazebo::event::ConnectionPtr();
}
this->m_updateConnection.reset();

return true;
}
8 changes: 2 additions & 6 deletions plugins/multicamera/src/MultiCameraDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,12 +145,8 @@ bool yarp::dev::GazeboYarpMultiCameraDriver::open(yarp::os::Searchable& config)
bool yarp::dev::GazeboYarpMultiCameraDriver::close()
{
for (unsigned int i = 0; i < m_camera_count; ++i) {
if (this->m_updateConnection[i].get())
{
m_camera[i]->DisconnectNewImageFrame(this->m_updateConnection[i]);
this->m_updateConnection[i] = gazebo::event::ConnectionPtr();
m_parentSensor = NULL;
}
this->m_updateConnection[i].reset();
m_parentSensor = NULL;
delete[] m_imageBuffer[i];
m_imageBuffer[i] = 0;
delete m_dataMutex[i];
Expand Down
3 changes: 2 additions & 1 deletion plugins/showmodelcom/src/ShowModelCoM.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,8 @@ namespace gazebo
delete m_comOutputPort;
m_comOutputPort = 0;
}
gazebo::event::Events::DisconnectWorldUpdateBegin(this->m_updateConnection);

m_updateConnection.reset();
yarp::os::Network::fini();
}

Expand Down
2 changes: 1 addition & 1 deletion plugins/videotexture/src/VideoTexture.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ namespace gazebo

VideoTexture::~VideoTexture()
{
event::Events::DisconnectPreRender(m_connection);
m_connection.reset();
if (m_network)
{
delete m_network;
Expand Down

0 comments on commit 487becf

Please sign in to comment.