Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Prefer C++ method std::acos over C method acos #3236

Merged
merged 1 commit into from
Jul 19, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions apps/in_hand_scanner/src/visibility_confidence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ pcl::ihs::addDirection (const Eigen::Vector4f& normal,
// TODO: The threshold is hard coded for a frequency=3.
// It can be calculated with
// - max_z = maximum z value of the dome vertices (excluding [0; 0; 1])
// - thresh = cos (acos (max_z) / 2)
// - thresh = cos (std::acos (max_z) / 2)
// - always round up!
// - with max_z = 0.939 -> thresh = 0.9847 ~ 0.985
if (dot <= .985f)
Expand All @@ -134,7 +134,7 @@ pcl::ihs::addDirection (const Eigen::Vector4f& normal,

// Find the closest viewing direction
// NOTE: cos (0deg) = 1 = max
// acos (angle) = dot (a, b) / (norm (a) * norm (b)
// std::acos (angle) = dot (a, b) / (norm (a) * norm (b)
// m_sphere_vertices are already normalized
unsigned int index = 0;
aligned_direction.transpose ().lazyProduct (pcl::ihs::dome.getVertices ()).maxCoeff (&index);
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/common/impl/common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ pcl::getAngle3D (const Eigen::Vector4f &v1, const Eigen::Vector4f &v2, const boo
rad = -1.0;
else if (rad > 1.0)
rad = 1.0;
return (in_degree ? acos (rad) * 180.0 / M_PI : acos (rad));
return (in_degree ? std::acos (rad) * 180.0 / M_PI : std::acos (rad));
}

inline double
Expand All @@ -63,7 +63,7 @@ pcl::getAngle3D (const Eigen::Vector3f &v1, const Eigen::Vector3f &v2, const boo
rad = -1.0;
else if (rad > 1.0)
rad = 1.0;
return (in_degree ? acos (rad) * 180.0 / M_PI : acos (rad));
return (in_degree ? std::acos (rad) * 180.0 / M_PI : std::acos (rad));
}

//////////////////////////////////////////////////////////////////////////////////////////////
Expand Down
2 changes: 1 addition & 1 deletion common/include/pcl/common/impl/polynomial_calculations.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -230,7 +230,7 @@ inline void
else
{
double tmp1 = sqrt (- (4.0/3.0)*alpha),
tmp2 = acos (-sqrt (-27.0/alpha3)*0.5*beta)/3.0;
tmp2 = std::acos (-sqrt (-27.0/alpha3)*0.5*beta)/3.0;
roots.push_back (tmp1*cos (tmp2) - resubValue);
roots.push_back (-tmp1*cos (tmp2 + M_PI/3.0) - resubValue);
roots.push_back (-tmp1*cos (tmp2 - M_PI/3.0) - resubValue);
Expand Down
14 changes: 7 additions & 7 deletions common/include/pcl/range_image/impl/range_image.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -635,7 +635,7 @@ RangeImage::getImpactAngle (const PointWithRange& point1, const PointWithRange&
d = std::sqrt (dSqr);
float cos_impact_angle = (r2Sqr + dSqr - r1Sqr)/ (2.0f*r2*d);
cos_impact_angle = (std::max) (0.0f, (std::min) (1.0f, cos_impact_angle));
impact_angle = acosf (cos_impact_angle); // Using the cosine rule
impact_angle = std::acos (cos_impact_angle); // Using the cosine rule
}

if (point1.range > point2.range)
Expand Down Expand Up @@ -715,7 +715,7 @@ RangeImage::getSurfaceAngleChange (int x, int y, int radius, float& angle_change
}
angle_change_x = transformed_left.dot (transformed_right);
angle_change_x = (std::max) (0.0f, (std::min) (1.0f, angle_change_x));
angle_change_x = acosf (angle_change_x);
angle_change_x = std::acos (angle_change_x);
}

if (isObserved (x, y-radius) && isObserved (x, y+radius))
Expand Down Expand Up @@ -747,7 +747,7 @@ RangeImage::getSurfaceAngleChange (int x, int y, int radius, float& angle_change
}
angle_change_y = transformed_top.dot (transformed_bottom);
angle_change_y = (std::max) (0.0f, (std::min) (1.0f, angle_change_y));
angle_change_y = acosf (angle_change_y);
angle_change_y = std::acos (angle_change_y);
}
}

Expand All @@ -761,18 +761,18 @@ RangeImage::getSurfaceAngleChange (int x, int y, int radius, float& angle_change
//if (std::isinf (neighbor2.range))
//return 0.0f;
//else
//return acosf ( (Eigen::Vector3f (point.x, point.y, point.z)-getSensorPos ()).normalized ().dot ( (Eigen::Vector3f (neighbor2.x, neighbor2.y, neighbor2.z)-Eigen::Vector3f (point.x, point.y, point.z)).normalized ()));
//return std::acos ( (Eigen::Vector3f (point.x, point.y, point.z)-getSensorPos ()).normalized ().dot ( (Eigen::Vector3f (neighbor2.x, neighbor2.y, neighbor2.z)-Eigen::Vector3f (point.x, point.y, point.z)).normalized ()));
//}
//if (std::isinf (neighbor2.range))
//return acosf ( (Eigen::Vector3f (point.x, point.y, point.z)-getSensorPos ()).normalized ().dot ( (Eigen::Vector3f (neighbor1.x, neighbor1.y, neighbor1.z)-Eigen::Vector3f (point.x, point.y, point.z)).normalized ()));
//return std::acos ( (Eigen::Vector3f (point.x, point.y, point.z)-getSensorPos ()).normalized ().dot ( (Eigen::Vector3f (neighbor1.x, neighbor1.y, neighbor1.z)-Eigen::Vector3f (point.x, point.y, point.z)).normalized ()));

//float d1_squared = squaredEuclideanDistance (point, neighbor1),
//d1 = std::sqrt (d1_squared),
//d2_squared = squaredEuclideanDistance (point, neighbor2),
//d2 = std::sqrt (d2_squared),
//d3_squared = squaredEuclideanDistance (neighbor1, neighbor2);
//float cos_surface_change = (d1_squared + d2_squared - d3_squared)/ (2.0f*d1*d2),
//surface_change = acosf (cos_surface_change);
//surface_change = std::acos (cos_surface_change);
//if (std::isnan (surface_change))
//surface_change = static_cast<float> (M_PI);
////std::cout << PVARN (point)<<PVARN (neighbor1)<<PVARN (neighbor2)<<PVARN (cos_surface_change)<<PVARN (surface_change)<<PVARN (d1)<<PVARN (d2)<<PVARN (d1_squared)<<PVARN (d2_squared)<<PVARN (d3_squared);
Expand Down Expand Up @@ -887,7 +887,7 @@ RangeImage::getImpactAngleBasedOnLocalNormal (int x, int y, int radius) const
Eigen::Vector3f normal;
if (!getNormalForClosestNeighbors (x, y, radius, point, no_of_nearest_neighbors, normal, 1))
return -std::numeric_limits<float>::infinity ();
return deg2rad (90.0f) - acosf (normal.dot ( (getSensorPos ()-getEigenVector3f (point)).normalized ()));
return deg2rad (90.0f) - std::acos (normal.dot ( (getSensorPos ()-getEigenVector3f (point)).normalized ()));
}


Expand Down
2 changes: 1 addition & 1 deletion common/src/bearing_angle_image.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ BearingAngleImage::getAngle (const PointXYZ &point1, const PointXYZ &point2)

if (a != 0 && b != 0)
{
theta = acos ((a + b - c) / (2 * sqrt (a) * sqrt (b))) * 180 / M_PI;
theta = std::acos ((a + b - c) / (2 * sqrt (a) * sqrt (b))) * 180 / M_PI;
}
else
{
Expand Down
8 changes: 4 additions & 4 deletions cuda/sample_consensus/src/sac_model_1point_plane.cu
Original file line number Diff line number Diff line change
Expand Up @@ -485,9 +485,9 @@ namespace pcl
if ((fabs (actual_disparity - orig_disparity) <= 1.0/2.0) & (idx != -1)
&
(
fabs (acos (normal.x*coefficients.x + normal.y*coefficients.y + normal.z*coefficients.z)) < angle_threshold
fabs (std::acos (normal.x*coefficients.x + normal.y*coefficients.y + normal.z*coefficients.z)) < angle_threshold
|
fabs (acos (-(normal.x*coefficients.x + normal.y*coefficients.y + normal.z*coefficients.z))) < angle_threshold
fabs (std::acos (-(normal.x*coefficients.x + normal.y*coefficients.y + normal.z*coefficients.z))) < angle_threshold
)
)
return (idx);
Expand All @@ -510,9 +510,9 @@ namespace pcl
pt.z * coefficients.z + coefficients.w) < threshold
&
(
fabs (acos (normal.x*coefficients.x + normal.y*coefficients.y + normal.z*coefficients.z)) < angle_threshold
fabs (std::acos (normal.x*coefficients.x + normal.y*coefficients.y + normal.z*coefficients.z)) < angle_threshold
|
fabs (acos (-(normal.x*coefficients.x + normal.y*coefficients.y + normal.z*coefficients.z))) < angle_threshold
fabs (std::acos (-(normal.x*coefficients.x + normal.y*coefficients.y + normal.z*coefficients.z))) < angle_threshold
)
)
// If inlier, return its position in the vector
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ rejectBadCorrespondences (const CorrespondencesPtr &all_correspondences,

// Reject if the angle between the normals is really off
CorrespondenceRejectorSurfaceNormal rej_normals;
rej_normals.setThreshold (acos (deg2rad (45.0)));
rej_normals.setThreshold (std::acos (deg2rad (45.0)));
rej_normals.initializeDataContainer<PointT, PointT> ();
rej_normals.setInputCloud<PointT> (src);
rej_normals.setInputNormals<PointT, PointT> (src);
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/3dsc.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,7 @@ pcl::ShapeContext3DEstimation<PointInT, PointNT, PointOutT>::computePoint (
Eigen::Vector3f no = neighbour - origin;
no.normalize ();
float theta = normal.dot (no);
theta = pcl::rad2deg (acosf (std::min (1.0f, std::max (-1.0f, theta))));
theta = pcl::rad2deg (std::acos (std::min (1.0f, std::max (-1.0f, theta))));

// Bin (j, k, l)
size_t j = 0;
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/board.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ pcl::BOARDLocalReferenceFrameEstimation<PointInT, PointNT, PointOutT>::getAngleB
{
Eigen::Vector3f angle_orientation;
angle_orientation = v1.cross (v2);
float angle_radians = acosf (std::max (-1.0f, std::min (1.0f, v1.dot (v2))));
float angle_radians = std::acos (std::max (-1.0f, std::min (1.0f, v1.dot (v2))));

angle_radians = angle_orientation.dot (axis) < 0.f ? (2 * static_cast<float> (M_PI) - angle_radians) : angle_radians;

Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/cppf.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ pcl::CPPFEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut
Eigen::Vector3f model_reference_point = input_->points[i].getVector3fMap (),
model_reference_normal = normals_->points[i].getNormalVector3fMap (),
model_point = input_->points[j].getVector3fMap ();
Eigen::AngleAxisf rotation_mg (acosf (model_reference_normal.dot (Eigen::Vector3f::UnitX ())),
Eigen::AngleAxisf rotation_mg (std::acos (model_reference_normal.dot (Eigen::Vector3f::UnitX ())),
model_reference_normal.cross (Eigen::Vector3f::UnitX ()).normalized ());
Eigen::Affine3f transform_mg = Eigen::Translation3f ( rotation_mg * ((-1) * model_reference_point)) * rotation_mg;

Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/cvfh.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ pcl::CVFHEstimation<PointInT, PointNT, PointOutT>::extractEuclideanClustersSmoot
+ normals.points[seed_queue[sq_idx]].normal[1] * normals.points[nn_indices[j]].normal[1]
+ normals.points[seed_queue[sq_idx]].normal[2] * normals.points[nn_indices[j]].normal[2];

if (fabs (acos (dot_p)) < eps_angle)
if (fabs (std::acos (dot_p)) < eps_angle)
{
processed[nn_indices[j]] = true;
seed_queue.push_back (nn_indices[j]);
Expand Down
6 changes: 3 additions & 3 deletions features/include/pcl/features/impl/esf.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,9 +118,9 @@ pcl::ESFEstimation<PointInT, PointOutT>::computeESF (
v23.normalize ();

//TODO: .dot gives nan's
th1 = static_cast<int> (pcl_round (acos (fabs (v21.dot (v31))) / pih * (binsize-1)));
th2 = static_cast<int> (pcl_round (acos (fabs (v23.dot (v31))) / pih * (binsize-1)));
th3 = static_cast<int> (pcl_round (acos (fabs (v23.dot (v21))) / pih * (binsize-1)));
th1 = static_cast<int> (pcl_round (std::acos (fabs (v21.dot (v31))) / pih * (binsize-1)));
th2 = static_cast<int> (pcl_round (std::acos (fabs (v23.dot (v31))) / pih * (binsize-1)));
th3 = static_cast<int> (pcl_round (std::acos (fabs (v23.dot (v21))) / pih * (binsize-1)));
if (th1 < 0 || th1 >= binsize)
{
nn_idx--;
Expand Down
4 changes: 2 additions & 2 deletions features/include/pcl/features/impl/our_cvfh.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,7 @@ pcl::OURCVFHEstimation<PointInT, PointNT, PointOutT>::extractEuclideanClustersSm
+ normals.points[seed_queue[sq_idx]].normal[1] * normals.points[nn_indices[j]].normal[1] + normals.points[seed_queue[sq_idx]].normal[2]
* normals.points[nn_indices[j]].normal[2];

if (fabs (acos (dot_p)) < eps_angle)
if (fabs (std::acos (dot_p)) < eps_angle)
{
processed[nn_indices[j]] = true;
seed_queue.push_back (nn_indices[j]);
Expand Down Expand Up @@ -641,7 +641,7 @@ pcl::OURCVFHEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloud
{
//decide if normal should be added
double dot_p = avg_normal.dot (normals_filtered_cloud->points[index].getNormalVector4fMap ());
if (fabs (acos (dot_p)) < (eps_angle_threshold_ * refine_clusters_))
if (fabs (std::acos (dot_p)) < (eps_angle_threshold_ * refine_clusters_))
{
clusters_[cluster_filtered_idx].indices.push_back (indices_from_nfc_to_indices[index]);
clusters_filtered[cluster_filtered_idx].indices.push_back (index);
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/ppf.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ pcl::PPFEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut
Eigen::Vector3f model_reference_point = input_->points[i].getVector3fMap (),
model_reference_normal = normals_->points[i].getNormalVector3fMap (),
model_point = input_->points[j].getVector3fMap ();
float rotation_angle = acosf (model_reference_normal.dot (Eigen::Vector3f::UnitX ()));
float rotation_angle = std::acos (model_reference_normal.dot (Eigen::Vector3f::UnitX ()));
bool parallel_to_x = (model_reference_normal.y() == 0.0f && model_reference_normal.z() == 0.0f);
Eigen::Vector3f rotation_axis = (parallel_to_x)?(Eigen::Vector3f::UnitY ()):(model_reference_normal.cross (Eigen::Vector3f::UnitX ()). normalized());
Eigen::AngleAxisf rotation_mg (rotation_angle, rotation_axis);
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/ppfrgb.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ pcl::PPFRGBEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudO
Eigen::Vector3f model_reference_point = input_->points[i].getVector3fMap (),
model_reference_normal = normals_->points[i].getNormalVector3fMap (),
model_point = input_->points[j].getVector3fMap ();
Eigen::AngleAxisf rotation_mg (acosf (model_reference_normal.dot (Eigen::Vector3f::UnitX ())),
Eigen::AngleAxisf rotation_mg (std::acos (model_reference_normal.dot (Eigen::Vector3f::UnitX ())),
model_reference_normal.cross (Eigen::Vector3f::UnitX ()).normalized ());
Eigen::Affine3f transform_mg = Eigen::Translation3f ( rotation_mg * ((-1) * model_reference_point)) * rotation_mg;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -388,8 +388,8 @@ bool RangeImageBorderExtractor::calculateMainPrincipalCurvature(int x, int y, in
//magnitude = -std::numeric_limits<float>::infinity ();
//return false;
//}
//float angle2 = acosf(surface_structure_[y*range_image_->width+x+1]->normal.dot(local_surface->normal)),
//angle1 = acosf(surface_structure_[y*range_image_->width+x-1]->normal.dot(local_surface->normal));
//float angle2 = std::acos(surface_structure_[y*range_image_->width+x+1]->normal.dot(local_surface->normal)),
//angle1 = std::acos(surface_structure_[y*range_image_->width+x-1]->normal.dot(local_surface->normal));
//magnitude = angle2-angle1;

return std::isfinite(magnitude);
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/rift.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ pcl::RIFTEstimation<PointInT, GradientT, PointOutT>::computeRIFT (
Eigen::Map<const Eigen::Vector3f> gradient_vector (& (gradient.points[indices[idx]].gradient[0]));

float gradient_magnitude = gradient_vector.norm ();
float gradient_angle_from_center = acosf (gradient_vector.dot ((point - p0).normalized ()) / gradient_magnitude);
float gradient_angle_from_center = std::acos (gradient_vector.dot ((point - p0).normalized ()) / gradient_magnitude);
if (!std::isfinite (gradient_angle_from_center))
gradient_angle_from_center = 0.0;

Expand Down
4 changes: 2 additions & 2 deletions features/include/pcl/features/impl/rsd.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ pcl::computeRSD (const pcl::PointCloud<PointInT> &surface, const pcl::PointCloud
normals.points[*i].normal[2] * normals.points[*begin].normal[2];
if (cosine > 1) cosine = 1;
if (cosine < -1) cosine = -1;
double angle = acos (cosine);
double angle = std::acos (cosine);
if (angle > M_PI/2) angle = M_PI - angle; /// \note: orientation is neglected!

// Compute point to point distance
Expand Down Expand Up @@ -185,7 +185,7 @@ pcl::computeRSD (const pcl::PointCloud<PointNT> &normals,
normals.points[*i].normal[2] * normals.points[*begin].normal[2];
if (cosine > 1) cosine = 1;
if (cosine < -1) cosine = -1;
double angle = acos (cosine);
double angle = std::acos (cosine);
if (angle > M_PI/2) angle = M_PI - angle; /// \note: orientation is neglected!

// Compute point to point distance
Expand Down
4 changes: 2 additions & 2 deletions features/include/pcl/features/impl/shot.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -359,7 +359,7 @@ pcl::SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::interpolateSing
if (inclinationCos > 1.0)
inclinationCos = 1.0;

double inclination = acos (inclinationCos);
double inclination = std::acos (inclinationCos);

assert (inclination >= 0.0 && inclination <= PST_RAD_180);

Expand Down Expand Up @@ -558,7 +558,7 @@ pcl::SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::interpolateDou
if (inclinationCos > 1.0)
inclinationCos = 1.0;

double inclination = acos (inclinationCos);
double inclination = std::acos (inclinationCos);

assert (inclination >= 0.0 && inclination <= PST_RAD_180);

Expand Down
8 changes: 4 additions & 4 deletions features/include/pcl/features/impl/spin_image.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -211,10 +211,10 @@ pcl::SpinImageEstimation<PointInT, PointNT, PointOutT>::computeSiForPoint (int i

if (is_angular_)
{
m_averAngles (alpha_bin, beta_bin) += (1-a) * (1-b) * acos (cos_between_normals);
m_averAngles (alpha_bin+1, beta_bin) += a * (1-b) * acos (cos_between_normals);
m_averAngles (alpha_bin, beta_bin+1) += (1-a) * b * acos (cos_between_normals);
m_averAngles (alpha_bin+1, beta_bin+1) += a * b * acos (cos_between_normals);
m_averAngles (alpha_bin, beta_bin) += (1-a) * (1-b) * std::acos (cos_between_normals);
m_averAngles (alpha_bin+1, beta_bin) += a * (1-b) * std::acos (cos_between_normals);
m_averAngles (alpha_bin, beta_bin+1) += (1-a) * b * std::acos (cos_between_normals);
m_averAngles (alpha_bin+1, beta_bin+1) += a * b * std::acos (cos_between_normals);
}
}

Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/usc.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,7 @@ pcl::UniqueShapeContext<PointInT, PointOutT, PointRFT>::computePointDescriptor (
Eigen::Vector3f no = neighbour - origin;
no.normalize ();
float theta = normal.dot (no);
theta = pcl::rad2deg (acosf (std::min (1.0f, std::max (-1.0f, theta))));
theta = pcl::rad2deg (std::acos (std::min (1.0f, std::max (-1.0f, theta))));

/// Bin (j, k, l)
size_t j = 0;
Expand Down
2 changes: 1 addition & 1 deletion features/src/pfh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ pcl::computePairFeatures (const Eigen::Vector4f &p1, const Eigen::Vector4f &n1,

// Make sure the same point is selected as 1 and 2 for each pair
float angle2 = n2_copy.dot (dp2p1) / f4;
if (acos (std::fabs (angle1)) > acos (std::fabs (angle2)))
if (std::acos (std::fabs (angle1)) > std::acos (std::fabs (angle2)))
{
// switch p1 and p2
n1_copy = n2;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ namespace pcl


float angle2 = dot(n2_copy, dp2p1) / f4;
if (acos (fabs (angle1)) > acos (fabs (angle2)))
if (std::acos (fabs (angle1)) > std::acos (fabs (angle2)))
{
// switch p1 and p2
n1_copy = n2;
Expand Down Expand Up @@ -179,7 +179,7 @@ namespace pcl
__device__ __host__ __forceinline__ void computeAlfaM(const float3& model_reference_point, const float3& model_reference_normal,
const float3& model_point, float& alpha_m)
{
float acos_value = acos (model_reference_normal.x);
float acos_value = std::acos (model_reference_normal.x);

//float3 cross_vector = cross(model_reference_normal, Eigen::Vector3f::UnitX);
float3 cross_vector = make_float3(0, model_reference_normal.z, - model_reference_normal.y);
Expand Down
2 changes: 1 addition & 1 deletion gpu/features/src/spinimages.cu
Original file line number Diff line number Diff line change
Expand Up @@ -227,7 +227,7 @@ namespace pcl

if (angular)
{
float anlge_betwwn_normals = acos(cos_between_normals);
float anlge_betwwn_normals = std::acos(cos_between_normals);
incAngle(alpha_bin, beta_bin, anlge_betwwn_normals * (1-a) * (1-b));
incAngle(alpha_bin+1, beta_bin, anlge_betwwn_normals * a * (1-b));
incAngle(alpha_bin, beta_bin+1, anlge_betwwn_normals * (1-a) * b );
Expand Down
2 changes: 1 addition & 1 deletion gpu/kinfu/src/kinfu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -589,7 +589,7 @@ namespace pcl
double c = (R.trace() - 1) * 0.5;
c = c > 1. ? 1. : c < -1. ? -1. : c;

double theta = acos(c);
double theta = std::acos(c);

if( s < 1e-5 )
{
Expand Down
2 changes: 1 addition & 1 deletion gpu/kinfu_large_scale/src/kinfu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -870,7 +870,7 @@ namespace pcl
double c = (R.trace() - 1) * 0.5;
c = c > 1. ? 1. : c < -1. ? -1. : c;

double theta = acos(c);
double theta = std::acos(c);

if( s < 1e-5 )
{
Expand Down
2 changes: 1 addition & 1 deletion keypoints/src/narf_keypoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,7 @@ namespace
Eigen::Vector3f rotated_direction = rotation*direction;
Eigen::Vector2f direction_vector (rotated_direction[0], rotated_direction[1]);
direction_vector.normalize ();
float angle = 0.5f*normAngle (2.0f*acosf (direction_vector[0]));
float angle = 0.5f*normAngle (2.0f*std::acos (direction_vector[0]));
return (angle);
}

Expand Down
Loading