diff --git a/src/clustering.cpp b/src/clustering.cpp index b5a4a7c75333db9538f6731cc9ea5b6f8e1c5678..950d549aa62924182f6d611716ae7039ad043036 100644 --- a/src/clustering.cpp +++ b/src/clustering.cpp @@ -271,7 +271,7 @@ void laserscanutils::preFilterScan(const laserscanutils::ScanParams & _params, { act_range = _ranges[i]; - if ( (act_range >=_params.range_min_) && (act_range <= _params.range_max_) && !(isnan(act_range)) && !(isinf(act_range)) ) + if ( (act_range >=_params.range_min_) && (act_range <= _params.range_max_) && !(std::isnan(act_range)) && !(std::isinf(act_range)) ) { act_theta = _params.angle_min_+ _params.angle_step_*(i); @@ -701,7 +701,7 @@ unsigned int laserscanutils::scanProcess(const ScanParams & _params, for(unsigned int i=0; i<_ranges.size(); ++i) { act_range = _ranges[i]; - if ( (act_range >=_params.range_min_) && (act_range <= _params.range_max_) && !(isnan(act_range)) && !(isinf(act_range)) ) + if ( (act_range >=_params.range_min_) && (act_range <= _params.range_max_) && !(std::isnan(act_range)) && !(std::isinf(act_range)) ) { act_theta = _params.angle_min_+ _params.angle_step_*(i); diff --git a/src/object_detector.cpp b/src/object_detector.cpp index 35607fc5e1e8baf9d63d0fc7c9f58425d9fba91e..5a6c08f07bf1c317657ac7803c6ef01d5edfb726 100644 --- a/src/object_detector.cpp +++ b/src/object_detector.cpp @@ -254,7 +254,7 @@ void laserscanutils::preFilterScan2homog(const laserscanutils::ScanParams & _par { act_range = _ranges[i]; - if ( (act_range >=_params.range_min_) && (act_range <= _params.range_max_) && !(isnan(act_range)) && !(isinf(act_range)) ) + if ( (act_range >=_params.range_min_) && (act_range <= _params.range_max_) && !(std::isnan(act_range)) && !(std::isinf(act_range)) ) { act_theta = _params.angle_min_+ _params.angle_step_*(i); diff --git a/src/scan_basics.cpp b/src/scan_basics.cpp index aed6946fc32cc5c9a9cf59f396a58ddc481155fb..193f2bcf801f65baaf58b502fb3879dc3341dcdb 100644 --- a/src/scan_basics.cpp +++ b/src/scan_basics.cpp @@ -26,7 +26,7 @@ void laserscanutils::ranges2xy(const ScanParams & _params, std::vector<float> & //for each range, check correctness of value and translate from polar to xy coordinates while (ii <_ranges.size()) { - if ( _ranges[ii] >_params.range_min_ && _ranges[ii] < _params.range_max_ && !isnan(_ranges[ii]) && !isinf(_ranges[ii]) ) + if ( _ranges[ii] >_params.range_min_ && _ranges[ii] < _params.range_max_ && !std::isnan(_ranges[ii]) && !std::isinf(_ranges[ii]) ) { //transform from polar to euclidean _points(0,ii) = _ranges[ii] * cos(azimuth); @@ -66,7 +66,7 @@ void laserscanutils::ranges2xy(const ScanParams & _params, std::vector<float> & //for each range, check correctness of value and translate from polar to xy coordinates while (ii <_ranges.size()) { - if ( _ranges[ii] >_params.range_min_ && _ranges[ii] < _params.range_max_ && !isnan(_ranges[ii]) && !isinf(_ranges[ii]) ) + if ( _ranges[ii] >_params.range_min_ && _ranges[ii] < _params.range_max_ && !std::isnan(_ranges[ii]) && !std::isinf(_ranges[ii]) ) { //transform from polar to euclidean _points(0,ii) = _ranges[ii] * cos(azimuth);