Template Class CalibrationTargetSacModel

Inheritance Relationships

Base Type

  • public pcl::SampleConsensusModelPerpendicularPlane< PointT >

Class Documentation

template<typename PointT>
class CalibrationTargetSacModel : public pcl::SampleConsensusModelPerpendicularPlane<PointT>

PCL sample consensus model of the calibration target to be used within the RANSAC algorithm of the PCL to detect and fit the calibration target within in point cloud.

The model coefficients are defined as:

  • normal_x : the X coordinate of the target’s normal vector (normalized)

  • normal_y : the Y coordinate of the target’s normal vector (normalized)

  • normal_z : the Z coordinate of the target’s normal vector (normalized)

  • d : the fourth Hessian component of the board’s equation

  • up_x : the X coordinate of the target’s up vector (normalized)

  • up_y : the Y coordinate of the target’s up vector (normalized)

  • up_z : the Z coordinate of the target’s up vector (normalized)

  • center_x : the X coordinate of the target’s center

  • center_y : the Y coordinate of the target’s center

  • center_z : the Z coordinate of the target’s center

  • width : the width of the target

  • height : the height of the target

When used within the RANSAC algorithm of the PCL, in each iteration the up vector, as well as the center point will be varied according to the values set in setRotationVariance() and setTranslationVariance() in order to find the best fitting pose. With incrementalPoseGuessUpdate() the model can be set to keep track of the number of inliers and update the poseGuess_ each time the number of inlier increases.

Public Types

using PointCloud = typename pcl::SampleConsensusModel<PointT>::PointCloud
using PointCloudPtr = typename pcl::SampleConsensusModel<PointT>::PointCloudPtr
using PointCloudConstPtr = typename pcl::SampleConsensusModel<PointT>::PointCloudConstPtr
using Ptr = pcl::shared_ptr<CalibrationTargetSacModel<PointT>>
using ConstPtr = pcl::shared_ptr<const CalibrationTargetSacModel<PointT>>

Public Functions

CalibrationTargetSacModel(const CalibrationTarget &target, const PointCloudConstPtr &cloud, bool random = false)

Constructor for CalibrationTargetSacModel.

Parameters:
  • target[in] object of the calibration target.

  • cloud[in] the input point cloud dataset.

  • random[in] if true set the random seed to the current time, else set to 12345 (default: false)

CalibrationTargetSacModel(const CalibrationTarget &target, const PointCloudConstPtr &cloud, const std::vector<int> &indices, bool random = false)

Constructor for CalibrationTargetSacModel.

Parameters:
  • target[in] object of the calibration target.

  • cloud[in] the input point cloud dataset

  • indices[in] a vector of point indices to be used from cloud

  • random[in] if true set the random seed to the current time, else set to 12345 (default: false)

~CalibrationTargetSacModel()

Empty destructor.

void clearIndices()

Clear list of indices.

void setPoseGuess(const Eigen::Vector3f &iCenter, const Eigen::Vector3f &iUp, const Eigen::Vector3f &iNormal)

Method to set guess of board pose as seen from the sensors coordinate system.

Parameters:
  • iCenter[in] Translational vector as seen from the reference coordinate system.

  • iUp[in] Up vector as seen from the reference coordinate system.

  • iNormal[in] Normal vector as seen from the reference coordinate system and pointing into direction of the origin of the reference coordinate system.

void setIncrementalPoseGuessUpdate(const bool iValue)

Method to set incremental pose guess.

If set to true, this will allow the model to keep track of the number of inliers and update the poseGuess_ each time the number of inlier increases.

void setRotationVariance(const double iValue)

Set the variance up to which different rotations of the target pose (to the left and right of the up-vector) should be testet.

Parameters:

iValue – Value in degrees, in the range of [0,180]

void setTranslationVariance(const double iValue)

Set the shift value (with respect to the pose guess) with which different positions of the target should be testet.

Parameters:

iValue – Value in meters.

bool computeModelCoefficients(const std::vector<int> &samples, Eigen::VectorXf &model_coefficients) const override

Check whether the given index samples can form a valid plane model, compute the model coefficients from these samples and store them internally in model_coefficients_. The plane coefficients are: a, b, c, d (ax+by+cz+d=0)

Parameters:
  • samples[in] the point indices found as possible good candidates for creating a valid model

  • model_coefficients[out] the resultant model coefficients

void selectWithinDistance(const Eigen::VectorXf &model_coefficients, const double threshold, std::vector<int> &inliers) override

Select all the points which respect the given model coefficients as inliers.

Parameters:
  • model_coefficients[in] the coefficients of a plane model that we need to compute distances to

  • threshold[in] a maximum admissible distance threshold for determining the inliers from the outliers

  • inliers[out] the resultant model inliers

std::size_t countWithinDistance(const Eigen::VectorXf &model_coefficients, const double threshold) const override

Count all the points which respect the given model coefficients as inliers.

Parameters:
  • model_coefficients[in] the coefficients of a model that we need to compute distances to

  • threshold[in] maximum admissible distance threshold for determining the inliers from the outliers

Returns:

the resultant number of inliers

void optimizeModelCoefficients(const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients) const

Optimize the coefficients with the help of ICP and the full input cloud and return them to the user.

Note

: these are the coefficients of the plane model after refinement (e.g. after SVD)

Parameters:
  • model_coefficients[in] the initial guess for the model coefficients

  • optimized_coefficients[out] the resultant recomputed coefficients after non-linear optimization

void optimizeModelCoefficients(const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients) const override

Optimize the coefficients with the help of ICP and the given inlier set and return them to the user.

Note

: these are the coefficients of the plane model after refinement (e.g. after SVD)

Parameters:
  • inliers[in] the data inliers found as supporting the model

  • model_coefficients[in] the initial guess for the model coefficients

  • optimized_coefficients[out] the resultant recomputed coefficients after non-linear optimization

void setIcpCorrespondenceDistance(const double &ratio)

Set maximum distance for ICP to search for point correspondences. Given as ratio with respect to shorter side of calibration target.

void setIcpRotationTolerance(const double &tolerance_deg)

Rotation tolerance for convergence check. Given in degrees.

void setIcpTranslationTolerance(const double &tolerance)

Translation tolerance for convergence check. Given in unit of LiDAR point cloud, typically meters.

void setIcpVariant(const small_gicp::RegistrationSetting::RegistrationType &type)

Set the ICP variant used for the optimization of coefficients.

void setInputCloud(const PointCloudConstPtr &cloud) override

Provide a pointer to the input dataset. This will first clear the list of indices.

Parameters:

cloud[in] the const boost shared pointer to a PointCloud message

Protected Functions

virtual void init(const CalibrationTarget &target)

Initialize model.

bool isModelValid(const Eigen::VectorXf &model_coefficients) const override

Check whether a model is valid given the user constraints.

Parameters:

model_coefficients[in] the set of model coefficients