From 2f9f6a7f8e73659f4ab287b42f5475b3778efd7d Mon Sep 17 00:00:00 2001 From: Steven Peters Date: Tue, 12 Jan 2016 17:36:06 -0800 Subject: [PATCH] Fix gazebo6 deprecation warnings Several RaySensor functions are deprecated in gazebo6 and are removed in gazebo7. The return type is changed to use ignition math and the function name is changed. This adds ifdef's to handle the changes. --- gazebo_plugins/src/gazebo_ros_block_laser.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/gazebo_plugins/src/gazebo_ros_block_laser.cpp b/gazebo_plugins/src/gazebo_ros_block_laser.cpp index d8f40bc6a..76e020639 100644 --- a/gazebo_plugins/src/gazebo_ros_block_laser.cpp +++ b/gazebo_plugins/src/gazebo_ros_block_laser.cpp @@ -230,8 +230,13 @@ void GazeboRosBlockLaser::PutLaserData(common::Time &_updateTime) this->parent_ray_sensor_->SetActive(false); +#if GAZEBO_MAJOR_VERSION >= 6 + auto maxAngle = this->parent_ray_sensor_->AngleMax(); + auto minAngle = this->parent_ray_sensor_->AngleMin(); +#else math::Angle maxAngle = this->parent_ray_sensor_->GetAngleMax(); math::Angle minAngle = this->parent_ray_sensor_->GetAngleMin(); +#endif double maxRange = this->parent_ray_sensor_->GetRangeMax(); double minRange = this->parent_ray_sensor_->GetRangeMin(); @@ -240,8 +245,13 @@ void GazeboRosBlockLaser::PutLaserData(common::Time &_updateTime) int verticalRayCount = this->parent_ray_sensor_->GetVerticalRayCount(); int verticalRangeCount = this->parent_ray_sensor_->GetVerticalRangeCount(); +#if GAZEBO_MAJOR_VERSION >= 6 + auto verticalMaxAngle = this->parent_ray_sensor_->VerticalAngleMax(); + auto verticalMinAngle = this->parent_ray_sensor_->VerticalAngleMin(); +#else math::Angle verticalMaxAngle = this->parent_ray_sensor_->GetVerticalAngleMax(); math::Angle verticalMinAngle = this->parent_ray_sensor_->GetVerticalAngleMin(); +#endif double yDiff = maxAngle.Radian() - minAngle.Radian(); double pDiff = verticalMaxAngle.Radian() - verticalMinAngle.Radian();