ICP  1.1.0
 Hosted by GitHub
Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
cl_algo::ICP::ICP< CR, CW > Class Template Reference

Interface class for the ICP pipeline. More...

#include <algorithms.hpp>

Inheritance diagram for cl_algo::ICP::ICP< CR, CW >:
Inheritance graph
[legend]
Collaboration diagram for cl_algo::ICP::ICP< CR, CW >:
Collaboration graph
[legend]

Public Member Functions

 ICP (clutils::CLEnv &_env, clutils::CLEnvInfo< 1 > _infoRBC, clutils::CLEnvInfo< 1 > _infoICP)
 Configures an OpenCL environment as specified by _info. More...
 
void init (unsigned int _m, unsigned int _nr, float _a=1e2f, float _c=1e-6f, unsigned int _max_iterations=40, double _angle_threshold=0.001, double _translation_threshold=0.01, Staging _staging=Staging::IO)
 Configures kernel execution parameters. More...
 
void buildRBC (const std::vector< cl::Event > *events=nullptr, cl::Event *event=nullptr)
 Builds the RBC data structure. More...
 
void run ()
 Executes the necessary kernels. More...
 
unsigned int getMaxIterations ()
 Gets the maximum number of iterations. More...
 
void setMaxIterations (unsigned int _max_iterations)
 Sets the maximum number of iterations. More...
 
double getAngleThreshold ()
 Gets the threshold for the change in angle. More...
 
void setAngleThreshold (double _angle_threshold)
 Sets the threshold for the change in angle. More...
 
double getTranslationThreshold ()
 Gets the threshold for the change in translation. More...
 
void setTranslationThreshold (double _translation_threshold)
 Sets the threshold for the change in translation. More...
 
template<typename period >
double run (clutils::GPUTimer< period > &timer)
 Executes the necessary kernels. More...
 

Public Attributes

unsigned int k
 Current iteration number. More...
 

Protected Member Functions

bool check ()
 Performs the convergence check. More...
 

Protected Attributes

unsigned int max_iterations
 Maximum number of iterations that a registration process is allowed to perform. More...
 
double angle_threshold
 Threshold for the change in angle (in degrees) in the transformation. More...
 
double translation_threshold
 Threshold for the change in translation (in mm) in the transformation. More...
 

Detailed Description

template<ICPStepConfigT CR, ICPStepConfigW CW>
class cl_algo::ICP::ICP< CR, CW >

Interface class for the ICP pipeline.

Performs the ICP algorithm and estimates the transformation between two point clouds.

Note
The implemented algorithms are described by Horn in Closed-Form Solution of Absolute Orientation Using Unit Quaternions and by Arun et al. in Least-Squares Fitting of Two 3-D Point Sets.
The class creates its own buffers. If you would like to provide your own buffers, call get to get references to the placeholders within the class and assign them to your buffers. You will have to do this strictly before the call to init. You can also call get (after the call to init) to get a reference to a buffer within the class and assign it to another kernel class instance further down in your task pipeline.

The following input/output OpenCL memory objects are created by a ICP<ICPStepConfigT::POWER_METHOD, ICPStepConfigW::WEIGHTED> instance:

Name Type Placement I/O Use Properties Size
H_IN_F Buffer Host I Staging CL_MEM_READ_WRITE \(m*sizeof\ (cl\_float8)\)
H_IN_M Buffer Host I Staging CL_MEM_READ_WRITE \(m*sizeof\ (cl\_float8)\)
H_IO_T Buffer Host IOStaging CL_MEM_READ_WRITE \(2*sizeof\ (cl\_float4)\)
D_IN_F Buffer Device I Processing CL_MEM_READ_ONLY \(m*sizeof\ (cl\_float8)\)
D_IN_M Buffer Device I Processing CL_MEM_READ_ONLY \(m*sizeof\ (cl\_float8)\)
D_IO_T Buffer Device IOProcessing CL_MEM_READ_WRITE \(2*sizeof\ (cl\_float4)\)
Template Parameters
CRconfigures the class with different methods of rotation computation.
CWconfigures the class for performing either regular or weighted computation.

Constructor & Destructor Documentation

template<ICPStepConfigT CR, ICPStepConfigW CW>
cl_algo::ICP::ICP< CR, CW >::ICP ( clutils::CLEnv &  _env,
clutils::CLEnvInfo< 1 >  _infoRBC,
clutils::CLEnvInfo< 1 >  _infoICP 
)

Configures an OpenCL environment as specified by _info.

Parameters
[in]_envopencl environment.
[in]_infoRBCopencl configuration for the RBC classes. It specifies the context, queue, etc, to be used.
[in]_infoICPopencl configuration for the ICP classes. It specifies the context, queue, etc, to be used.

Member Function Documentation

template<ICPStepConfigT CR, ICPStepConfigW CW>
void cl_algo::ICP::ICP< CR, CW >::buildRBC ( const std::vector< cl::Event > *  events = nullptr,
cl::Event *  event = nullptr 
)

Builds the RBC data structure.

Note
Call buildRBC after the D_IN_F buffer has been written, and before any calls to run (for each registration).
template<ICPStepConfigT CR, ICPStepConfigW CW>
bool cl_algo::ICP::ICP< CR, CW >::check ( )
inlineprotected

Performs the convergence check.

Checks the change in the transformation and the number of iterations.

Note
Call buildRBC after the D_IN_F buffer has been written, and before any calls to run (for each registration).
Returns
false for convergence, true otherwise.
template<ICPStepConfigT CR, ICPStepConfigW CW>
double cl_algo::ICP::ICP< CR, CW >::getAngleThreshold ( )

Gets the threshold for the change in angle.

Returns
The threshold for the change in angle (in degrees).
template<ICPStepConfigT CR, ICPStepConfigW CW>
unsigned int cl_algo::ICP::ICP< CR, CW >::getMaxIterations ( )

Gets the maximum number of iterations.

Returns
The maximum number of iterations.
template<ICPStepConfigT CR, ICPStepConfigW CW>
double cl_algo::ICP::ICP< CR, CW >::getTranslationThreshold ( )

Gets the threshold for the change in translation.

Returns
The threshold for the change in translation (in mm).
template<ICPStepConfigT CR, ICPStepConfigW CW>
void cl_algo::ICP::ICP< CR, CW >::init ( unsigned int  _m,
unsigned int  _nr,
float  _a = 1e2f,
float  _c = 1e-6f,
unsigned int  _max_iterations = 40,
double  _angle_threshold = 0.001,
double  _translation_threshold = 0.01,
Staging  _staging = Staging::IO 
)

Configures kernel execution parameters.

Sets up memory objects as necessary, and defines the kernel workspaces.

Note
If you have assigned a memory object to one member variable of the class before the call to init, then that memory will be maintained. Otherwise, a new memory object will be created.
Parameters
[in]_mnumber of points in the sets.
[in]_nrnumber of fixed set representatives.
[in]_afactor scaling the results of the distance calculations for the geometric \( x_g \) and photometric \( x_p \) dimensions of the \( x\epsilon\mathbb{R}^8 \) points. That is, \( \|x-x'\|_2^2= f_g(a)\|x_g-x'_g\|_2^2+f_p(a)\|x_p-x'_p\|_2^2 \). For more info, look at euclideanSquaredMetric8 in kernels/rbc_kernels.cl.
[in]_cscaling factor for dealing with floating point arithmetic issues when computing the S matrix.
[in]_max_iterationsmaximum number of iterations that a registration is allowed to perform.
[in]_angle_thresholdthreshold for the change in angle (in degrees) in the transformation.
[in]_translation_thresholdthreshold for the change in translation (in mm) in the transformation.
[in]_stagingflag to indicate whether or not to instantiate the staging buffers.
template<ICPStepConfigT CR, ICPStepConfigW CW>
void cl_algo::ICP::ICP< CR, CW >::run ( )

Executes the necessary kernels.

Executes the iterative ICP algorithm and estimates the relative transformation between the two associated point clouds.

Note
The function call is blocking, so it doesn't need to offer an event. It also doesn't accept events, since it's meant to be called after buildRBC which is the one that will wait on the events.
template<ICPStepConfigT CR, ICPStepConfigW CW>
template<typename period >
double cl_algo::ICP::ICP< CR, CW >::run ( clutils::GPUTimer< period > &  timer)
inline

Executes the necessary kernels.

This run instance is used for profiling.

Parameters
[in]timerGPUTimer that does the profiling of the kernel executions.
Returns
Τhe total execution time measured by the timer.
template<ICPStepConfigT CR, ICPStepConfigW CW>
void cl_algo::ICP::ICP< CR, CW >::setAngleThreshold ( double  _angle_threshold)

Sets the threshold for the change in angle.

Updates the parameter for the threshold for the change in angle (in degrees) in the transformation.

Parameters
[in]_angle_thresholdthreshold for the change in angle (in degrees).
template<ICPStepConfigT CR, ICPStepConfigW CW>
void cl_algo::ICP::ICP< CR, CW >::setMaxIterations ( unsigned int  _max_iterations)

Sets the maximum number of iterations.

Updates the parameter for the maximum number of iterations.

Parameters
[in]_max_iterationsmaximum number of iterations.
template<ICPStepConfigT CR, ICPStepConfigW CW>
void cl_algo::ICP::ICP< CR, CW >::setTranslationThreshold ( double  _translation_threshold)

Sets the threshold for the change in translation.

Updates the parameter for the threshold for the change in translation (in mm) in the transformation.

Parameters
[in]_translation_thresholdthreshold for the change in translation (in mm).

Member Data Documentation

template<ICPStepConfigT CR, ICPStepConfigW CW>
double cl_algo::ICP::ICP< CR, CW >::angle_threshold
protected

Threshold for the change in angle (in degrees) in the transformation.

template<ICPStepConfigT CR, ICPStepConfigW CW>
unsigned int cl_algo::ICP::ICP< CR, CW >::k

Current iteration number.

Gets reset in buildRBC with every registration.

template<ICPStepConfigT CR, ICPStepConfigW CW>
unsigned int cl_algo::ICP::ICP< CR, CW >::max_iterations
protected

Maximum number of iterations that a registration process is allowed to perform.

template<ICPStepConfigT CR, ICPStepConfigW CW>
double cl_algo::ICP::ICP< CR, CW >::translation_threshold
protected

Threshold for the change in translation (in mm) in the transformation.


The documentation for this class was generated from the following files: