Skip to content

Commit

Permalink
Fix compilation failure against Gazebo 11.10.0 (#605)
Browse files Browse the repository at this point in the history
  • Loading branch information
traversaro authored Jan 13, 2022
1 parent 6dadd10 commit e941025
Show file tree
Hide file tree
Showing 19 changed files with 24 additions and 5 deletions.
5 changes: 5 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,11 @@ The format of this document is based on [Keep a Changelog](https://keepachangelo

## [Unreleased]

## [4.1.1] - 2022-01-13

### Fixed
- Fix compilation against Gazebo 11.10.0 (https://github.com/robotology/gazebo-yarp-plugins/pull/605, https://github.com/robotology/gazebo-yarp-plugins/issues/606).

## [4.1.0] - 2021-12-23

### Changed
Expand Down
4 changes: 1 addition & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ option(GAZEBO_YARP_PLUGINS_DISABLE_IMPLICIT_NETWORK_WRAPPERS "if enabled removes
# Project version
set(${PROJECT_NAME}_MAJOR_VERSION 4)
set(${PROJECT_NAME}_MINOR_VERSION 1)
set(${PROJECT_NAME}_PATCH_VERSION 0)
set(${PROJECT_NAME}_PATCH_VERSION 1)

set(${PROJECT_NAME}_VERSION
${${PROJECT_NAME}_MAJOR_VERSION}.${${PROJECT_NAME}_MINOR_VERSION}.${${PROJECT_NAME}_PATCH_VERSION})
Expand Down Expand Up @@ -114,5 +114,3 @@ endif()

# add a dox target to generate doxygen documentation
add_subdirectory(doc)


1 change: 1 addition & 0 deletions plugins/basestate/src/BaseStateDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,7 @@ bool GazeboYarpBaseStateDriver::open(yarp::os::Searchable& config)

m_baseState.resize(m_stateDimensions);

using namespace boost::placeholders;
m_updateConnection = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboYarpBaseStateDriver::onUpdate, this, _1));

return true;
Expand Down
1 change: 1 addition & 0 deletions plugins/camera/src/CameraDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -131,6 +131,7 @@ bool GazeboYarpCameraDriver::open(yarp::os::Searchable& config)
}

//Connect the driver to the gazebo simulation
using namespace boost::placeholders;
this->m_updateConnection = m_camera->ConnectNewImageFrame(boost::bind(&GazeboYarpCameraDriver::captureImage, this, _1, _2, _3, _4, _5));
return true;
}
Expand Down
3 changes: 2 additions & 1 deletion plugins/clock/src/Clock.cc
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,7 @@ namespace gazebo
yInfo() << "GazeboYarpClock loaded. Clock port will be " << m_portName;

//The proper loading is done when the world is created
using namespace boost::placeholders;
m_worldCreatedEvent = gazebo::event::Events::ConnectWorldCreated(boost::bind(&GazeboYarpClock::gazeboYarpClockLoad,this,_1));
}

Expand Down Expand Up @@ -153,7 +154,7 @@ namespace gazebo

//Getting world pointer
m_world = gazebo::physics::get_world(world_name);

using namespace boost::placeholders;
m_timeUpdateEvent = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboYarpClock::clockUpdate,this));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -201,7 +201,7 @@ bool GazeboYarpContactLoadCellArrayDriver::open(yarp::os::Searchable& config)
}

std::lock_guard<std::mutex> guard(m_dataMutex);

using namespace boost::placeholders;
this->m_updateConnection = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboYarpContactLoadCellArrayDriver::onUpdate, this, _1));
this->m_sensor->SetActive(true);

Expand Down
1 change: 1 addition & 0 deletions plugins/controlboard/src/ControlBoardDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -387,6 +387,7 @@ bool GazeboYarpControlBoardDriver::gazebo_init()
}

// Connect the onUpdate method to the WorldUpdateBegin event callback
using namespace boost::placeholders;
this->m_updateConnection =
gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboYarpControlBoardDriver::onUpdate,
this, _1));
Expand Down
1 change: 1 addition & 0 deletions plugins/depthCamera/src/DepthCameraDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,7 @@ bool GazeboYarpDepthCameraDriver::open(yarp::os::Searchable &config)
}

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

Expand Down
1 change: 1 addition & 0 deletions plugins/externalwrench/src/ApplyExternalWrench.cc
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,7 @@ void ApplyExternalWrench::Load ( physics::ModelPtr _model, sdf::ElementPtr _sdf

// Listen to the update event. This event is broadcast every
// simulation iteration.
using namespace boost::placeholders;
this->m_updateConnection = event::Events::ConnectWorldUpdateBegin ( boost::bind ( &ApplyExternalWrench::onUpdate, this, _1 ) );

// Listen to gazebo world reset event
Expand Down
1 change: 1 addition & 0 deletions plugins/fakecontrolboard/src/FakeControlBoardDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ bool GazeboYarpFakeControlBoardDriver::open(yarp::os::Searchable& config)
m_controlMode.resize(m_numberOfJoints,VOCAB_CM_NOT_CONFIGURED);
m_interactionMode.resize(m_numberOfJoints,VOCAB_IM_STIFF);

using namespace boost::placeholders;
m_updateConnection =
gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboYarpFakeControlBoardDriver::onUpdate,
this, _1));
Expand Down
1 change: 1 addition & 0 deletions plugins/forcetorque/src/ForceTorqueDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,7 @@ bool GazeboYarpForceTorqueDriver::open(yarp::os::Searchable& config)
}

//Connect the driver to the gazebo simulation
using namespace boost::placeholders;
this->m_updateConnection = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboYarpForceTorqueDriver::onUpdate, this, _1));

return true;
Expand Down
1 change: 1 addition & 0 deletions plugins/imu/src/IMUDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,7 @@ bool GazeboYarpIMUDriver::open(yarp::os::Searchable& config)
}

//Connect the driver to the gazebo simulation
using namespace boost::placeholders;
this->m_updateConnection = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboYarpIMUDriver::onUpdate, this, _1));

return true;
Expand Down
1 change: 1 addition & 0 deletions plugins/inertialmtbPart/src/inertialMTBPartDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,7 @@ bool GazeboYarpInertialMTBPartDriver::open(yarp::os::Searchable& config)
buildOutBufferFixedData(robotPart,enabledSensors);

//Connect the driver to the gazebo simulation
using namespace boost::placeholders;
m_updateConnection = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboYarpInertialMTBPartDriver::onUpdate, this, _1));

return true;
Expand Down
1 change: 1 addition & 0 deletions plugins/lasersensor/src/LaserSensorDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,7 @@ bool GazeboYarpLaserSensorDriver::open(yarp::os::Searchable& config)
}

//Connect the driver to the gazebo simulation
using namespace boost::placeholders;
this->m_updateConnection = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboYarpLaserSensorDriver::onUpdate, this, _1));

//this block of parameters is obtained from gazebo
Expand Down
1 change: 1 addition & 0 deletions plugins/maissensor/src/MaisSensorDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,7 @@ bool GazeboYarpMaisSensorDriver::gazebo_init()

configureJointsLimits();

using namespace boost::placeholders;
this->m_updateConnection = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboYarpMaisSensorDriver::onUpdate, this, _1));

m_gazeboNode = gazebo::transport::NodePtr(new gazebo::transport::Node);
Expand Down
1 change: 1 addition & 0 deletions plugins/multicamera/src/MultiCameraDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,6 +126,7 @@ bool yarp::dev::GazeboYarpMultiCameraDriver::open(yarp::os::Searchable& config)
}

// Connect all the cameras only when everything is set up
using namespace boost::placeholders;
for (unsigned int i = 0; i < m_camera_count; ++i) {
this->m_updateConnection.push_back(this->m_camera[i]->ConnectNewImageFrame(boost::bind(&yarp::dev::GazeboYarpMultiCameraDriver::captureImage, this, i, _1, _2, _3, _4, _5)));
}
Expand Down
1 change: 1 addition & 0 deletions plugins/multicamera/src/MultiCameraPlugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ void MultiCameraPlugin::Load(sensors::SensorPtr _sensor,
std::string cameraName = this->parentSensor->Camera(i)->Name();

// gzdbg << "camera(" << i << ") name [" << cameraName << "]\n";
using namespace boost::placeholders;

// FIXME: hardcoded 2 camera support only
if (cameraName.find("left") != std::string::npos)
Expand Down
1 change: 1 addition & 0 deletions plugins/showmodelcom/src/ShowModelCoM.cc
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,7 @@ namespace gazebo

// Listen to the update event. This event is broadcast every
// simulation iteration.

this->m_updateConnection = event::Events::ConnectWorldUpdateBegin ( boost::bind ( &ShowModelCoM::UpdateChild, this ) );
}
}
1 change: 1 addition & 0 deletions plugins/worldinterface/src/worldinterface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,7 @@ void WorldInterface::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)

// Listen to the update event. This event is broadcast every
// simulation iteration.
using namespace boost::placeholders;
this->updateConnection = event::Events::ConnectWorldUpdateBegin(
boost::bind(&WorldInterface::OnUpdate, this, _1));

Expand Down

0 comments on commit e941025

Please sign in to comment.