Class ExtrinsicLidarLidarCalibration
Defined in File ExtrinsicLidarLidarCalibration.h
Inheritance Relationships
Base Types
public multisensor_calibration::Extrinsic3d3dCalibrationBase< LidarDataProcessor, LidarDataProcessor >(Template Class Extrinsic3d3dCalibrationBase)public rclcpp::Node
Class Documentation
-
class ExtrinsicLidarLidarCalibration : public multisensor_calibration::Extrinsic3d3dCalibrationBase<LidarDataProcessor, LidarDataProcessor>, public rclcpp::Node
Node to perform extrinsic lidar-lidar calibration.
This subclasses multisensor_calibration::Extrinsic3d3dCalibrationBase.
Public Functions
-
ExtrinsicLidarLidarCalibration(const std::string &nodeName, const rclcpp::NodeOptions &options = rclcpp::NodeOptions())
-
ExtrinsicLidarLidarCalibration(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())
-
~ExtrinsicLidarLidarCalibration() override
-
void calibrateLastObservation()
Run the extrinsic calibration based on the last observation of the calibration target.
This will remove observations without correspondence and estimate a rigid transformation based on the detected marker corners.
Method to receive synchronized sensor data, i.e. LiDAR point clouds from the source and the reference sensor.
This calls the processing of the data data processors, i.e. detect the calibration target or possible candidates, depending on wether the command to capture the target is triggered or not. When the target is detected a calibration with the last observation is performed. In this, the observations might be rejected if the error of the calibration is too large.
- Parameters:
ipSrcCloudMsg – [in] Pointer to point cloud message from source sensor that is to be calibrated.
ipRefCloudMsg – [in] Pointer to point cloud message from reference sensor against which the source sensor is to be calibrated.
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
-
ExtrinsicLidarLidarCalibration(const std::string &nodeName, const rclcpp::NodeOptions &options = rclcpp::NodeOptions())