#include <sequential_fitter.h>
Classes | |
struct | Parameter |
Public Member Functions | |
ON_NurbsSurface | compute (bool assemble=false) |
Compute point cloud and fit (multiple) models. | |
ON_NurbsSurface | compute_boundary (const ON_NurbsSurface &nurbs) |
Compute boundary points and fit (multiple) models (without interior points - minimal curvature surface) | |
ON_NurbsSurface | compute_interior (const ON_NurbsSurface &nurbs) |
Compute interior points and fit (multiple) models (without boundary points) | |
void | getBoundaryError (std::vector< double > &error) |
Get error of each boundary point (L2-norm of point to closest point on surface) and square-error. | |
void | getBoundaryNormals (std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &normals) |
get the normals to the boundary points given by setBoundary() | |
void | getBoundaryParams (std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > ¶ms) |
Get parameter of each boundary point. | |
void | getInteriorError (std::vector< double > &error) |
Get error of each interior point (L2-norm of point to closest point on surface) and square-error. | |
void | getInteriorNormals (std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &normal) |
get the normals to the interior points given by setInterior() | |
void | getInteriorParams (std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > ¶ms) |
Get parameter of each interior point. | |
ON_NurbsSurface | getNurbs () |
Get resulting NURBS surface. | |
ON_NurbsSurface | grow (float max_dist=1.0f, float max_angle=M_PI_4, unsigned min_length=0, unsigned max_length=10) |
Growing algorithm (TODO: under construction) | |
SequentialFitter (Parameter p=Parameter()) | |
void | setBoundary (pcl::PointIndices::Ptr &pcl_cloud_indices) |
Set boundary points of input point cloud. | |
void | setCorners (pcl::PointIndices::Ptr &corners, bool flip_on_demand=true) |
Set corner points of input point cloud. | |
void | setInputCloud (pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pcl_cloud) |
Set input point cloud. | |
void | setInterior (pcl::PointIndices::Ptr &pcl_cloud_indices) |
Set interior points of input point cloud. | |
void | setParams (const Parameter &p) |
void | setProjectionMatrix (const Eigen::Matrix4d &intrinsic, const Eigen::Matrix4d &extrinsic) |
Set camera- and world matrices, for projection and back-face detection. | |
Static Public Member Functions | |
static void | getClosestPointOnNurbs (ON_NurbsSurface nurbs, const Eigen::Vector3d &pt, Eigen::Vector2d ¶ms, int maxSteps=100, double accuracy=1e-4) |
Get the closest point on a NURBS from a point pt in parameter space. | |
static unsigned | PCL2ON (pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pcl_cloud, const std::vector< int > &indices, vector_vec3d &cloud) |
Convert point-cloud. | |
Private Member Functions | |
void | compute_boundary (FittingSurface *fitting) |
void | compute_interior (FittingSurface *fitting) |
void | compute_quadfit () |
void | compute_refinement (FittingSurface *fitting) |
bool | is_back_facing (const Eigen::Vector3d &v0, const Eigen::Vector3d &v1, const Eigen::Vector3d &v2, const Eigen::Vector3d &v3) |
Eigen::Vector2d | project (const Eigen::Vector3d &pt) |
Private Attributes | |
pcl::PointIndices::Ptr | m_boundary_indices |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr | m_cloud |
ON_3dPoint | m_corners [4] |
NurbsDataSurface | m_data |
Eigen::Matrix4d | m_extrinsic |
bool | m_have_cloud |
bool | m_have_corners |
pcl::PointIndices::Ptr | m_interior_indices |
Eigen::Matrix4d | m_intrinsic |
ON_NurbsSurface | m_nurbs |
Parameter | m_params |
int | m_surf_id |
Definition at line 63 of file sequential_fitter.h.
Definition at line 63 of file sequential_fitter.cpp.
ON_NurbsSurface SequentialFitter::compute | ( | bool | assemble = false | ) |
Compute point cloud and fit (multiple) models.
Definition at line 286 of file sequential_fitter.cpp.
void SequentialFitter::compute_boundary | ( | FittingSurface * | fitting | ) | [private] |
Definition at line 140 of file sequential_fitter.cpp.
ON_NurbsSurface SequentialFitter::compute_boundary | ( | const ON_NurbsSurface & | nurbs | ) |
Compute boundary points and fit (multiple) models (without interior points - minimal curvature surface)
Definition at line 381 of file sequential_fitter.cpp.
void SequentialFitter::compute_interior | ( | FittingSurface * | fitting | ) | [private] |
Definition at line 152 of file sequential_fitter.cpp.
ON_NurbsSurface SequentialFitter::compute_interior | ( | const ON_NurbsSurface & | nurbs | ) |
Compute interior points and fit (multiple) models (without boundary points)
Definition at line 404 of file sequential_fitter.cpp.
void SequentialFitter::compute_quadfit | ( | ) | [private] |
Definition at line 72 of file sequential_fitter.cpp.
void SequentialFitter::compute_refinement | ( | FittingSurface * | fitting | ) | [private] |
Definition at line 125 of file sequential_fitter.cpp.
void SequentialFitter::getBoundaryError | ( | std::vector< double > & | error | ) |
Get error of each boundary point (L2-norm of point to closest point on surface) and square-error.
Definition at line 432 of file sequential_fitter.cpp.
void SequentialFitter::getBoundaryNormals | ( | std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > & | normals | ) |
get the normals to the boundary points given by setBoundary()
Definition at line 456 of file sequential_fitter.cpp.
void SequentialFitter::getBoundaryParams | ( | std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > & | params | ) |
Get parameter of each boundary point.
Definition at line 444 of file sequential_fitter.cpp.
void SequentialFitter::getClosestPointOnNurbs | ( | ON_NurbsSurface | nurbs, |
const Eigen::Vector3d & | pt, | ||
Eigen::Vector2d & | params, | ||
int | maxSteps = 100 , |
||
double | accuracy = 1e-4 |
||
) | [static] |
Get the closest point on a NURBS from a point pt in parameter space.
[in] | nurbs | The NURBS surface |
[in] | pt | A point in 3D from which the closest point is calculated |
[out] | params | The closest point on the NURBS in parameter space |
[in] | maxSteps | Maximum iteration steps |
[in] | accuracy | Accuracy below which the iterations stop |
Definition at line 462 of file sequential_fitter.cpp.
void SequentialFitter::getInteriorError | ( | std::vector< double > & | error | ) |
Get error of each interior point (L2-norm of point to closest point on surface) and square-error.
Definition at line 426 of file sequential_fitter.cpp.
void SequentialFitter::getInteriorNormals | ( | std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > & | normal | ) |
get the normals to the interior points given by setInterior()
Definition at line 450 of file sequential_fitter.cpp.
void SequentialFitter::getInteriorParams | ( | std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > & | params | ) |
Get parameter of each interior point.
Definition at line 438 of file sequential_fitter.cpp.
ON_NurbsSurface pcl::on_nurbs::SequentialFitter::getNurbs | ( | ) | [inline] |
Get resulting NURBS surface.
Definition at line 171 of file sequential_fitter.h.
ON_NurbsSurface SequentialFitter::grow | ( | float | max_dist = 1.0f , |
float | max_angle = M_PI_4 , |
||
unsigned | min_length = 0 , |
||
unsigned | max_length = 10 |
||
) |
Growing algorithm (TODO: under construction)
Definition at line 477 of file sequential_fitter.cpp.
bool SequentialFitter::is_back_facing | ( | const Eigen::Vector3d & | v0, |
const Eigen::Vector3d & | v1, | ||
const Eigen::Vector3d & | v2, | ||
const Eigen::Vector3d & | v3 | ||
) | [private] |
Definition at line 182 of file sequential_fitter.cpp.
unsigned SequentialFitter::PCL2ON | ( | pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | pcl_cloud, |
const std::vector< int > & | indices, | ||
vector_vec3d & | cloud | ||
) | [static] |
Convert point-cloud.
Definition at line 611 of file sequential_fitter.cpp.
Eigen::Vector2d SequentialFitter::project | ( | const Eigen::Vector3d & | pt | ) | [private] |
Definition at line 168 of file sequential_fitter.cpp.
void SequentialFitter::setBoundary | ( | pcl::PointIndices::Ptr & | pcl_cloud_indices | ) |
Set boundary points of input point cloud.
Definition at line 210 of file sequential_fitter.cpp.
void SequentialFitter::setCorners | ( | pcl::PointIndices::Ptr & | corners, |
bool | flip_on_demand = true |
||
) |
Set corner points of input point cloud.
Definition at line 232 of file sequential_fitter.cpp.
void SequentialFitter::setInputCloud | ( | pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | pcl_cloud | ) |
void SequentialFitter::setInterior | ( | pcl::PointIndices::Ptr & | pcl_cloud_indices | ) |
Set interior points of input point cloud.
Definition at line 221 of file sequential_fitter.cpp.
void pcl::on_nurbs::SequentialFitter::setParams | ( | const Parameter & | p | ) | [inline] |
Definition at line 127 of file sequential_fitter.h.
void SequentialFitter::setProjectionMatrix | ( | const Eigen::Matrix4d & | intrinsic, |
const Eigen::Matrix4d & | extrinsic | ||
) |
Set camera- and world matrices, for projection and back-face detection.
[in] | intrinsic | The camera projection matrix. |
[in] | intrinsic | The world matrix. |
Definition at line 277 of file sequential_fitter.cpp.
Definition at line 94 of file sequential_fitter.h.
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pcl::on_nurbs::SequentialFitter::m_cloud [private] |
Definition at line 93 of file sequential_fitter.h.
ON_3dPoint pcl::on_nurbs::SequentialFitter::m_corners[4] [private] |
Definition at line 92 of file sequential_fitter.h.
Definition at line 89 of file sequential_fitter.h.
Eigen::Matrix4d pcl::on_nurbs::SequentialFitter::m_extrinsic [private] |
Definition at line 98 of file sequential_fitter.h.
bool pcl::on_nurbs::SequentialFitter::m_have_cloud [private] |
Definition at line 100 of file sequential_fitter.h.
bool pcl::on_nurbs::SequentialFitter::m_have_corners [private] |
Definition at line 101 of file sequential_fitter.h.
Definition at line 95 of file sequential_fitter.h.
Eigen::Matrix4d pcl::on_nurbs::SequentialFitter::m_intrinsic [private] |
Definition at line 97 of file sequential_fitter.h.
Definition at line 90 of file sequential_fitter.h.
Definition at line 87 of file sequential_fitter.h.
int pcl::on_nurbs::SequentialFitter::m_surf_id [private] |
Definition at line 103 of file sequential_fitter.h.