Template Class SensorDataProcessorBase

Class Documentation

template<class SensorDataT>
class SensorDataProcessorBase

Base class of all sensor data processor templated with the data type of the sensor data which is to be processed by the class.

Template Parameters:

SensorDataT – Type of data to be processed.

Public Types

enum EProcessingLevel

Enumeration holding level at which the sensor data is to be processed.

Values:

enumerator PREVIEW

Process sensor data only for preview purposes.

enumerator TARGET_DETECTION

Do actual detection of calibration target in data processing.

enum EProcessingResult

Enumeration holding the different results that can be returned after data processing.

Values:

enumerator FAILED

Processing of sensor data has failed.

enumerator SUCCESS

Processing of sensor data has succeeded. Only then, are the results that valid.

enumerator PENDING

processing is pending, i.e. waiting for more data.

Public Functions

SensorDataProcessorBase() = delete

Default constructor is deleted.

SensorDataProcessorBase(const std::string &iLoggerName, const std::string &iSensorName, const fs::path &iCalibTargetFilePath)

Initialization constructor, providing the node name, the sensor name as well as the path to the calibration target configuration file.

virtual ~SensorDataProcessorBase()

Destructor.

std::vector<lib3d::Extrinsics> getCalibrationTargetPoses() const

Get List of all detected and estimated poses of the calibration target.

lib3d::Extrinsics getLastCalibrationTargetPose() const

Get last pose of calibration target board.

uint getNumCalibIterations() const

Get the number of iterations for which observations have been captured.

std::string getSensorName() const

Get name of the sensor from which the data is processed.

virtual EProcessingResult processData(const SensorDataT &iSensorData, const EProcessingLevel &iProcLevel) = 0

Purely virtual interface class to call the processing of the data.

Parameters:
  • iSensorData[in] Sensor data.

  • iProcLevel[in] Level at which the data is to be processed, i.e. PREVIEW or TARGET_DETECTION

Returns:

Result of the processing.

void publishLastCalibrationTargetPose(const std_msgs::msg::Header &iHeader, const lib3d::Extrinsics &iPose, const bool &iIsDetection, const rclcpp::Publisher<TargetBoardPose_Message_T>::SharedPtr &ipPub) const

Method to publish given extrinsic pose of the calibration target.

Parameters:
  • iHeader[in] Header with which to publish the pose.

  • iPose[in] Pose to publish.

  • iIsDetection[in] Flag to indicate if pose is actual detection or just preview.

  • ipPub[in] Publisher.

virtual void publishPreview(const std_msgs::msg::Header &iHeader) const = 0

Method to publish preview data.

Parameters:

iHeader[in] Header for the ROS message that is to be published.

void publishPreview(const rclcpp::Time &iStamp, std::string &iFrameId) const

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Parameters:
  • iStamp[in] Timestamp for the ROS message that is to be published.

  • iFrameId[in] FrameId for the ROS message that is to be published.

virtual void publishLastTargetDetection(const std_msgs::msg::Header &iHeader) const = 0

Method to publish data of last successful target detection.

Parameters:

iHeader[in] Header for the ROS message that is to be published.

void publishLastTargetDetection(const rclcpp::Time &iStamp, std::string &iFrameId) const

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Parameters:
  • iStamp[in] Timestamp for the ROS message that is to be published.

  • iFrameId[in] FrameId for the ROS message that is to be published.

virtual bool removeCalibIteration(const uint &iIterationId)

Remove observations corresponding to given calibration iteration.

Parameters:

iIterationId[in] Iteration ID for which the observations are to be removed.

Returns:

True, if successful. False, otherwise (i.e. if the specified iteration is not available).

virtual bool saveObservations(const fs::path iOutputDir) const

Save the observations to given output directory.

Parameters:

iOutputDir[in] Path to output directory.

Returns:

True if successful, false otherwise.

Protected Functions

bool averageObservations(const std::vector<lib3d::Extrinsics> &iCalibTargetPoses, lib3d::Extrinsics &oAvgdCalibTargetPose) const

Method to average the observations.

Parameters:
  • iCalibTargetPoses[out] List of calibration target poses which are to be averaged.

  • oAvgdCalibTargetPose[out] Pose of the calibration target, averaged from given poses.

Returns:

True if successful, false otherwise (e.g. no observations available).

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

Method to initialize publishers.

Parameters:

ipNode[inout] Pointer to node to which the publishers are to be initialized.

Returns:

True, if successful. False otherwise.

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

Method to initialize services.

Parameters:

ioNh[inout] Pointer to node to which the services are to be initialized.

Returns:

True, if successful. False otherwise.

virtual void reset()

Method to reset.

Protected Attributes

rclcpp::Logger logger_

Logging Object.

bool isInitialized_

Flag indicating if node is initialized.

std::string sensorName_

Name of the sensor for which the data is being processed.

CalibrationTarget calibrationTarget_

Object of calibration target.

std::pair<int, int> markerIdRange_

Range of marker IDs deployed on calibration target.

std::vector<lib3d::Extrinsics> capturedCalibTargetPoses_

List of captured poses of the calibration target.