Class DataProcessor3d

Inheritance Relationships

Base Type

Derived Types

Class Documentation

class DataProcessor3d : public multisensor_calibration::SensorDataProcessorBase<pcl::PointCloud<InputPointType>>

Base class for processing the 3D sensor data in the form of a 3D point cloud.

This subclasses the base class SensorDataProcessorBase with pcl::PointCloud as template specialization.

Subclassed by multisensor_calibration::LidarDataProcessor, multisensor_calibration::ReferenceDataProcessor3d

Public Functions

DataProcessor3d() = delete

Default constructor is deleted.

DataProcessor3d(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 ~DataProcessor3d()

Destructor.

void setDataTransform(const std::shared_ptr<tf2::Transform> &pTransform)

Method to set pointer to transform that will transform the data into a common frame.

Parameters:

pTransform[in] Pointer to Transform object.

std::vector<pcl::PointCloud<InputPointType>::Ptr> getCalibrationTargetCloudPtrs() const

Get copy of list holding pointers to point clouds of detected calibration boards.

pcl::PointCloud<InputPointType>::Ptr getLastCalibrationTargetCloud() const

Get copy of pointer to last point cloud of detected calibration board.

pcl::PointCloud<InputPointType>::Ptr getLastInputCloud() const

Get copy of pointer to last input point cloud.

std::vector<std::array<cv::Point3f, 4>> getLastEstimatedMarkerCorners() const

Get list of last estimated marker corners corresponding to detected marker IDs.

std::vector<uint> getLastEstimatedMarkerIds() const

Get list of last estimated marker IDs.

pcl::PointCloud<pcl::PointXYZI>::Ptr getLastMarkerCornersCloud() const

Get pointer to 3D cloud holding the estimated marker corner positions. Each point holds the ID of the corresponding marker in the intensity value. the corners are stored in a clockwise direction starting from top-left corner.

void getOrderedObservations(std::set<uint> &oObservationIds, std::vector<cv::Point3f> &oCornerObservations, const int &iIterationBegin = 1, const int &iNumIterations = -1) const

Get observations with unique IDs and in ascending order.

Parameters:
  • oObservationIds[out] Ordered set holding the IDs of 3D point observations. The observations of the marker corners are associated with the marker IDs. And for each iteration the ID is added to a corresponding multiple of hundred (i.e. Iteration 1 + ID 1 = 101, Iteration 2 + ID 1 = 201).

  • oCornerObservations[out] List holding the actual observations of the marker corners in the order as stored in oObservationIds. Since for each marker four corners (clockwise from top-left) are observed, the size of oCornerPoints is 4x the size of oObservationIds.

  • iIterationBegin[in] Iteration number from which to begin the extraction.

  • iNumIterations[in] Number of iterations for which the observations are to be extracted. If set to -1, all iterations between iTerationBegin and end will be included.

pcl::PointCloud<InputPointType>::Ptr getRegionOfInterestsCloudPtr() const

Get Pointer to cloud holding all region of interests.

bool getSensorDataFromMsg(const InputCloud_Message_T::ConstSharedPtr &ipMsg, pcl::PointCloud<InputPointType> &oData) const

Get sensor data from ros message.

Parameters:
  • ipMsg[in] Pointer to input message.

  • oData[out] Sensor data.

virtual bool initializePublishers(rclcpp::Node *ipNode)

Method to initialize publishers.

Parameters:

ipNode[inout] Pointer to node to which the service is to be initialized.

Returns:

True, if successful. False otherwise.

virtual bool initializeServices(rclcpp::Node *ipNode)

Method to initialize services.

Parameters:

ipNode[inout] Pointer to node to which the service is to be initialized.

Returns:

True, if successful. False otherwise.

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

Method to publish preview data, i.e. the segmented region of interest.

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

Parameters:

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

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

Method to publish data of successful target detection.

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

Parameters:

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

virtual bool removeCalibIteration(const uint &iIterationId) override

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 void reset() override

Reset processor.

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

Save the observations to given output directory.

Parameters:

iOutputDir[in] Path to output directory.

Returns:

True if successful, false otherwise.

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.

Public Static Functions

static void writeMarkerObservationsToFile(const fs::path &iFilePath, const std::vector<uint> &iMarkerIds, const std::vector<std::array<cv::Point3f, 4>> &iMarkerCorners)

Write observations of marker corners into file.

Parameters:
  • iFilePath[in] Path to output file.

  • iMarkerIds[in] List of marker ids.

  • iMarkerCorners[in] List of marker corners. For each marker (corresponding to marker ID) there are 4 corners with 3D coordinates.

static bool readMarkerObservationsFromFile(const fs::path &iFilePath, std::vector<uint> &oMarkerIds, std::vector<std::array<cv::Point3f, 4>> &oMarkerCorners)

Read observations of marker corners from file.

Parameters:
  • iFilePath[in] Path to output file.

  • oMarkerIds[out] List of marker ids.

  • oMarkerCorners[out] List of marker corners. For each marker (corresponding to marker ID) there are 4 corners with 3D coordinates.

Returns:

True if successful, false otherwise (e.g. if file not exists).

Protected Functions

bool onAddMarkerObservations(const std::shared_ptr<multisensor_calibration_interface::srv::AddMarkerObservations::Request> iReq, std::shared_ptr<multisensor_calibration_interface::srv::AddMarkerObservations::Response> oRes)

Service call to handle adding of reference marker positions.

Parameters:
  • iReq[in] Request.

  • oRes[out] Response.

bool onImportMarkerObservations(const std::shared_ptr<multisensor_calibration_interface::srv::ImportMarkerObservations::Request> iReq, std::shared_ptr<multisensor_calibration_interface::srv::ImportMarkerObservations::Response> oRes)

Service call to handle import of reference marker positions.

Parameters:
  • iReq[in] Request.

  • oRes[out] Response.

Protected Attributes

std::shared_ptr<tf2::Transform> pDataTransform_

Pointer to transform object which can be used transform the Lidar data prior to processing or the detected data points in post-processing.

pcl::PointCloud<InputPointType>::Ptr pRoisCloud_

Pointer to point cloud holding the regions of interest for publishing.

std::vector<pcl::PointCloud<InputPointType>::Ptr> inputCloudPtrs_

List of pointers to input point clouds in which the target has been detected.

std::vector<pcl::PointCloud<InputPointType>::Ptr> calibrationTargetCloudPtrs_

List of pointers to point cloud of detected calibration board.

std::vector<std::vector<uint>> estimatedMarkerIds_

List of captured marker IDs per iteration.

std::vector<std::vector<std::array<cv::Point3f, 4>>> estimatedMarkerCorners_

List of captured marker corners corresponding to detected marker IDs.

std::vector<pcl::PointCloud<pcl::PointXYZI>::Ptr> estimatedMarkerCornersCloudPtrs_

List of pointers to 3D cloud holding the estimated marker corner positions.

rclcpp::Service<multisensor_calibration_interface::srv::AddMarkerObservations>::SharedPtr pAddMarkerObsSrv_

Pointer to service to add marker observations.

rclcpp::Service<multisensor_calibration_interface::srv::ImportMarkerObservations>::SharedPtr pImportMarkerObsSrv_

Pointer to service to import marker observations.

rclcpp::Publisher<RoisCloud_Message_T>::SharedPtr pRoisCloudPub_

Publisher for regions of interest in which a search for the calibration target is performed.

rclcpp::Publisher<TargetPatternCloud_Message_T>::SharedPtr pTargetCloudPub_

Publisher for target point cloud.

rclcpp::Publisher<MarkerCornerCloud_Message_T>::SharedPtr pMarkerCornersPub_

Publisher for corners of marker positions.

rclcpp::Publisher<TargetBoardPose_Message_T>::SharedPtr pTargetBoardPosePub_

Publisher for target board pose.