Class ExtrinsicLidarVehicleCalibration
Defined in File ExtrinsicLidarVehicleCalibration.h
Inheritance Relationships
Base Types
public multisensor_calibration::Extrinsic3d3dCalibrationBase< LidarDataProcessor, LidarDataProcessor >(Template Class Extrinsic3d3dCalibrationBase)public rclcpp::Node
Class Documentation
-
class ExtrinsicLidarVehicleCalibration : public multisensor_calibration::Extrinsic3d3dCalibrationBase<LidarDataProcessor, LidarDataProcessor>, public rclcpp::Node
Node to perform extrinsic lidar-vehicle calibration.
This subclasses multisensor_calibration::Extrinsic3d3dCalibrationBase.
Public Functions
-
ExtrinsicLidarVehicleCalibration(const std::string &nodeName, const rclcpp::NodeOptions &options = rclcpp::NodeOptions())
-
ExtrinsicLidarVehicleCalibration(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())
-
~ExtrinsicLidarVehicleCalibration() override = default
Compute planar regions in cloud data based on selected region markers.
- Parameters:
ipCloudMsg – [in] Pointer to cloud message from which the regions cloud is to be computed.
iRegionMarkers – [in] List of markers for which regions should be computed.
oRegionSeedPointsPtrs – [out] List of point clouds holding the seed points for the selected regions.
opRegionsCloud – [out] Pointer to cloud which is to hold the regions.
-
void doCoarseCalibration()
Do coarse calibration based on the seed points of the regions of interest.
This will estimate a rigid transformation between the selected seed points.
Handle point clicked in RViz.
- Parameters:
ipPointMsg – [in] Pointer to message holding the clicked point.
handle service call to request addition of region marker.
- Parameters:
ipReq – [in] Request
opRes – [out] Response
Method to receive reference data from vehicle model.
- Parameters:
ipRefCloudMsg – [in] Pointer to point cloud message from reference model.
Method to receive sensor data from source LiDAR which is to be calibrated with respect to the vehicle.
- Parameters:
ipSrcCloudMsg – [in] Pointer to point cloud message from source sensor that is to be calibrated.
-
ExtrinsicLidarVehicleCalibration(const std::string &nodeName, const rclcpp::NodeOptions &options = rclcpp::NodeOptions())