commit 04855dc0fd2d82d6fe72c0b54ae66a5f86c5ceb4 Author: Steven Peters Date: Tue Jan 12 17:36:06 2016 -0800 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. diff --git a/gazebo_plugins/src/gazebo_ros_block_laser.cpp b/gazebo_plugins/src/gazebo_ros_block_laser.cpp index d8f40bc..76e0206 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();