Class GuidanceBase

Inheritance Relationships

Derived Types

Class Documentation

class GuidanceBase

Base class for all classes that guide the user in the calibration process.

Note

The guidance feature of the calibration is currently still in development and not yet functional.

Subclassed by multisensor_calibration::GuidedCameraLidarTargetPlacementNode, multisensor_calibration::GuidedLidarLidarTargetPlacementNode

Public Functions

GuidanceBase(rclcpp::Node *pNode)

Default constructor.

virtual ~GuidanceBase()

Destructor.

Protected Types

typedef multisensor_calibration_interface::srv::CalibrationMetaData CalibrationMetadataSrv
typedef multisensor_calibration_interface::srv::SensorExtrinsics SensorExtrinsicsSrv

Protected Functions

float computeAxisBound(const Eigen::Vector3d &iPnt, const Eigen::Vector3d &iVec, const Eigen::Vector4d &iPlane) const

Function to compute bound on axis along ‘iVec’ w.r.t to ‘iPnt’ by intersecting the axis with the plane ‘iPlane’.

virtual void computeExtrinsicFovBoundingPlanes() = 0

Method to compute overlapping Fov between the two sensors based on the estimated extrinsic pose.

Note

This is a pure virtual method and needs to be implemented by the specific subclasses.

virtual bool computeIntrinsicFovBoundingPlanes() = 0

Method to compute Fov of the two sensors based on the intrinsic parameters.

Note

This is a pure virtual method and needs to be implemented by the specific subclasses.

virtual void computeNextTargetPose() = 0

Method to compute next target pose.

Note

This is a pure virtual method and needs to be implemented by the specific subclasses.

virtual bool initializePublishers() = 0

Method to initialize publishers.

Parameters:

ioNh[inout] Reference to node handle

Returns:

True, if successful. False otherwise.

virtual bool initializeServices()

Method to initialize services.

Parameters:

ioNh[inout] Reference to node handle

Returns:

True, if successful. False otherwise.

virtual bool initializeSubscribers()

Method to initialize subscribers.

Returns:

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

virtual bool initializeTimers()

Method to initialize timers.

Parameters:

ioNh[inout] Reference to node handle

Returns:

True, if successful. False otherwise.

bool isTargetPoseWithinBoundingPlanes(const lib3d::Extrinsics &iPose) const

Function to check if pose of the calibration target is within the bounding planes.

Returns:

True, if target with given pose is within bounding planes. False, otherwise.

virtual void onCalibrationResultReceived(const CalibrationResult_Message_T::ConstSharedPtr &ipResultMsg)

Callback function handling calibration results messages.

Parameters:

ipResultMsg[in] Calibration result message.

virtual void onTargetPoseReceived(const TargetBoardPose_Message_T::ConstSharedPtr &ipPoseMsg)

Callback function handling target pose messages.

Parameters:

ipPoseMsg[in] Target pose message.

virtual bool readLaunchParameters()

Method to read launch parameters.

Parameters:

iNh[in] Object of node handle

Returns:

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

virtual void resetNextTargetPose() = 0

Method to reset nextTargetPose_.

Protected Attributes

bool isInitialized_

Flag indicating if node is initialized.

bool initialPoseReceived_

Flag indicating if the initialPose has been received.

std::string appTitle_

Name of the app.

rclcpp::Node *pNode_

Global node handler.

rclcpp::Executor *pExecutor_

ROS2 Executor.

std::string calibratorNodeName_

Name of the calibrator node.

rclcpp::TimerBase::SharedPtr pCalibMetaDataTimer_

Timer object to trigger service call to get calibration meta data.

rclcpp::Subscription<CalibrationResult_Message_T>::SharedPtr pCalibResultSubsc_

Subscriber to calibration result messages.

rclcpp::Subscription<TargetBoardPose_Message_T>::SharedPtr pTargetPoseSubsc_

Subscriber to target pose messages.

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

Server to provide service to reset calibration.

CalibrationMetadataSrv::Response::SharedPtr pCalibrationMetaData_

Member variable holding calibration meta data.

lib3d::Extrinsics extrinsicSensorPose_

Extrinsic pose between the sensors to calibrate.

std::vector<Eigen::Vector4d> fovBoundingPlanes_

List of planes encapsulating the overlapping FoV between the sensors.

CalibrationTarget calibrationTarget_

Object of the calibration target used.

std::vector<lib3d::Extrinsics> detectedTargetPoses_

List of target poses detected during calibration.

lib3d::Extrinsics nextTargetPose_

Pose of the calibration target that is to be placed next.

std::array<Eigen::Vector3d, 3> axes_

Axes to be covered by the calibration.

rclcpp::Client<CalibrationMetadataSrv>::SharedPtr pMetaDataClient_

Services.

rclcpp::Client<SensorExtrinsicsSrv>::SharedPtr extrinsicsClient_