Class DataProcessor2d
Defined in File DataProcessor2d.h
Inheritance Relationships
Base Type
public multisensor_calibration::SensorDataProcessorBase< cv::Mat >
(Template Class SensorDataProcessorBase)
Derived Type
public multisensor_calibration::CameraDataProcessor
(Class CameraDataProcessor)
Class Documentation
-
class DataProcessor2d : public multisensor_calibration::SensorDataProcessorBase<cv::Mat>
Base class for processing the 2D sensor data in the form of a images.
This subclasses the base class SensorDataProcessorBase with cv::Mat as template specialization.
Subclassed by multisensor_calibration::CameraDataProcessor
Public Functions
-
DataProcessor2d() = delete
Default constructor is deleted.
-
DataProcessor2d(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 ~DataProcessor2d()
Destructor.
-
cv::Mat getAnnotatedCameraImagePreview() const
Get copy of last camera image annotated with detected markers as preview.
This will only annotate the borders of the markers, not the corners them selfs.
-
pcl::PointCloud<pcl::PointXYZRGB>::Ptr getLastCalibrationTargetCloudPtr() const
Get copy of pointer to point cloud of last detected calibration board.
-
std::vector<std::array<cv::Point2f, 4>> getLastCapturedMarkerCorners() const
Get list of last detected marker corners corresponding to detected marker IDs extracted with getLastCapturedMarkerIds().
-
std::vector<int> getLastCapturedMarkerIds() const
Get list of last detected marker IDs.
-
void getOrderedObservations(std::set<uint> &oObservationIds, std::vector<cv::Point2f> &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 2D image 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.
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 camera image annotated with the marker detections.
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.
-
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<int> &iMarkerIds, const std::vector<std::array<cv::Point2f, 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 2D coordinates.
Protected Attributes
-
cv::Mat annotatedCameraImgPreview_
Copy of last camera image annotated with detected markers used for preview.
-
std::vector<cv::Mat> annotatedCameraImageDetection_
Camera images in which the detections are annotated.
-
std::vector<std::vector<int>> capturedMarkerIds_
List of captured marker IDs per iteration.
-
std::vector<std::vector<std::array<cv::Point2f, 4>>> capturedMarkerCorners_
List of captured marker corners corresponding to detected marker IDs.
-
std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> calibrationTargetCloudPtrs_
List of pointers to point cloud of detected calibration board.
-
rclcpp::Publisher<AnnotatedImage_Message_T>::SharedPtr pAnnotatedImgPub_
Publisher for image annotated with marker detections.
-
rclcpp::Publisher<MarkerCornersImgPnts_Message_T>::SharedPtr pMarkerCornersPub_
Publisher for corners of marker positions.
-
rclcpp::Publisher<TargetPatternCloud_Message_T>::SharedPtr pTargetCloudPub_
Publisher for target point cloud.
-
rclcpp::Publisher<TargetBoardPose_Message_T>::SharedPtr pTargetBoardPosePub_
Publisher for target board pose.
-
DataProcessor2d() = delete