Skip to content

Commit

Permalink
Fix gazebo6 deprecation warnings
Browse files Browse the repository at this point in the history
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.
  • Loading branch information
scpeters committed Jan 15, 2016
1 parent 0d814d4 commit 2f9f6a7
Showing 1 changed file with 10 additions and 0 deletions.
10 changes: 10 additions & 0 deletions gazebo_plugins/src/gazebo_ros_block_laser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand All @@ -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();
Expand Down

0 comments on commit 2f9f6a7

Please sign in to comment.