Template Class ExtrinsicCalibrationBase

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Derived Types

Class Documentation

template<class SrcDataProcessorT, class RefDataProcessorT>
class ExtrinsicCalibrationBase : public multisensor_calibration::CalibrationBase

Base class of all extrinsic calibration nodes.

Template Parameters:
  • SrcDataProcessorT – Class to process data from source sensor.

  • RefDataProcessorT – Class to process data from reference sensor.

Subclassed by multisensor_calibration::Extrinsic2d3dCalibrationBase< CameraDataProcessor, LidarDataProcessor >, multisensor_calibration::Extrinsic2d3dCalibrationBase< CameraDataProcessor, ReferenceDataProcessor3d >, multisensor_calibration::Extrinsic3d3dCalibrationBase< LidarDataProcessor, LidarDataProcessor >, multisensor_calibration::Extrinsic3d3dCalibrationBase< LidarDataProcessor, ReferenceDataProcessor3d >, multisensor_calibration::Extrinsic2d3dCalibrationBase< SrcDataProcessorT, RefDataProcessorT >, multisensor_calibration::Extrinsic3d3dCalibrationBase< SrcDataProcessorT, RefDataProcessorT >

Public Functions

ExtrinsicCalibrationBase() = delete

Default constructor is deleted.

ExtrinsicCalibrationBase(ECalibrationType type)

Initialization constructor.

[in] type type of calibration.

virtual ~ExtrinsicCalibrationBase()

Destructor.

Protected Functions

virtual bool initializePublishers(rclcpp::Node *ipNode) override

Initialize publishers. Purely virtual.

Parameters:

ipNode[inout] Pointer to node.

Returns:

True, if successful. False otherwise.

virtual bool initializeServices(rclcpp::Node *ipNode) override

Method to initialize services. This overrides the CalibrationBase::initializeServices. In this, the method from the base class is also called.

Parameters:

ipNode[inout] Pointer to node.

Returns:

True, if successful. False otherwise.

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

Handle call requesting calibration meta data.

Parameters:
  • ipReq[in] Request

  • opRes[out] Response.

virtual bool onRequestRemoveObservation(const std::shared_ptr<interf::srv::RemoveLastObservation::Request> ipReq, std::shared_ptr<interf::srv::RemoveLastObservation::Response> oRes) = 0

Handle call requesting removal of last observation. This is a pure virtual definition and needs to be implemented in a subclass.

Parameters:
  • ipReq[in] Request, with flag to capture calibration target

  • opRes[out] Response, empty.

virtual bool onRequestSensorExtrinsics(const std::shared_ptr<interf::srv::SensorExtrinsics::Request> ipReq, std::shared_ptr<interf::srv::SensorExtrinsics::Response> oRes)

Handling call requesting sensor extrinsics.

Parameters:
  • ipReq[in] Request, empty.

  • oRes[out] Response.

void publishCalibrationResult(const lib3d::Extrinsics &iSensorExtrinsics) const

Publish given sensor extrinsics as calibration result.

Parameters:

iSensorExtrinsics[in] Sensor extrinsics to publish.

void publishLastCalibrationResult() const

Publish las sensor extrinsics in sensorExtrinsics_ as calibration result.

virtual bool saveCalibrationSettingsToWorkspace() override

Save calibration settings to setting.ini inside calibration workspace.

This overrides CalibrationBase::saveCalibrationSettingsToWorkspace. In this, the method of the parent class is also called.

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

Read launch parameters.

This overrides CalibrationBase::readLaunchParameters. In this, the method of the parent class is also called.

The implementation within this class hold launch parameters that are common to all calibration nodes, e.g. robot_ws_path, target_config_file.

Parameters:

ipNode[in] Pointer to node.

Returns:

True if successful. False, otherwise (e.g. if sanity check fails)

template<typename Id_T, typename Obs_T, typename Cloud_T, typename Pose_T>
void removeObservationsFromIteration(const uint &iCalibrationItr, std::set<Id_T> &ioIds, std::vector<Obs_T> &ioObs, std::vector<Cloud_T> &ioClouds, std::vector<Pose_T> &ioPoses) const

Method to remove all observations that were captured during the given calibration iteration.

Template Parameters:
  • Id_T – Type of IDs.

  • Obs_T – Type of Observations.

  • Cloud_T – Type of target clouds.

  • Pose_T – Type of target board poses.

Parameters:
  • iCalibrationItr[in] Calibration iteration.

  • ioIds[inout] List of IDs.

  • ioObs[inout] List of Observations.

  • ioClouds[inout] List of target clouds.

  • ioPoses[inout] List of target board clouds.

template<typename Id_T, typename Obs_T>
void removeCornerObservationsWithoutCorrespondence(const std::set<Id_T> &iReferenceIds, std::set<Id_T> &ioSrcIds, std::vector<Obs_T> &ioSrcObs) const

Method to remove observations from ta given source list that do not have corresponding observations with the same ID in the reference list.

Template Parameters:
  • Id_T – Type of IDs

  • Obs_T – Type of Observations

Parameters:
  • iReferenceIds[in] Reference list of IDs to check against.

  • ioSrcIds[inout] List of IDs which are to be checked against the reference list.

  • ioSrcObs[inout] List of Observations.

virtual void reset() override

Reset calibration.

This overrides CalibrationBase::reset. In this, the method of the parent class is also called.

virtual bool saveCalibration() override

Save calibration.

This overrides CalibrationBase::saveCalibration. In this, the method of the parent class is also called.

bool saveCalibrationToUrdfModel()

Method to save the calibration into the URDF model.

This will write out the calibration into the provided urdf model. Prior to that the old model file is copied and renamed as a backup.

bool saveObservationsToCalibrationWorkspace() const

Trigger data processors to save observations that have been used for calibration to the corresponding workspace.

Returns:

True, if successful. False, otherwise.

bool saveResultsToCalibrationWorkspace() const

Method to save the results of the calibration into file in the calibration workspace.

This will write out a file in the calibration workspace that olds teh calibration results. If the desired file already exists, the existing file is copied and renamed.

Returns:

True, if successful. False, otherwise.

bool setSensorExtrinsicsFromFrameIds(const std::string &iSourceFrameId, const std::string &iReferenceFrameId)

Set relative sensor extrinsics (sensorExtrinsics_) from the given frame IDs.

This will extract a transformation from the tfListener and set the sensor extrinsics accordingly.

Parameters:
  • iSourceFrameId[in] Frame Id of source sensor.

  • iReferenceFrameId[in] Frame Id of reference sensor.

Returns:

True, if successful. False, otherwise.

std::pair<tf2::Vector3, tf2::Vector3> computeTargetPoseStdDev(const std::vector<lib3d::Extrinsics> &iSrcTargetPoses, const std::vector<lib3d::Extrinsics> &iRefTargetPoses) const

Compute standard deviation in detected target poses when they are transformed between the sensor frames based on the estimated extrinsic calibration.

This will transform the detected target poses from the source sensor into the frame of the reference sensor and compute the standard deviation between the poses. The transformation is done using the sensor extrinsic that is estimated last.

Parameters:
  • iSrcTargetPoses[in] Target poses detected in source sensor.

  • iRefTargetPoses[in] Target poses detected in reference sensor.

Returns:

The standard deviation of the target poses in XYZ (in meters) and RPY (in degrees).

bool initializeAndStartSensorCalibration(rclcpp::Node *ipNode)

Initialize and start calibration.

Parameters:

ipNode[inout] Pointer to node.

Returns:

True, if successful. False otherwise.

Protected Attributes

rclcpp::Publisher<CalibrationResult_Message_T>::SharedPtr pCalibResultPub_

Pointert to publish calibration result.

rclcpp::Service<interf::srv::RemoveLastObservation>::SharedPtr pRemoveObsSrv_

Pointer to service to remove last observation.

rclcpp::Service<interf::srv::CalibrationMetaData>::SharedPtr pCalibMetaDataSrv_

Pointer to service to request calibration meta data.

rclcpp::Service<interf::srv::SensorExtrinsics>::SharedPtr pSensorExtrinsicsSrv_

Pointer to service to request sensor extrinsics.

std::shared_ptr<SrcDataProcessorT> pSrcDataProcessor_

Pointer to data processor of source sensor.

std::shared_ptr<RefDataProcessorT> pRefDataProcessor_

Pointer to data processor of reference sensor.

std::string srcSensorName_

Name of the source sensor.

std::string srcTopicName_

Topic name of the data from the source sensor.

std::string srcFrameId_

Frame id of data from the source sensor.

std::string refSensorName_

Name of the reference sensor.

std::string refTopicName_

Topic name of the data from the source sensor.

std::string refFrameId_

Frame id of data from the reference sensor.

std::string baseFrameId_

Frame id of base frame with respect to which the source frame is to be calibrated. If omitted, the source frame will be calibrated with respect to refFrameID_.

std::vector<lib3d::Extrinsics> sensorExtrinsics_

Object holding extrinsic transformation between the source and the reference sensor.

CalibrationResult calibResult_

Object holding the result of the calibration.

bool useTfTreeAsInitialGuess_

Fag to use frame IDs in TF-Tree as initial guess. Default: false.