Class LidarDataProcessor
Defined in File LidarDataProcessor.h
Inheritance Relationships
Base Type
public multisensor_calibration::DataProcessor3d
(Class DataProcessor3d)
Class Documentation
-
class LidarDataProcessor : public multisensor_calibration::DataProcessor3d
Class to processing the point cloud data from the LiDAR sensor and to detect the calibration target within this data.
Public Functions
-
LidarDataProcessor() = delete
Default constructor is deleted.
-
LidarDataProcessor(const std::string &iLoggerName, const std::string &iSensorName, const fs::path &iCalibTargetFilePath)
Initialization constructor, providing the node name, the sensor name as well as the path to the calibration target configuration file.
-
virtual ~LidarDataProcessor()
Destructor.
-
virtual EProcessingResult processData(const pcl::PointCloud<InputPointType> &iPointCloud, const EProcessingLevel &iProcLevel) override
Callback method to process the point cloud data.
In this, first, the point cloud is transformed into a reference coordinate system if according transformation is set with setDataTransform(). After that a preprocessing filter is applied if it has been set using setPreprocFilter(). After the point cloud has been transformed and filtered, the point cloud normals are estimated and the region growing is applied. If the processing level is set to PREVIEW, only the cluster candidates are computed and published. If the processing level is set to TARGET_DETECTION, the target pose is detected and fit into the cloud using RANSAC as described above.
- Parameters:
iPointCloud – Point cloud as pcl::PointCloud
iProcLevel – [in] Level at which the data is to be processed, i.e. PREVIEW or TARGET_DETECTION
- Returns:
Result of the processing.
-
void setPreprocFilter(const pcl::Filter<InputPointType>::Ptr &pFilter)
Method to set pointer to filter used for pre-processing.
- Parameters:
pFilter – [in] Pointer to filter object that is to be set. If null, the preprocessing filter is deactivated.
-
void setParameters(const LidarTargetDetectionParameters &iParams)
Set parameters for target detection in lidar data.
Public Static Functions
-
static bool extractPlaneFromPointCloud(const pcl::PointCloud<InputPointType>::Ptr &ipInputCloud, const Eigen::Vector3f &iNormalVec, const double &iAngleTolerance, pcl::PointCloud<InputPointType>::Ptr &opOutputCloud)
Method to extract a planar point cloud from input cloud.
This uses the RANSAC based segmentation of the PCL to find a plane which has a normal vector that parallel to given vector within a given tolerance.
- Parameters:
ipInputCloud – [in] Pointer to input cloud.
iNormalVec – [in] Desired normal direction of the plane which is to be found.
iAngleTolerance – [in] Angular tolerance between given and predicted normal vector in degrees.
opOutputCloud – [out] Pointer to output cloud. If the pointer is a nullptr, a new pointcloud will be instantiated.
-
static bool extractPlaneFromPointCloud(const pcl::PointCloud<InputPointType>::Ptr &ipInputCloud, const tf2::Vector3 &iNormalVec, const double &iAngleTolerance, pcl::PointCloud<InputPointType>::Ptr &opOutputCloud)
Overloaded function.
-
LidarDataProcessor() = delete