Template Class Extrinsic3d3dCalibrationBase

Inheritance Relationships

Base Type

Class Documentation

template<class SrcDataProcessorT, class RefDataProcessorT>
class Extrinsic3d3dCalibrationBase : public multisensor_calibration::ExtrinsicCalibrationBase<SrcDataProcessorT, RefDataProcessorT>

Base class for all extrinsic 3D-3D calibration routines.

This subclasses multisensor_calibration::ExtrinsicCalibrationBase.

Template Parameters:
  • SrcDataProcessorT – Class to process data from source sensor.

  • RefDataProcessorT – Class to process data from reference sensor.

Public Functions

Extrinsic3d3dCalibrationBase() = delete

Default constructor is deleted.

Extrinsic3d3dCalibrationBase(ECalibrationType type)

Initialization constructor.

Parameters:

type[in] Type of calibration

virtual ~Extrinsic3d3dCalibrationBase()

Destructor.

Protected Types

typedef message_filters::sync_policies::ApproximateTime<InputCloud_Message_T, InputCloud_Message_T> CloudCloudApproxSync
typedef message_filters::sync_policies::ExactTime<InputCloud_Message_T, InputCloud_Message_T> CloudCloudExactSync

Protected Functions

template<typename PointT>
lib3d::Extrinsics computeExtrinsicsFromPointCorrespondences(const typename pcl::PointCloud<PointT>::Ptr pSrcCloud, const typename pcl::PointCloud<PointT>::Ptr pRefCloud, const pcl::Correspondences &pointCorrespondences)

Compute extrinsic pose from 3D correspondences.

Template Parameters:

PointT – Point type of input point clouds.

Parameters:
  • pSrcCloud[in] Point cloud for which the rigid transformation is to be computed.

  • pRefCloud[in] Point cloud used as reference.

  • pointCorrespondences[in] List of correspondences between point clouds.

Returns:

Extrinsic sensor pose from pSrcCloud to pRefCloud.

template<typename PointT>
double runIcp(const typename pcl::PointCloud<PointT>::Ptr pSrcCloud, const typename pcl::PointCloud<PointT>::Ptr pRefCloud, const small_gicp::RegistrationSetting::RegistrationType &icpVariant = small_gicp::RegistrationSetting::GICP, const double &maxCorrespondenceDistance = 0.1, const double &rotationToleranceDegree = 0.5, const double &translationTolerance = 0.001, const double &downsamplingResolution = 0.01)

Method to run ICP between fused clouds of the calibration targets from source LiDAR and of the calibration targets from reference LiDAR. The ICP is initialized with the pose guess stored in sensorExtrinsics_.

The transformation estimated by the ICP is only stored, if the RMSE after the ICP is smaller than before.

Template Parameters:

PointT – Point type of input point clouds.

Parameters:
  • pSrcCloud[in] Point cloud which is to be registered with ICP.

  • pRefCloud[in] Point cloud against which SpSrcCloud is to be registered.

  • icpVariant[in] ICP variant to use (Default: GICP)

  • maxCorrespondenceDistance[in] Maximium distance between the point correspondences

  • rotationToleranceDegree[in] Accepted rotation tolerance in degrees

  • translationTolerance[in] Accepted translation tolerance

  • downsamplingResolution[in] Resolution that is used for downsampling prior to ICP

Returns:

Returns the minimum of RMSE before and after the ICP.

Protected Attributes

rclcpp::Logger logger_

Logger object of node.