Template Class Extrinsic2d3dCalibrationBase
Defined in File Extrinsic2d3dCalibrationBase.h
Inheritance Relationships
Base Type
public multisensor_calibration::ExtrinsicCalibrationBase< SrcDataProcessorT, RefDataProcessorT >
(Template Class ExtrinsicCalibrationBase)
Class Documentation
-
template<class SrcDataProcessorT, class RefDataProcessorT>
class Extrinsic2d3dCalibrationBase : public multisensor_calibration::ExtrinsicCalibrationBase<SrcDataProcessorT, RefDataProcessorT> Base class for all extrinsic 2D-3D calibration routines.
This subclasses multisensor_calibration::ExtrinsicCalibrationBase.
- Template Parameters:
SrcDataProcessorT – Class to process data from source sensor.
RefDataProcessorT – Class to process data from reference sensor.
Public Functions
-
Extrinsic2d3dCalibrationBase() = delete
Default constructor is deleted.
-
Extrinsic2d3dCalibrationBase(ECalibrationType type)
Initialization constructor.
- Parameters:
type – [in] Type of calibration
-
virtual ~Extrinsic2d3dCalibrationBase()
Destructor.
Protected Types
-
typedef message_filters::sync_policies::ApproximateTime<InputImage_Message_T, InputCloud_Message_T> ImgCloudApproxSync
-
typedef message_filters::sync_policies::ExactTime<InputImage_Message_T, InputCloud_Message_T> ImgCloudExactSync
Protected Functions
-
void calculateAdditionalStereoCalibrations()
-
std::pair<double, int> runPnp(const std::vector<cv::Point2f>::const_iterator &iCamObsStart, const std::vector<cv::Point2f>::const_iterator &iCamObsEnd, const std::vector<cv::Point3f>::const_iterator &iLidarObsStart, const std::vector<cv::Point3f>::const_iterator &iLidarObsEnd, const lib3d::Intrinsics &iCameraIntrinsics, const float &iInlierMaxRpjError, const bool &iUsePoseGuess, lib3d::Extrinsics &oNewSensorExtrinsics, const std::vector<uint> &iIndices = {}) const
Method to do PnP calibration between observation of 2d corner points from camera sensor and 3d corner point from the lidar sensor.
- Parameters:
iCamObsStart – [in] Begin iterator of the corner observations from the camera image.
iCamObsEnd – [in] End iterator of the corner observations from the camera image.
iLidarObsStart – [in] Begin iterator of the corner observations from the lidar image.
iLidarObsEnd – [in] End iterator of the corner observations from the lidar image.
iCameraIntrinsics – [in] Intrinsic parameters of the camera.
iInlierMaxRpjError – [in] Maximum reprojection error to be accepted for inliers.
iUsePoseGuess – [in] Flag to use pose guess from back of sensorExtrinsics_.
oNewSensorExtrinsics – [out] Estimated sensor extrinsics.
iIndices – [in] Optional list of indices within list of observation to consider for calibration. Leave empty if full range of passed observations is to be used.
- Returns:
Pair made up of mean reprojection error and number of inliers from the RANSAC detection.
-
bool initializeCameraIntrinsics(CameraDataProcessor *iopCamProcessor)
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.
-
virtual bool initializeSubscribers(rclcpp::Node *ipNode) override
Method to initialize subscribers. This overrides the method of the parent class. In this, the parent method is also called.
- Returns:
True, if all settings are valid. False, otherwise.
Handle reception of camera info message of left camera.
Handle reception of camera info message of right camera. Only used when isStereoCamera_ == true.
-
virtual bool saveCalibrationSettingsToWorkspace() override
Method to save calibration specific settings to the workspace. This overrides the method of the parent class.
- Returns:
True, if all settings are valid. False, otherwise.
-
virtual void setupLaunchParameters(rclcpp::Node *ipNode) const override
Setup launch parameters.
The implementation within this class hold launch parameters that are common to all calibration nodes.
- Parameters:
ipNode – [in] Pointer to node.
-
virtual bool readLaunchParameters(const rclcpp::Node *ipNode) override
Method to read launch parameters. This overrides the method of the parent class. In this, the parent method is also called.
- Parameters:
iNh – [in] Object of node handle
- Returns:
True if successful. False, otherwise (e.g. if sanity check fails)
Protected Attributes
-
std::string &cameraSensorName_ = ExtrinsicCalibrationBase<SrcDataProcessorT, RefDataProcessorT>::srcSensorName_
Name of the camera sensor as given in the URDF model. This is a reference to ExtrinsicCalibrationBase::srcSensorName_
-
std::string &cameraImageTopic_ = ExtrinsicCalibrationBase<SrcDataProcessorT, RefDataProcessorT>::srcTopicName_
Topic name of the camera images which are to be used for extrinsic calibration. This is a reference to ExtrinsicCalibrationBase::srcTopicName_
-
std::string cameraInfoTopic_
Topic name of the camera info messages. If not explicitly set, this is constructed from cameraImageTopic_.
-
std::string &imageFrameId_ = ExtrinsicCalibrationBase<SrcDataProcessorT, RefDataProcessorT>::srcFrameId_
Frame id of image received by #imageSubsc_ This is a reference to ExtrinsicCalibrationBase::srcFrameId_
-
EImageState imageState_
State of image received on the subscribed topic.
-
bool isStereoCamera_
True if camera that is calibrated is a stereo.
-
std::string rightCameraSensorName_
Name of the right camera sensor in case of a stereo camera.
-
std::string rightCameraInfoTopic_
Topic name of the right camera info messages in case of a stereo camera.
-
std::string rightImageFrameId_
Frame id of the right image in case of a stereo camera. This is retrieved from the camera info message of the right camera.
-
std::string rectSuffix_
Suffix of the right sensor name as well as the frame id for the rectified images. If the imageState_ input images is DISTORTED or UNDISTORTED, this is added to the rectified frame id. If the imageState_ is STEREO_RECTIFIED this is removed from the frame id.
-
rclcpp::Subscription<sensor_msgs::msg::CameraInfo>::SharedPtr pLeftCamInfoSubsc_
Subscriber to camera info messages of left camera.
-
sensor_msgs::msg::CameraInfo leftCameraInfo_
Camera info data of left camera.
-
rclcpp::Subscription<sensor_msgs::msg::CameraInfo>::SharedPtr pRightCamInfoSubsc_
Subscriber to camera info messages of right camera. Only used when isStereoCamera_ == true.
-
sensor_msgs::msg::CameraInfo rightCameraInfo_
Camera info data of right camera. Only used when isStereoCamera_ == true.