Skip to content
Open
Show file tree
Hide file tree
Changes from 2 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: 4 additions & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
@@ -1,7 +1,11 @@
---
Checks: >
-*,
bugprone-assert-side-effect,
bugprone-copy-constructor-init,
bugprone-dangling-handle,
bugprone-forward-declaration-namespace,
bugprone-inaccurate-erase,
bugprone-macro-parentheses,
bugprone-unhandled-self-assignment,
bugprone-unused-raii,
Expand Down
6 changes: 3 additions & 3 deletions examples/surface/example_nurbs_fitting_closed_curve.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,9 @@ VisualizeCurve (ON_NurbsCurve &curve, double r, double g, double b, bool show_cp
curve.GetCV (i, cp);

pcl::PointXYZ p;
p.x = float (cp.x);
p.y = float (cp.y);
p.z = float (cp.z);
p.x = static_cast<float>(cp.x);
p.y = static_cast<float>(cp.y);
p.z = static_cast<float>(cp.z);
cps->push_back (p);
}
pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> handler (cps, 255 * r, 255 * g, 255 * b);
Expand Down
6 changes: 3 additions & 3 deletions examples/surface/example_nurbs_fitting_closed_curve3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,9 +41,9 @@ VisualizeCurve (ON_NurbsCurve &curve, double r, double g, double b, bool show_cp
curve.GetCV (i, cp);

pcl::PointXYZ p;
p.x = float (cp.x);
p.y = float (cp.y);
p.z = float (cp.z);
p.x = static_cast<float>(cp.x);
p.y = static_cast<float>(cp.y);
p.z = static_cast<float>(cp.z);
cps->push_back (p);
}
pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> handler (cps, 255 * r, 255 * g, 255 * b);
Expand Down
6 changes: 3 additions & 3 deletions examples/surface/example_nurbs_fitting_curve2d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,9 +41,9 @@ VisualizeCurve (ON_NurbsCurve &curve, double r, double g, double b, bool show_cp
curve.GetCV (i, cp);

pcl::PointXYZ p;
p.x = float (cp.x);
p.y = float (cp.y);
p.z = float (cp.z);
p.x = static_cast<float>(cp.x);
p.y = static_cast<float>(cp.y);
p.z = static_cast<float>(cp.z);
cps->push_back (p);
}
pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> handler (cps, 255 * r, 255 * g, 255 * b);
Expand Down
6 changes: 3 additions & 3 deletions examples/surface/example_nurbs_fitting_surface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -202,9 +202,9 @@ visualizeCurve (ON_NurbsCurve &curve, ON_NurbsSurface &surface, pcl::visualizati
double pnt[3];
surface.Evaluate (p1.x, p1.y, 0, 3, pnt);
pcl::PointXYZRGB p2;
p2.x = float (pnt[0]);
p2.y = float (pnt[1]);
p2.z = float (pnt[2]);
p2.x = static_cast<float>(pnt[0]);
p2.y = static_cast<float>(pnt[1]);
p2.z = static_cast<float>(pnt[2]);

p2.r = 255;
p2.g = 0;
Expand Down
4 changes: 2 additions & 2 deletions examples/surface/example_nurbs_viewer_surface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ main (int argc, char *argv[])
return -1;
}

const ON_NurbsSurface& on_surf = *(ON_NurbsSurface*)on_object;
const ON_NurbsSurface& on_surf = *dynamic_cast<const ON_NurbsSurface*>(on_object);

pcl::PolygonMesh mesh;
std::string mesh_id = "mesh_nurbs";
Expand All @@ -68,7 +68,7 @@ main (int argc, char *argv[])
return -1;
}

const ON_NurbsCurve& on_curv = *(ON_NurbsCurve*)on_object;
const ON_NurbsCurve& on_curv = *dynamic_cast<const ON_NurbsCurve*>(on_object);

pcl::on_nurbs::Triangulation::convertTrimmedSurface2PolygonMesh (on_surf, on_curv, mesh,
mesh_resolution);
Expand Down
12 changes: 6 additions & 6 deletions examples/surface/test_nurbs_fitting_surface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,15 +12,15 @@ CreateCylinderPoints (pcl::PointCloud<Point>::Ptr cloud, pcl::on_nurbs::vector_v
{
for (unsigned i = 0; i < npoints; i++)
{
double da = alpha * double (rand ()) / RAND_MAX;
double dh = h * (double (rand ()) / RAND_MAX - 0.5);
double da = alpha * static_cast<double>(rand ()) / RAND_MAX;
double dh = h * (static_cast<double>(rand ()) / RAND_MAX - 0.5);

Point p;
p.x = float (r * std::cos (da));
p.y = float (r * sin (da));
p.z = float (dh);
p.x = static_cast<float>(r * std::cos (da));
p.y = static_cast<float>(r * sin (da));
p.z = static_cast<float>(dh);

data.push_back (Eigen::Vector3d (p.x, p.y, p.z));
data.emplace_back(p.x, p.y, p.z);
cloud->push_back (p);
}
}
Expand Down
16 changes: 8 additions & 8 deletions surface/src/on_nurbs/closing_boundary.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,7 @@ ClosingBoundary::sampleUniform (ON_NurbsSurface *nurbs, vector_vec3d &point_list
{
params (0) = minU + (maxU - minU) * ds * i;
nurbs->Evaluate (params (0), params (1), 0, 3, points);
point_list.push_back (Eigen::Vector3d (points[0], points[1], points[2]));
point_list.emplace_back(points[0], points[1], points[2]);
}
}
}
Expand All @@ -262,10 +262,10 @@ ClosingBoundary::sampleRandom (ON_NurbsSurface *nurbs, vector_vec3d &point_list,

for (unsigned i = 0; i < samples; i++)
{
params (0) = minU + (maxU - minU) * (double (rand ()) / RAND_MAX);
params (1) = minV + (maxV - minV) * (double (rand ()) / RAND_MAX);
params (0) = minU + (maxU - minU) * (static_cast<double>(rand ()) / RAND_MAX);
params (1) = minV + (maxV - minV) * (static_cast<double>(rand ()) / RAND_MAX);
nurbs->Evaluate (params (0), params (1), 0, 3, points);
point_list.push_back (Eigen::Vector3d (points[0], points[1], points[2]));
point_list.emplace_back(points[0], points[1], points[2]);
}
}

Expand All @@ -290,7 +290,7 @@ ClosingBoundary::sampleFromBoundary (ON_NurbsSurface *nurbs, vector_vec3d &point
{
params (1) = minV + (maxV - minV) * ds * i;
nurbs->Evaluate (params (0), params (1), 0, 3, points);
point_list.push_back (Eigen::Vector3d (points[0], points[1], points[2]));
point_list.emplace_back(points[0], points[1], points[2]);
param_list.push_back (params);
}

Expand All @@ -300,7 +300,7 @@ ClosingBoundary::sampleFromBoundary (ON_NurbsSurface *nurbs, vector_vec3d &point
{
params (1) = minV + (maxV - minV) * ds * i;
nurbs->Evaluate (params (0), params (1), 0, 3, points);
point_list.push_back (Eigen::Vector3d (points[0], points[1], points[2]));
point_list.emplace_back(points[0], points[1], points[2]);
param_list.push_back (params);
}

Expand All @@ -310,7 +310,7 @@ ClosingBoundary::sampleFromBoundary (ON_NurbsSurface *nurbs, vector_vec3d &point
{
params (0) = minU + (maxU - minU) * ds * i;
nurbs->Evaluate (params (0), params (1), 0, 3, points);
point_list.push_back (Eigen::Vector3d (points[0], points[1], points[2]));
point_list.emplace_back(points[0], points[1], points[2]);
param_list.push_back (params);
}

Expand All @@ -320,7 +320,7 @@ ClosingBoundary::sampleFromBoundary (ON_NurbsSurface *nurbs, vector_vec3d &point
{
params (0) = minU + (maxU - minU) * ds * i;
nurbs->Evaluate (params (0), params (1), 0, 3, points);
point_list.push_back (Eigen::Vector3d (points[0], points[1], points[2]));
point_list.emplace_back(points[0], points[1], points[2]);
param_list.push_back (params);
}
}
Expand Down
12 changes: 6 additions & 6 deletions surface/src/on_nurbs/fitting_curve_2d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ int
FittingCurve2d::findElement (double xi, const std::vector<double> &elements)
{
if (xi >= elements.back ())
return (int (elements.size ()) - 2);
return (static_cast<int>(elements.size ()) - 2);

for (std::size_t i = 0; i < elements.size () - 1; i++)
{
Expand Down Expand Up @@ -120,7 +120,7 @@ FittingCurve2d::assemble (const Parameter &parameter)
{
int ncp = m_nurbs.m_cv_count;
int nCageReg = m_nurbs.m_cv_count - 2;
int nInt = int (m_data->interior.size ());
int nInt = static_cast<int>(m_data->interior.size ());

double wInt = 1.0;
if (!m_data->interior_weight.empty ())
Expand Down Expand Up @@ -290,7 +290,7 @@ FittingCurve2d::initNurbsPCA (int order, NurbsDataCurve2d *data, int ncps)
if (ncps < order)
ncps = order;

unsigned s = static_cast<unsigned> (data->interior.size ());
auto s = static_cast<unsigned> (data->interior.size ());
data->interior_param.clear ();

NurbsTools::pca (data->interior, mean, eigenvectors, eigenvalues);
Expand Down Expand Up @@ -399,7 +399,7 @@ FittingCurve2d::getElementVector (const ON_NurbsCurve &nurbs)
void
FittingCurve2d::assembleInterior (double wInt, double rScale, unsigned &row)
{
int nInt = int (m_data->interior.size ());
int nInt = static_cast<int>(m_data->interior.size ());
m_data->interior_error.clear ();
m_data->interior_normals.clear ();
m_data->interior_line_start.clear ();
Expand All @@ -413,7 +413,7 @@ FittingCurve2d::assembleInterior (double wInt, double rScale, unsigned &row)
double param;
Eigen::Vector2d pt, t;
double error;
if (p < int (m_data->interior_param.size ()))
if (p < static_cast<int>(m_data->interior_param.size ()))
{
param = findClosestElementMidPoint (m_nurbs, pcp, m_data->interior_param[p]);
param = inverseMapping (m_nurbs, pcp, param, error, pt, t, rScale, in_max_steps, in_accuracy, m_quiet);
Expand All @@ -428,7 +428,7 @@ FittingCurve2d::assembleInterior (double wInt, double rScale, unsigned &row)

m_data->interior_error.push_back (error);

if (p < int (m_data->interior_weight.size ()))
if (p < static_cast<int>(m_data->interior_weight.size ()))
wInt = m_data->interior_weight[p];

m_data->interior_line_start.push_back (pcp);
Expand Down
26 changes: 13 additions & 13 deletions surface/src/on_nurbs/fitting_curve_2d_apdm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ int
FittingCurve2dAPDM::findElement (double xi, const std::vector<double> &elements)
{
if (xi >= elements.back ())
return (int (elements.size ()) - 2);
return (static_cast<int>(elements.size ()) - 2);

for (std::size_t i = 0; i < elements.size () - 1; i++)
{
Expand Down Expand Up @@ -148,8 +148,8 @@ FittingCurve2dAPDM::assemble (const Parameter &parameter)
int cp_red = m_nurbs.m_order - 2;
int ncp = m_nurbs.m_cv_count - 2 * cp_red;
int nCageReg = m_nurbs.m_cv_count - 2 * cp_red;
int nInt = int (m_data->interior.size ());
int nClosestP = int (elements.size ()) * cp_res;
int nInt = static_cast<int>(m_data->interior.size ());
int nClosestP = static_cast<int>(elements.size ()) * cp_res;

double wInt = 1.0;
if (!m_data->interior_weight.empty ())
Expand Down Expand Up @@ -330,8 +330,8 @@ FittingCurve2dAPDM::removeCPsOnLine (const ON_NurbsCurve &nurbs, double min_curv
}

int order = nurbs.Order ();
ON_NurbsCurve nurbs_opt = ON_NurbsCurve (2, false, order, int (cps.size ()) + 2 * cp_red);
nurbs_opt.MakePeriodicUniformKnotVector (1.0 / (double (cps.size ())));
ON_NurbsCurve nurbs_opt = ON_NurbsCurve (2, false, order, static_cast<int>(cps.size ()) + 2 * cp_red);
nurbs_opt.MakePeriodicUniformKnotVector (1.0 / (static_cast<double>(cps.size ())));
nurbs_opt.m_knot[cp_red] = 0.0;
nurbs_opt.m_knot[nurbs_opt.m_knot_capacity - cp_red - 1] = 1.0;

Expand Down Expand Up @@ -428,7 +428,7 @@ FittingCurve2dAPDM::addCageRegularisation (double weight, unsigned &row, const s
{
int i = j % ncp;

if (i >= int (m_data->closest_points_error.size () - 1))
if (i >= static_cast<int>(m_data->closest_points_error.size () - 1))
{
printf ("[FittingCurve2dAPDM::addCageRegularisation] Warning, index for closest_points_error out of bounds\n");
m_solver.f (row, 0, 0.0);
Expand Down Expand Up @@ -512,15 +512,15 @@ FittingCurve2dAPDM::initCPsNurbsCurve2D (int order, const vector_vec2d &cps)
return nurbs;
}

int ncps = int (cps.size ()) + 2 * cp_red; // +2*cp_red for smoothness and +1 for closing
int ncps = static_cast<int>(cps.size ()) + 2 * cp_red; // +2*cp_red for smoothness and +1 for closing
nurbs = ON_NurbsCurve (2, false, order, ncps);
nurbs.MakePeriodicUniformKnotVector (1.0 / (ncps - order + 1));

for (std::size_t j = 0; j < cps.size (); j++)
nurbs.SetCV (cp_red + j, ON_3dPoint (cps[j] (0), cps[j] (1), 0.0));

// close nurbs
nurbs.SetCV (cp_red + int (cps.size ()), ON_3dPoint (cps[0] (0), cps[0] (1), 0.0));
nurbs.SetCV (cp_red + static_cast<int>(cps.size ()), ON_3dPoint (cps[0] (0), cps[0] (1), 0.0));

// make smooth at closing point
for (int j = 0; j < cp_red; j++)
Expand All @@ -544,7 +544,7 @@ FittingCurve2dAPDM::initNurbsCurve2D (int order, const vector_vec2d &data, int n

Eigen::Vector2d mean = NurbsTools::computeMean (data);

unsigned s = unsigned (data.size ());
auto s = static_cast<unsigned>(data.size ());

double r (0.0);
for (unsigned i = 0; i < s; i++)
Expand Down Expand Up @@ -641,7 +641,7 @@ FittingCurve2dAPDM::getElementVector (const ON_NurbsCurve &nurbs)
void
FittingCurve2dAPDM::assembleInterior (double wInt, double sigma2, double rScale, unsigned &row)
{
int nInt = int (m_data->interior.size ());
int nInt = static_cast<int>(m_data->interior.size ());
bool wFunction (true);
double ds = 1.0 / (2.0 * sigma2);
m_data->interior_error.clear ();
Expand All @@ -657,7 +657,7 @@ FittingCurve2dAPDM::assembleInterior (double wInt, double sigma2, double rScale,
double param;
Eigen::Vector2d pt, t;
double error;
if (p < int (m_data->interior_param.size ()))
if (p < static_cast<int>(m_data->interior_param.size ()))
{
param = findClosestElementMidPoint (m_nurbs, pcp, m_data->interior_param[p]);
param = inverseMapping (m_nurbs, pcp, param, error, pt, t, rScale, in_max_steps, in_accuracy, m_quiet);
Expand All @@ -677,10 +677,10 @@ FittingCurve2dAPDM::assembleInterior (double wInt, double sigma2, double rScale,
Eigen::Vector3d b (t (0), t (1), 0.0);
Eigen::Vector3d z = a.cross (b);

if (p < int (m_data->interior_weight.size ()))
if (p < static_cast<int>(m_data->interior_weight.size ()))
wInt = m_data->interior_weight[p];

if (p < int (m_data->interior_weight_function.size ()))
if (p < static_cast<int>(m_data->interior_weight_function.size ()))
wFunction = m_data->interior_weight_function[p];

double w (wInt);
Expand Down
12 changes: 6 additions & 6 deletions surface/src/on_nurbs/fitting_curve_2d_asdm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,12 +59,12 @@ FittingCurve2dASDM::assemble (const FittingCurve2dAPDM::Parameter &parameter)
int cp_red = m_nurbs.m_order - 2;
int ncp = m_nurbs.m_cv_count - 2 * cp_red;
int nCageReg = m_nurbs.m_cv_count - 2 * cp_red;
int nInt = int (m_data->interior.size ());
int nInt = static_cast<int>(m_data->interior.size ());
// int nCommon = m_data->common.size();
// int nClosestP = parameter.closest_point_resolution;

std::vector<double> elements = getElementVector (m_nurbs);
int nClosestP = int (elements.size ());
int nClosestP = static_cast<int>(elements.size ());

double wInt = 1.0;
if (!m_data->interior_weight.empty ())
Expand Down Expand Up @@ -213,7 +213,7 @@ FittingCurve2dASDM::addCageRegularisation (double weight, unsigned &row, const s
{
int i = j % ncp;

if (i >= int (m_data->closest_points_error.size () - 1))
if (i >= static_cast<int>(m_data->closest_points_error.size () - 1))
{
printf ("[FittingCurve2dASDM::addCageRegularisation] Warning, index for closest_points_error out of bounds\n");
}
Expand Down Expand Up @@ -259,7 +259,7 @@ FittingCurve2dASDM::addCageRegularisation (double weight, unsigned &row, const s
void
FittingCurve2dASDM::assembleInterior (double wInt, double sigma2, double rScale, unsigned &row)
{
unsigned nInt = unsigned (m_data->interior.size ());
auto nInt = static_cast<unsigned>(m_data->interior.size ());
bool wFunction (true);
double ds = 1.0 / (2.0 * sigma2);
m_data->interior_line_start.clear ();
Expand Down Expand Up @@ -410,7 +410,7 @@ FittingCurve2dASDM::assembleClosestPoints (const std::vector<double> &elements,
for (std::size_t i = 0; i < elements.size (); i++)
{

int j = (i + 1) % int (elements.size ());
int j = (i + 1) % static_cast<int>(elements.size ());

double dxi = elements[j] - elements[i];
double xi = elements[i] + 0.5 * dxi;
Expand Down Expand Up @@ -444,7 +444,7 @@ FittingCurve2dASDM::assembleClosestPoints (const std::vector<double> &elements,
if (m_data->closest_rho.size () != elements.size ())
{
printf ("[FittingCurve2dASDM::assembleClosestPoints] ERROR: size does not match %d %d\n",
int (m_data->closest_rho.size ()), int (elements.size ()));
static_cast<int>(m_data->closest_rho.size ()), static_cast<int>(elements.size ()));
}
else
{
Expand Down
Loading