Class ExtrinsicLidarVehicleCalibration

Inheritance Relationships

Base Types

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
void computeRegionsCloud(const InputCloud_Message_T::ConstSharedPtr &ipCloudMsg, const std::vector<InputPointType> &iRegionMarkers, std::vector<pcl::PointCloud<InputPointType>::Ptr> &oRegionSeedPointsPtrs, pcl::PointCloud<RegionPointType>::Ptr &opRegionsCloud) const

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.

void onPointClicked(const geometry_msgs::msg::PointStamped::ConstSharedPtr &ipPointMsg)

Handle point clicked in RViz.

Parameters:

ipPointMsg[in] Pointer to message holding the clicked point.

bool onRequestAddRegionMarker(const std::shared_ptr<interf::srv::AddRegionMarker::Request> ipReq, std::shared_ptr<interf::srv::AddRegionMarker::Response> opRes)

handle service call to request addition of region marker.

Parameters:
  • ipReq[in] Request

  • opRes[out] Response

void onReferenceDataReceived(const InputCloud_Message_T::ConstSharedPtr &ipRefCloudMsg)

Method to receive reference data from vehicle model.

Parameters:

ipRefCloudMsg[in] Pointer to point cloud message from reference model.

void onSensorDataReceived(const InputCloud_Message_T::ConstSharedPtr &ipSrcCloudMsg)

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.