Class ExtrinsicCameraCameraCalibration

Inheritance Relationships

Base Types

Class Documentation

class ExtrinsicCameraCameraCalibration : public multisensor_calibration::Extrinsic2d2dCalibrationBase<CameraDataProcessor, CameraDataProcessor>, public rclcpp::Node

Node to perform extrinsic lidar-lidar calibration.

This subclasses multisensor_calibration::Extrinsic3d3dCalibrationBase.

Public Functions

ExtrinsicCameraCameraCalibration(const std::string &nodeName, const rclcpp::NodeOptions &options = rclcpp::NodeOptions())
ExtrinsicCameraCameraCalibration(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())
~ExtrinsicCameraCameraCalibration() override
void onSensorDataReceived(const InputImage_Message_T::ConstSharedPtr &ipSrcImgMsg, const InputImage_Message_T::ConstSharedPtr &ipRefImgMsg)

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:
  • ipSrcImgMsg[in] Pointer to point cloud message from source sensor that is to be calibrated.

  • ipRefImgMsg[in] Pointer to point cloud message from reference sensor against which the source sensor is to be calibrated.

bool initializeCameraIntrinsics(CameraDataProcessor *iopCamProcessor, sensor_msgs::msg::CameraInfo &cameraInfo, EImageState imageState, std::string cameraInfoTopic)

Initialize camera intrinsics from camera info topics.

Parameters:

iopCamProcessor[inout] Pointer to camera data processor to which the intrinsics are to be set.

Returns:

True, if successful. False otherwise.

void onSrcCameraInfoReceived(const sensor_msgs::msg::CameraInfo::SharedPtr pCamInfo)

Handle reception of camera info message.

void onRefCameraInfoReceived(const sensor_msgs::msg::CameraInfo::SharedPtr pCamInfo)
bool onRequestCameraIntrinsics(const std::shared_ptr<interf::srv::CameraIntrinsics::Request> ipReq, std::shared_ptr<interf::srv::CameraIntrinsics::Response> opRes)

Handle service call to get camera intrinsics.

Parameters:
  • ipReq[in] Request, UNUSED.

  • opRes[out] Response.

Protected Types

typedef message_filters::sync_policies::ApproximateTime<InputImage_Message_T, InputImage_Message_T> ImageImageApproxSync
typedef message_filters::sync_policies::ExactTime<InputImage_Message_T, InputImage_Message_T> ImageImageExactSync