Commit d4903a76 authored by Nicolae Rosia's avatar Nicolae Rosia
Browse files

gazebo_lidar_plugin: fix compilation warnings against Gazebo 7


Signed-off-by: default avatarNicolae Rosia <nicolae.rosia@gmail.com>
parent ba00aeb8
...@@ -48,7 +48,11 @@ RayPlugin::RayPlugin() ...@@ -48,7 +48,11 @@ RayPlugin::RayPlugin()
///////////////////////////////////////////////// /////////////////////////////////////////////////
RayPlugin::~RayPlugin() RayPlugin::~RayPlugin()
{ {
#if GAZEBO_MAJOR_VERSION >= 7
this->parentSensor->LaserShape()->DisconnectNewLaserScans(
#else
this->parentSensor->GetLaserShape()->DisconnectNewLaserScans( this->parentSensor->GetLaserShape()->DisconnectNewLaserScans(
#endif
this->newLaserScansConnection); this->newLaserScansConnection);
this->newLaserScansConnection.reset(); this->newLaserScansConnection.reset();
...@@ -70,10 +74,18 @@ void RayPlugin::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf) ...@@ -70,10 +74,18 @@ void RayPlugin::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
if (!this->parentSensor) if (!this->parentSensor)
gzthrow("RayPlugin requires a Ray Sensor as its parent"); gzthrow("RayPlugin requires a Ray Sensor as its parent");
#if GAZEBO_MAJOR_VERSION >= 7
this->world = physics::get_world(this->parentSensor->WorldName());
#else
this->world = physics::get_world(this->parentSensor->GetWorldName()); this->world = physics::get_world(this->parentSensor->GetWorldName());
#endif
this->newLaserScansConnection = this->newLaserScansConnection =
#if GAZEBO_MAJOR_VERSION >= 7
this->parentSensor->LaserShape()->ConnectNewLaserScans(
#else
this->parentSensor->GetLaserShape()->ConnectNewLaserScans( this->parentSensor->GetLaserShape()->ConnectNewLaserScans(
#endif
boost::bind(&RayPlugin::OnNewLaserScans, this)); boost::bind(&RayPlugin::OnNewLaserScans, this));
if (_sdf->HasElement("robotNamespace")) if (_sdf->HasElement("robotNamespace"))
...@@ -91,9 +103,15 @@ void RayPlugin::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf) ...@@ -91,9 +103,15 @@ void RayPlugin::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
void RayPlugin::OnNewLaserScans() void RayPlugin::OnNewLaserScans()
{ {
lidar_message.set_time_msec(0); lidar_message.set_time_msec(0);
#if GAZEBO_MAJOR_VERSION >= 7
lidar_message.set_min_distance(parentSensor->RangeMin());
lidar_message.set_max_distance(parentSensor->RangeMax());
lidar_message.set_current_distance(parentSensor->Range(0));
#else
lidar_message.set_min_distance(parentSensor->GetRangeMin()); lidar_message.set_min_distance(parentSensor->GetRangeMin());
lidar_message.set_max_distance(parentSensor->GetRangeMax()); lidar_message.set_max_distance(parentSensor->GetRangeMax());
lidar_message.set_current_distance(parentSensor->GetRange(0)); lidar_message.set_current_distance(parentSensor->GetRange(0));
#endif
lidar_pub_->Publish(lidar_message); lidar_pub_->Publish(lidar_message);
} }
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment