OCLSLAM  0.1.0
 Hosted by GitHub
Public Member Functions | Public Attributes | List of all members
OCLSLAM< CR, CW > Class Template Reference

Interface class for the SLAM pipeline. More...

#include <ocl_processing.hpp>

Public Member Functions

 OCLSLAM (Kinect *kinect, octomap::OcTree &map)
 Constructor. More...
 
 ~OCLSLAM ()
 Destructor. More...
 
void init ()
 Initializes the SLAM pipeline. More...
 
void registerPointCloud ()
 Registers a point cloud. More...
 
void write (std::string filename=std::string("map.ot"))
 Stores an occupancy map on disk. More...
 
void writeBinary (std::string filename=std::string("map.bt"))
 Stores an binary map on disk. More...
 
void display ()
 Prints on the console results about the current registration and localization. More...
 
bool getSLAMStatus ()
 Gets the status of the automated SLAM process. More...
 
void setSLAMStatus (bool flag)
 Sets the status of the automated SLAM process. More...
 
void toggleSLAMStatus ()
 Toggles the status of the automated SLAM process. More...
 
bool getGFRGBStatus ()
 Gets the status of the RGB Guided Filter. More...
 
void setGFRGBStatus (bool flag)
 Sets the status of the RGB Guided Filter. More...
 
void toggleGFRGBStatus ()
 Toggles the status of the RGB Guided Filter. More...
 
bool getGFDStatus ()
 Gets the status of the Depth Guided Filter. More...
 
void setGFDStatus (bool flag)
 Sets the status of the Depth Guided Filter. More...
 
void toggleGFDStatus ()
 Toggles the status of the Depth Guided Filter. More...
 
int getRGBNormalization ()
 Gets the status of the RGB normalization. More...
 
void setRGBNormalization (int flag)
 Sets the status of the RGB normalization. More...
 
void toggleRGBNormalization ()
 Toggles the status of the RGB normalization. More...
 
int getGFRGBRadius ()
 Gets the window radius \(r\) for the guided filter performed on the RGB frame. More...
 
void setGFRGBRadius (int radius)
 Sets the window radius \(r\) for the guided filter performed on the RGB frame. More...
 
float getGFRGBEps ()
 Gets the variability threshold \(\epsilon\) for the guided filter performed on the RGB frame. More...
 
void setGFRGBEps (float eps)
 Sets the variability threshold \(\epsilon\) for the guided filter performed on the RGB frame. More...
 
int getGFDRadius ()
 Gets the window radius \(r\) for the guided filter performed on the Depth frame. More...
 
void setGFDRadius (int radius)
 Sets the window radius \(r\) for the guided filter performed on the Depth frame. More...
 
float getGFDEps ()
 Gets the variability threshold \(\epsilon\) for the guided filter performed on the Depth frame. More...
 
void setGFDEps (float eps)
 Sets the variability threshold \(\epsilon\) for the guided filter performed on the Depth frame. More...
 
float getGFDScaling ()
 Gets the scaling applied to the depth frame for processing with the guided filter. More...
 
void setGFDScaling (float scaling)
 Sets the scaling applied to the depth frame for processing with the guided filter. More...
 
float getSensorFocalLength ()
 Gets the sensor's focal length. More...
 
void setSensorFocalLength (float f)
 Sets the sensor's focal length. More...
 
float getRBCAlpha ()
 Gets the parameter \( \alpha \) used in the distance function for the RBC data structure. More...
 
void setRBCAlpha (float _a)
 Sets the parameter \( \alpha \) used in the distance function for the RBC data structure. More...
 
float getICPSScaling ()
 Gets the scaling applying to the deviations when computing matrix S in the ICP algorithm, for managing floating point arithmetic issues. More...
 
void setICPSScaling (float _c)
 Sets the scaling applying to the deviations when computing matrix S in the ICP algorithm, for managing floating point arithmetic issues. More...
 
unsigned int getICPMaxIterations ()
 Gets the maximum number of iterations considered for an ICP registration. More...
 
void setICPMaxIterations (unsigned int maxIter)
 Sets the maximum number of iterations considered for an ICP registration. More...
 
double getICPAngleThreshold ()
 Gets the angle threshold (in degrees) for the convergence check of the ICP. More...
 
void setICPAngleThreshold (double at)
 Sets the angle threshold (in degrees) for the convergence check of the ICP. More...
 
double getICPTranslationThreshold ()
 Gets the translation threshold (in mm) for the convergence check of the ICP. More...
 
void setICPTranslationThreshold (double tt)
 Sets the translation threshold (in mm) for the convergence check of the ICP. More...
 

Public Attributes

std::function< void()> slam
 Performs the SLAM process. More...
 
volatile int timeStep
 
Eigen::Matrix3f R_g
 
Eigen::Quaternionf q_g
 
Eigen::Vector3f t_g
 
cl_float s_g
 

Detailed Description

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

Interface class for the SLAM pipeline.

Retrieves data, registers point clouds, and builds a map.

Note
In order to handle memory consumption, there is a limit on the number of point clouds displayed on the screen. When the limit is reached though, the SLAM process keeps running on the background and the map gets updated as normal.
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<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
OCLSLAM< CR, CW >::OCLSLAM ( Kinect kinect,
octomap::OcTree &  map 
)

Constructor.

Initializes the OpenCL environment, the OpenGL buffers, and the classes for the SLAM pipeline.

Parameters
[in]kinectinitialized Kinect device.
[in]mapOctoMap structure for building the map.
template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
OCLSLAM< CR, CW >::~OCLSLAM ( )

Destructor.

Member Function Documentation

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::display ( )

Prints on the console results about the current registration and localization.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
float OCLSLAM< CR, CW >::getGFDEps ( )
inline

Gets the variability threshold \(\epsilon\) for the guided filter performed on the Depth frame.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
int OCLSLAM< CR, CW >::getGFDRadius ( )
inline

Gets the window radius \(r\) for the guided filter performed on the Depth frame.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
float OCLSLAM< CR, CW >::getGFDScaling ( )
inline

Gets the scaling applied to the depth frame for processing with the guided filter.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
bool OCLSLAM< CR, CW >::getGFDStatus ( )
inline

Gets the status of the Depth Guided Filter.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
float OCLSLAM< CR, CW >::getGFRGBEps ( )
inline

Gets the variability threshold \(\epsilon\) for the guided filter performed on the RGB frame.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
int OCLSLAM< CR, CW >::getGFRGBRadius ( )
inline

Gets the window radius \(r\) for the guided filter performed on the RGB frame.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
bool OCLSLAM< CR, CW >::getGFRGBStatus ( )
inline

Gets the status of the RGB Guided Filter.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
double OCLSLAM< CR, CW >::getICPAngleThreshold ( )
inline

Gets the angle threshold (in degrees) for the convergence check of the ICP.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
unsigned int OCLSLAM< CR, CW >::getICPMaxIterations ( )
inline

Gets the maximum number of iterations considered for an ICP registration.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
float OCLSLAM< CR, CW >::getICPSScaling ( )
inline

Gets the scaling applying to the deviations when computing matrix S in the ICP algorithm, for managing floating point arithmetic issues.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
double OCLSLAM< CR, CW >::getICPTranslationThreshold ( )
inline

Gets the translation threshold (in mm) for the convergence check of the ICP.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
float OCLSLAM< CR, CW >::getRBCAlpha ( )
inline

Gets the parameter \( \alpha \) used in the distance function for the RBC data structure.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
int OCLSLAM< CR, CW >::getRGBNormalization ( )
inline

Gets the status of the RGB normalization.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
float OCLSLAM< CR, CW >::getSensorFocalLength ( )
inline

Gets the sensor's focal length.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
bool OCLSLAM< CR, CW >::getSLAMStatus ( )
inline

Gets the status of the automated SLAM process.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::init ( )

Initializes the SLAM pipeline.

It sets up the first point cloud. After that, registerPointCloud can be called to perform the registration process.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::registerPointCloud ( )

Registers a point cloud.

Runs ICP on the current point cloud, delivers the result to OpenGL for visualization, and to OctoMap, in order to update the map.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::setGFDEps ( float  eps)
inline

Sets the variability threshold \(\epsilon\) for the guided filter performed on the Depth frame.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::setGFDRadius ( int  radius)
inline

Sets the window radius \(r\) for the guided filter performed on the Depth frame.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::setGFDScaling ( float  scaling)
inline

Sets the scaling applied to the depth frame for processing with the guided filter.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::setGFDStatus ( bool  flag)
inline

Sets the status of the Depth Guided Filter.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::setGFRGBEps ( float  eps)
inline

Sets the variability threshold \(\epsilon\) for the guided filter performed on the RGB frame.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::setGFRGBRadius ( int  radius)
inline

Sets the window radius \(r\) for the guided filter performed on the RGB frame.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::setGFRGBStatus ( bool  flag)
inline

Sets the status of the RGB Guided Filter.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::setICPAngleThreshold ( double  at)
inline

Sets the angle threshold (in degrees) for the convergence check of the ICP.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::setICPMaxIterations ( unsigned int  maxIter)
inline

Sets the maximum number of iterations considered for an ICP registration.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::setICPSScaling ( float  _c)
inline

Sets the scaling applying to the deviations when computing matrix S in the ICP algorithm, for managing floating point arithmetic issues.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::setICPTranslationThreshold ( double  tt)
inline

Sets the translation threshold (in mm) for the convergence check of the ICP.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::setRBCAlpha ( float  _a)
inline

Sets the parameter \( \alpha \) used in the distance function for the RBC data structure.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::setRGBNormalization ( int  flag)
inline

Sets the status of the RGB normalization.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::setSensorFocalLength ( float  f)
inline

Sets the sensor's focal length.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::setSLAMStatus ( bool  flag)

Sets the status of the automated SLAM process.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::toggleGFDStatus ( )
inline

Toggles the status of the Depth Guided Filter.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::toggleGFRGBStatus ( )
inline

Toggles the status of the RGB Guided Filter.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::toggleRGBNormalization ( )
inline

Toggles the status of the RGB normalization.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::toggleSLAMStatus ( )

Toggles the status of the automated SLAM process.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::write ( std::string  filename = std::string ("map.ot"))

Stores an occupancy map on disk.

Parameters
[in]filenamename for the map file [.ot].
template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
void OCLSLAM< CR, CW >::writeBinary ( std::string  filename = std::string ("map.bt"))

Stores an binary map on disk.

Parameters
[in]filenamename for the map file [.bt].

Member Data Documentation

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
Eigen::Quaternionf OCLSLAM< CR, CW >::q_g

Represents the orietation with respect to the global coordinate frame, given in quaternion representation, \( \dot{q}_g = \left[ \begin{matrix} q_x & q_y & q_z & q_w \end{matrix} \right]^T \).

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
Eigen::Matrix3f OCLSLAM< CR, CW >::R_g

Represents the orietation with respect to the global coordinate frame, given in rotation matrix representation, \( R_g \).

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
cl_float OCLSLAM< CR, CW >::s_g

Represents the scale of the current point cloud with respect to the first one, given as a scalar, \( s_g \). It's used when transforming the current point cloud before mapping.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
std::function<void ()> OCLSLAM< CR, CW >::slam

Performs the SLAM process.

Initially, it points to init for registering the first point cloud, and after that it gets assigned with a function that runs repeatedly registerPointCloud.

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
Eigen::Vector3f OCLSLAM< CR, CW >::t_g

Represents the translation (in mm) with respect to the global coordinate frame, given as a vector in 3-D, \( t_g \).

template<ICP::ICPStepConfigT CR, ICP::ICPStepConfigW CW>
volatile int OCLSLAM< CR, CW >::timeStep

Counts the discrete time steps, as in the number of point clouds registered.


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