Class CalibrationBase

Inheritance Relationships

Derived Types

Class Documentation

class CalibrationBase

Base class of all calibration nodes. This holds a common interface to all calibration nodes.

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

Public Functions

CalibrationBase() = delete

Default constructor is deleted.

CalibrationBase(ECalibrationType type)

Initialization constructor.

Parameters:

type[in] Type of calibration.

virtual ~CalibrationBase()

Destructor.

Protected Functions

bool initializeAndStartSensorCalibration(rclcpp::Node *ipNode)

Initialize and start calibration.

Parameters:

ipNode[inout] Pointer to node.

Returns:

True, if successful. False otherwise.

void initializeTfListener(rclcpp::Node *ipNode)

Initialize TF listener.

Parameters:

ipNode[in] Pointer to node.

virtual bool finalizeCalibration() = 0

Finalize calibration.

Returns:

True, if successful. False, otherwise.

virtual bool initializeDataProcessors() = 0

Initialize data processing, i.e. the objects that will process the sensor data and detect the calibration target within the data.

Returns:

True, if all settings are valid. False, otherwise.

virtual bool initializePublishers(rclcpp::Node *ipNode) = 0

Initialize publishers.

Parameters:

ipNode[inout] Pointer to node.

Returns:

True, if successful. False otherwise.

virtual bool initializeServices(rclcpp::Node *ipNode)

Initialize services.

Parameters:

ipNode[inout] Pointer to node.

Returns:

True, if successful. False otherwise.

virtual bool initializeSubscribers(rclcpp::Node *ipNode) = 0

Initialize subscribers.

Returns:

True, if all settings are valid. False, otherwise.

virtual bool initializeWorkspaceObjects()

Initialize workspace objects. In this class, i.e. the calibration base class, only the object of the robot workspace is initialized. The initialization requires the launch parameters, thus it is to be executed after the launch parameters are read.

Returns:

True if successful. False, otherwise (e.g. if instantiation has failed)

bool isFrameIdInUrdfModel(const std::string &iFrameId) const

Check if given frame ID is in URDF model.

Returns:

True, if frame ID is found in model. False, otherwise.

virtual bool saveCalibrationSettingsToWorkspace()

Save calibration settings to setting.ini inside calibration workspace.

Returns:

True, if all settings are valid. False, otherwise.

virtual void setupLaunchParameters(rclcpp::Node *ipNode) const

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 void setupDynamicParameters(rclcpp::Node *ipNode) const = 0

Setup dynamic parameters.

Parameters:

ipNode[in] Pointer to node.

virtual bool readLaunchParameters(const rclcpp::Node *ipNode)

Read launch parameters.

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)

rcl_interfaces::msg::SetParametersResult handleDynamicParameterChange(const std::vector<rclcpp::Parameter> &iParameters)

Handle dynamic change of parameters. For example, through rqt_reconfigure.

This loops through the list of parameters in iParameters and sets their value accordingly.

Parameters:

iParameters[in] Parameters that have changed.

virtual bool setDynamicParameter(const rclcpp::Parameter &iParameter)

Virtual function to set dynamic parameter. This is called from handleDynamicParameterChange for each parameter in the list that is to be changed.

Parameters:

iParameter[in] Parameter that is to be changed.

Returns:

True, if successful, i.e. if it has been changed. False, otherwise.

template<typename T>
T readNumericLaunchParameter(const rclcpp::Node *ipNode, const std::string &iParamName, const T &iDefaultVal, const T &iMinVal, const T &iMaxVal) const

Read numeric launch parameter with given name (‘iParamName’) and default Value (‘iDefaultVal’).

If parameter value is below ‘iMinVal’ or above ‘iMaxVal’, the default value is set

Returns:

Parameter value.

std::string readStringLaunchParameter(const rclcpp::Node *ipNode, const std::string &iParamName, const std::string &iDefaultVal = "") const

Read string launch parameter with given name (‘iParamName’) and default Value (‘iDefaultVal’).

If parameter string is empty and default value is not empty, it is assumed that the parameter is not allowed to be empty. In this case the default value will be set.

Returns:

Parameter value.

virtual void reset()

Reset calibration.

virtual bool shutdownSubscribers() = 0

Shutdown subscribers and disconnect callbacks.

Returns:

True, if successful. False, otherwise.

virtual bool saveCalibration() = 0

Save calibration.

Returns:

True, if successful. False, otherwise.

Protected Attributes

ECalibrationType type_

Type of calibration.

bool isInitialized_

Flag indicating if node is initialized.

rclcpp::Logger logger_

Logger object of node.

std::mutex dataProcessingMutex_

Mutex guarding the data processing.

rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr pParameterCallbackHandle_

Callback handle to adjust parameters.

std::unique_ptr<tf2_ros::Buffer> tfBuffer_

TF buffer needed for listener.

std::shared_ptr<tf2_ros::TransformListener> tfListener_

Transform listener to get transform between the two sensor frames.

rclcpp::Service<interf::srv::CaptureCalibTarget>::SharedPtr pCaptureSrv_

Pointer to service to request capturing of calibration target.

rclcpp::Service<interf::srv::FinalizeCalibration>::SharedPtr pFinalizeSrv_

Pointer to service to request finalization of calibration.

rclcpp::Service<interf::srv::ResetCalibration>::SharedPtr pResetSrv_

Pointer to service to reset calibration.

fs::path robotWsPath_

Absolute path to robot workspace.

std::shared_ptr<AbstractWorkspace> pRobotWs_

Pointer to robot workspace.

std::string robotName_

Name of robot.

bool isUrdfModelAvailable_

Flag to indicate if URDF model is available.

fs::path urdfModelPath_

absolute path to URDF model file of robot.

tinyxml2::XMLDocument urdfModelDoc_

XML document of URDF model.

urdf::Model urdfModel_

URDF model of robot.

bool saveObservationsToWs_

Flag controlling whether the observations are to be saved into the calibration workspace after calibration.

std::shared_ptr<AbstractWorkspace> pCalibrationWs_

Pointer to base calibration workspace. The instantiation of the pointer is done in the individual calibration node.

fs::path calibTargetFilePath_

Path to target configuration file.

bool captureCalibrationTarget_

Flag to capture calibration target in next sensor data package.

uint calibrationItrCnt_

Iteration number of the calibration routine.