|
| 1 | +#!/usr/bin/env python3 |
| 2 | +# Copyright (c) 2025-present WATonomous. All rights reserved. |
| 3 | +# |
| 4 | +# Licensed under the Apache License, Version 2.0 (the "License"); |
| 5 | +# you may not use this file except in compliance with the License. |
| 6 | +# You may obtain a copy of the License at |
| 7 | +# |
| 8 | +# http://www.apache.org/licenses/LICENSE-2.0 |
| 9 | +# |
| 10 | +# Unless required by applicable law or agreed to in writing, software |
| 11 | +# distributed under the License is distributed on an "AS IS" BASIS, |
| 12 | +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 13 | +# See the License for the specific language governing permissions and |
| 14 | +# limitations under the License. |
| 15 | + |
| 16 | +"""Launch test for deep_object_detection with CPU backend (cpu).""" |
| 17 | + |
| 18 | +import os |
| 19 | +import time |
| 20 | +import unittest |
| 21 | + |
| 22 | +import cv2 |
| 23 | +import launch |
| 24 | +import launch_ros.actions |
| 25 | +import launch_testing |
| 26 | +import launch_testing.actions |
| 27 | +import launch_testing.asserts |
| 28 | +import numpy as np |
| 29 | +import pytest |
| 30 | +import rclpy |
| 31 | +from deep_msgs.msg import MultiImage |
| 32 | +from sensor_msgs.msg import CompressedImage |
| 33 | +from std_msgs.msg import Header |
| 34 | +from vision_msgs.msg import Detection2DArray |
| 35 | + |
| 36 | + |
| 37 | +@pytest.mark.launch_test |
| 38 | +def generate_test_description(): |
| 39 | + """Generate launch description for CPU backend test.""" |
| 40 | + from ament_index_python.packages import get_package_share_directory |
| 41 | + |
| 42 | + # Path to base config file |
| 43 | + config_file = os.path.join( |
| 44 | + get_package_share_directory("deep_object_detection"), |
| 45 | + "config", |
| 46 | + "generic_model_params.yaml", |
| 47 | + ) |
| 48 | + |
| 49 | + # Deep object detection node with CPU backend |
| 50 | + detection_node = launch_ros.actions.Node( |
| 51 | + package="deep_object_detection", |
| 52 | + executable="deep_object_detection_node", |
| 53 | + name="deep_object_detection_node", |
| 54 | + parameters=[ |
| 55 | + config_file, |
| 56 | + {"preferred_provider": "cpu"}, |
| 57 | + {"enable_trt_engine_cache": False}, |
| 58 | + ], |
| 59 | + output="screen", |
| 60 | + ) |
| 61 | + |
| 62 | + # Lifecycle manager |
| 63 | + lifecycle_manager = launch_ros.actions.Node( |
| 64 | + package="nav2_lifecycle_manager", |
| 65 | + executable="lifecycle_manager", |
| 66 | + name="lifecycle_manager", |
| 67 | + parameters=[{"node_names": ["deep_object_detection_node"], "autostart": True}], |
| 68 | + output="screen", |
| 69 | + ) |
| 70 | + |
| 71 | + return ( |
| 72 | + launch.LaunchDescription( |
| 73 | + [detection_node, lifecycle_manager, launch_testing.actions.ReadyToTest()] |
| 74 | + ), |
| 75 | + { |
| 76 | + "detection_node": detection_node, |
| 77 | + "lifecycle_manager": lifecycle_manager, |
| 78 | + }, |
| 79 | + ) |
| 80 | + |
| 81 | + |
| 82 | +class TestCPUBackend(unittest.TestCase): |
| 83 | + """Test CPU backend functionality.""" |
| 84 | + |
| 85 | + @classmethod |
| 86 | + def setUpClass(cls): |
| 87 | + """Initialize ROS context.""" |
| 88 | + rclpy.init() |
| 89 | + |
| 90 | + @classmethod |
| 91 | + def tearDownClass(cls): |
| 92 | + """Shutdown ROS context.""" |
| 93 | + rclpy.shutdown() |
| 94 | + |
| 95 | + def setUp(self): |
| 96 | + """Set up test fixtures.""" |
| 97 | + self.node = rclpy.create_node("test_cpu_backend") |
| 98 | + |
| 99 | + def tearDown(self): |
| 100 | + """Clean up test fixtures.""" |
| 101 | + self.node.destroy_node() |
| 102 | + |
| 103 | + def test_node_starts(self, proc_output): |
| 104 | + """Test that the detection node starts successfully.""" |
| 105 | + proc_output.assertWaitFor("Deep object detection node created", timeout=10) |
| 106 | + |
| 107 | + def test_backend_loads(self, proc_output): |
| 108 | + """Test that CPU backend loads.""" |
| 109 | + proc_output.assertWaitFor("Initialized backend using provider: cpu", timeout=15) |
| 110 | + |
| 111 | + def test_model_loads(self, proc_output): |
| 112 | + """Test that the model loads successfully.""" |
| 113 | + # Model loading happens during backend initialization |
| 114 | + # Check for configuration completion which indicates model is loaded |
| 115 | + proc_output.assertWaitFor("Deep object detection node configured", timeout=20) |
| 116 | + |
| 117 | + def test_node_activates(self, proc_output): |
| 118 | + """Test that the node activates successfully.""" |
| 119 | + proc_output.assertWaitFor( |
| 120 | + "Deep object detection node activated", timeout=20 |
| 121 | + ) |
| 122 | + |
| 123 | + def test_detection_with_dummy_multiimage(self, proc_output): |
| 124 | + """Test end-to-end detection by publishing a dummy MultiImage and verifying output.""" |
| 125 | + # Wait for node to be fully activated |
| 126 | + proc_output.assertWaitFor( |
| 127 | + "Deep object detection node activated", timeout=20 |
| 128 | + ) |
| 129 | + time.sleep(1) |
| 130 | + |
| 131 | + # Create publisher for MultiImage messages |
| 132 | + multi_image_pub = self.node.create_publisher( |
| 133 | + MultiImage, "/multi_camera_sync/multi_image_compressed", 10 |
| 134 | + ) |
| 135 | + |
| 136 | + # Variable to track if we received detections |
| 137 | + received_detections = [] |
| 138 | + |
| 139 | + def detection_callback(msg): |
| 140 | + received_detections.append(msg) |
| 141 | + self.node.get_logger().info( |
| 142 | + f"Received detection output with {len(msg.detections)} detections" |
| 143 | + ) |
| 144 | + |
| 145 | + # Create subscriber for detection output with matching QoS |
| 146 | + from rclpy.qos import QoSProfile, SensorDataQoS |
| 147 | + qos_profile = SensorDataQoS() |
| 148 | + self.detection_sub = self.node.create_subscription( |
| 149 | + Detection2DArray, "/detections", detection_callback, qos_profile |
| 150 | + ) |
| 151 | + |
| 152 | + # Wait for publisher/subscriber to be ready |
| 153 | + time.sleep(2) |
| 154 | + |
| 155 | + # Create a dummy compressed image (640x640 RGB JPEG) |
| 156 | + # This matches the expected input size from the config |
| 157 | + dummy_image = np.zeros((640, 640, 3), dtype=np.uint8) |
| 158 | + dummy_image[:, :] = [128, 128, 128] # Gray image |
| 159 | + encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 90] |
| 160 | + _, encoded_image = cv2.imencode(".jpg", dummy_image, encode_param) |
| 161 | + |
| 162 | + # Create MultiImage message with 1 image (for testing) |
| 163 | + # Note: max_batch_size is 6, but node will process when batch timer fires |
| 164 | + multi_image_msg = MultiImage() |
| 165 | + multi_image_msg.header = Header() |
| 166 | + multi_image_msg.header.stamp = self.node.get_clock().now().to_msg() |
| 167 | + multi_image_msg.header.frame_id = "camera" |
| 168 | + |
| 169 | + # Create compressed image message |
| 170 | + compressed_img = CompressedImage() |
| 171 | + compressed_img.header = multi_image_msg.header |
| 172 | + compressed_img.format = "jpeg" |
| 173 | + compressed_img.data = encoded_image.tobytes() |
| 174 | + |
| 175 | + multi_image_msg.images = [compressed_img] |
| 176 | + |
| 177 | + # Publish MultiImage message multiple times to fill batch |
| 178 | + # (max_batch_size=6, but node processes when timer fires with >= max_batch_size) |
| 179 | + self.node.get_logger().info("Publishing dummy MultiImage for CPU detection test") |
| 180 | + for _ in range(6): |
| 181 | + multi_image_pub.publish(multi_image_msg) |
| 182 | + time.sleep(0.01) # Small delay between publishes |
| 183 | + |
| 184 | + # Spin to process callbacks and wait for batch processing |
| 185 | + start_time = time.time() |
| 186 | + timeout = 15.0 |
| 187 | + while len(received_detections) == 0 and (time.time() - start_time) < timeout: |
| 188 | + rclpy.spin_once(self.node, timeout_sec=0.1) |
| 189 | + |
| 190 | + # Verify we received detections (even if empty, the message should be published) |
| 191 | + self.assertGreater( |
| 192 | + len(received_detections), |
| 193 | + 0, |
| 194 | + "Should receive detection output after publishing MultiImage", |
| 195 | + ) |
| 196 | + self.node.get_logger().info( |
| 197 | + f"CPU detection test passed! Received {len(received_detections[0].detections)} detections" |
| 198 | + ) |
0 commit comments