1414
1515#pragma once
1616
17- #include < atomic>
1817#include < deque>
1918#include < memory>
2019#include < mutex>
2120#include < string>
2221#include < vector>
2322
23+ #include < deep_msgs/msg/multi_image.hpp>
2424#include < opencv2/core/mat.hpp>
2525#include < rclcpp/node_options.hpp>
2626#include < rclcpp/rclcpp.hpp>
2929#include < sensor_msgs/msg/compressed_image.hpp>
3030#include < std_msgs/msg/header.hpp>
3131
32- #include < deep_msgs/msg/multi_image.hpp>
33-
3432#include " deep_object_detection/backend_manager.hpp"
3533#include " deep_object_detection/detection_types.hpp"
3634#include " deep_object_detection/generic_postprocessor.hpp"
@@ -42,9 +40,9 @@ namespace deep_object_detection
4240/* *
4341 * @brief ROS2 lifecycle node for object detection using ONNX models
4442 *
45- * This node performs object detection on images from cameras or synchronized multi-camera streams.
43+ * This node performs object detection on synchronized multi-camera streams via MultiImage messages .
4644 * It supports:
47- * - Multiple input modes: individual camera topics or synchronized MultiImage messages
45+ * - MultiImage input: synchronized compressed images from multiple cameras
4846 * - Batch processing: groups images for efficient inference
4947 * - Multiple backends: CPU, CUDA, or TensorRT execution providers
5048 * - Configurable preprocessing: resizing, normalization, color format conversion
@@ -114,143 +112,40 @@ class DeepObjectDetectionNode : public rclcpp_lifecycle::LifecycleNode
114112 const rclcpp_lifecycle::State &) override ;
115113
116114private:
117- /* *
118- * @brief Declare and read all ROS2 parameters
119- *
120- * Reads model configuration, preprocessing/postprocessing parameters, camera topics,
121- * batch settings, and backend provider settings from ROS2 parameters.
122- */
123115 void declareAndReadParameters ();
124-
125- /* *
126- * @brief Setup subscriptions to individual camera compressed image topics
127- *
128- * Creates one subscription per camera topic in params_.camera_topics.
129- * Each subscription calls handleCompressedImage() with the camera index.
130- */
131- void setupMultiCameraSubscriptions ();
132-
133- /* *
134- * @brief Setup subscription to synchronized MultiImage topic
135- *
136- * Creates a single subscription to camera_sync_topic_ that receives MultiImage
137- * messages containing synchronized compressed images from multiple cameras.
138- */
139- void setupCameraSyncSubscription ();
140-
141- /* *
142- * @brief Handle incoming MultiImage message with synchronized images
143- * @param msg MultiImage message containing multiple compressed images
144- *
145- * Extracts each compressed image from the MultiImage and processes them
146- * through handleCompressedImage() with sequential camera IDs.
147- */
116+ void setupSubscription ();
148117 void onMultiImage (const deep_msgs::msg::MultiImage::ConstSharedPtr & msg);
149-
150- /* *
151- * @brief Handle incoming compressed image from a camera
152- * @param msg Compressed image message
153- * @param camera_id Camera identifier (index for multi-camera, or from MultiImage)
154- *
155- * Decodes the compressed image, enqueues it for batch processing.
156- * Handles decode failures according to decode_failure_policy.
157- */
158- void handleCompressedImage (const sensor_msgs::msg::CompressedImage & msg, int camera_id);
159-
160- /* *
161- * @brief Add image to processing queue
162- * @param image Decoded BGR image (OpenCV Mat)
163- * @param header ROS message header with timestamp and frame_id
164- *
165- * Thread-safe enqueueing. Applies queue_overflow_policy if queue is full.
166- * Tracks first image timestamp for batch timeout calculation.
167- */
118+ void handleCompressedImage (const sensor_msgs::msg::CompressedImage & msg);
168119 void enqueueImage (cv::Mat image, const std_msgs::msg::Header & header);
169-
170- /* *
171- * @brief Format tensor shape vector as string for logging
172- * @param shape Vector of dimension sizes
173- * @return Comma-separated string representation (e.g., "1, 3, 640, 640")
174- */
175- std::string formatShape (const std::vector<size_t > & shape) const ;
176-
177- /* *
178- * @brief Timer callback for batch processing
179- *
180- * Called periodically (every 5ms) to check if batch should be processed.
181- * Processes batch if:
182- * - Queue size >= min_batch_size, OR
183- * - max_batch_latency_ms exceeded and queue not empty
184- * Extracts up to max_batch_size images and calls processBatch().
185- */
186120 void onBatchTimer ();
187-
188- /* *
189- * @brief Process a batch of images through inference pipeline
190- * @param batch Vector of queued images to process
191- *
192- * For each image: preprocess -> inference -> postprocess -> publish detections.
193- * Handles multi-output models if configured. Publishes Detection2DArray messages.
194- */
195121 void processBatch (const std::vector<QueuedImage> & batch);
196-
197- /* *
198- * @brief Publish detection results for a batch
199- * @param batch_detections Detections for each image in batch
200- * @param headers Message headers for each image (for frame_id and timestamp)
201- * @param metas Image metadata for coordinate transformation
202- *
203- * Creates and publishes Detection2DArray message for each image with its detections.
204- */
205122 void publishDetections (
206123 const std::vector<std::vector<SimpleDetection>> & batch_detections,
207124 const std::vector<std_msgs::msg::Header> & headers,
208125 const std::vector<ImageMeta> & metas);
209-
210- /* *
211- * @brief Load class names from file
212- *
213- * Reads class names from params_.model_metadata.class_names_file (one per line).
214- * Stores in params_.class_names for use in postprocessing and message publishing.
215- */
216126 void loadClassNames ();
217-
218- /* *
219- * @brief Stop all subscriptions and cancel batch timer
220- *
221- * Clears all camera subscriptions, resets MultiImage subscription,
222- * cancels batch timer, and clears image queue. Used in deactivate/cleanup/shutdown.
223- */
127+ void cleanupPartialConfiguration ();
128+ void cleanupAllResources ();
224129 void stopSubscriptionsAndTimer ();
225130
226- DetectionParams params_; // /< All node configuration parameters
131+ DetectionParams params_;
132+
133+ rclcpp::Subscription<deep_msgs::msg::MultiImage>::SharedPtr multi_image_sub_;
134+ std::string input_topic_;
135+ rclcpp_lifecycle::LifecyclePublisher<Detection2DArrayMsg>::SharedPtr detection_pub_;
136+ rclcpp::TimerBase::SharedPtr batch_timer_;
227137
228- std::vector<rclcpp::Subscription<sensor_msgs::msg::CompressedImage>::SharedPtr>
229- multi_camera_subscriptions_; // /< Subscriptions for individual camera topics
230- rclcpp::Subscription<deep_msgs::msg::MultiImage>::SharedPtr
231- multi_image_sub_; // /< Subscription for synchronized MultiImage messages
232- bool use_camera_sync_{false }; // /< Whether to use MultiImage sync mode or individual topics
233- std::string camera_sync_topic_; // /< Topic name for MultiImage messages
234- rclcpp::Publisher<Detection2DArrayMsg>::SharedPtr detection_pub_; // /< Publisher for detection results
235- rclcpp::TimerBase::SharedPtr batch_timer_; // /< Timer for periodic batch processing checks
138+ std::deque<QueuedImage> image_queue_;
139+ std::mutex queue_mutex_;
140+ rclcpp::CallbackGroup::SharedPtr callback_group_;
236141
237- std::deque<QueuedImage> image_queue_; // /< Queue of images waiting for batch processing
238- std::mutex queue_mutex_; // /< Mutex protecting image_queue_ and first_image_timestamp_
239- std::atomic<bool > processing_{false }; // /< Flag to prevent concurrent batch processing
240- rclcpp::Time first_image_timestamp_; // /< Timestamp of oldest image in queue (for batch timeout)
142+ size_t dropped_images_count_;
241143
242- std::unique_ptr<ImagePreprocessor> preprocessor_; // /< Image preprocessing (resize, normalize, etc.)
243- std::unique_ptr<GenericPostprocessor> postprocessor_; // /< Detection postprocessing (NMS, decode, etc.)
244- std::unique_ptr<BackendManager> backend_manager_; // /< Backend plugin manager (CPU/CUDA/TensorRT)
144+ std::unique_ptr<ImagePreprocessor> preprocessor_;
145+ std::unique_ptr<GenericPostprocessor> postprocessor_;
146+ std::unique_ptr<BackendManager> backend_manager_;
245147};
246148
247- /* *
248- * @brief Factory function to create DeepObjectDetectionNode instance
249- * @param options Node options for ROS2 configuration
250- * @return Shared pointer to lifecycle node
251- *
252- * Used by rclcpp_components for component loading.
253- */
254149std::shared_ptr<rclcpp_lifecycle::LifecycleNode> createDeepObjectDetectionNode (
255150 const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
256151
0 commit comments