Skip to content

Commit 2ccadab

Browse files
committed
precommit
1 parent f174f70 commit 2ccadab

File tree

6 files changed

+37
-47
lines changed

6 files changed

+37
-47
lines changed

deep_object_detection/README.md

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -330,4 +330,3 @@ Launch tests are disabled by default and must be explicitly enabled with `ENABLE
330330
- Model file: `/workspaces/deep_ros/yolov8m.onnx` (for launch tests)
331331
- Class names file: `/workspaces/deep_ros/deep_object_detection/config/coco_classes.txt`
332332
- GPU access: Required for GPU and TensorRT backend tests (local only)
333-

deep_object_detection/test/launch_tests/test_deep_object_detection_cpu_backend.py

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -116,16 +116,12 @@ def test_model_loads(self, proc_output):
116116

117117
def test_node_activates(self, proc_output):
118118
"""Test that the node activates successfully."""
119-
proc_output.assertWaitFor(
120-
"Deep object detection node activated", timeout=20
121-
)
119+
proc_output.assertWaitFor("Deep object detection node activated", timeout=20)
122120

123121
def test_detection_with_dummy_multiimage(self, proc_output):
124122
"""Test end-to-end detection by publishing a dummy MultiImage and verifying output."""
125123
# Wait for node to be fully activated
126-
proc_output.assertWaitFor(
127-
"Deep object detection node activated", timeout=20
128-
)
124+
proc_output.assertWaitFor("Deep object detection node activated", timeout=20)
129125
time.sleep(1)
130126

131127
# Create publisher for MultiImage messages
@@ -143,7 +139,8 @@ def detection_callback(msg):
143139
)
144140

145141
# Create subscriber for detection output with matching QoS
146-
from rclpy.qos import QoSProfile, SensorDataQoS
142+
from rclpy.qos import SensorDataQoS
143+
147144
qos_profile = SensorDataQoS()
148145
self.detection_sub = self.node.create_subscription(
149146
Detection2DArray, "/detections", detection_callback, qos_profile
@@ -176,7 +173,9 @@ def detection_callback(msg):
176173

177174
# Publish MultiImage message multiple times to fill batch
178175
# (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")
176+
self.node.get_logger().info(
177+
"Publishing dummy MultiImage for CPU detection test"
178+
)
180179
for _ in range(6):
181180
multi_image_pub.publish(multi_image_msg)
182181
time.sleep(0.01) # Small delay between publishes

deep_object_detection/test/launch_tests/test_deep_object_detection_gpu_backend.py

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -111,7 +111,9 @@ def test_node_starts(self, proc_output):
111111

112112
def test_backend_loads(self, proc_output):
113113
"""Test that GPU backend plugin loads."""
114-
proc_output.assertWaitFor("Initialized backend using provider: cuda", timeout=15)
114+
proc_output.assertWaitFor(
115+
"Initialized backend using provider: cuda", timeout=15
116+
)
115117

116118
def test_model_loads(self, proc_output):
117119
"""Test that the model loads successfully with GPU backend."""
@@ -121,9 +123,7 @@ def test_model_loads(self, proc_output):
121123

122124
def test_node_activates(self, proc_output):
123125
"""Test that the node activates successfully with GPU backend."""
124-
proc_output.assertWaitFor(
125-
"Deep object detection node activated", timeout=20
126-
)
126+
proc_output.assertWaitFor("Deep object detection node activated", timeout=20)
127127

128128
def test_no_cuda_errors(self, proc_output):
129129
"""Test that there are no CUDA-related errors."""
@@ -134,9 +134,7 @@ def test_no_cuda_errors(self, proc_output):
134134
def test_gpu_detection_with_dummy_multiimage(self, proc_output):
135135
"""Test end-to-end GPU detection by publishing a dummy MultiImage and verifying output."""
136136
# Wait for node to be fully activated
137-
proc_output.assertWaitFor(
138-
"Deep object detection node activated", timeout=20
139-
)
137+
proc_output.assertWaitFor("Deep object detection node activated", timeout=20)
140138
time.sleep(1)
141139

142140
# Create publisher for MultiImage messages
@@ -182,7 +180,9 @@ def detection_callback(msg):
182180
multi_image_msg.images = [compressed_img]
183181

184182
# Publish MultiImage message
185-
self.node.get_logger().info("Publishing dummy MultiImage for GPU detection test")
183+
self.node.get_logger().info(
184+
"Publishing dummy MultiImage for GPU detection test"
185+
)
186186
multi_image_pub.publish(multi_image_msg)
187187

188188
# Spin to process callbacks

deep_object_detection/test/launch_tests/test_deep_object_detection_tensorrt_backend.py

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -108,7 +108,9 @@ def test_node_starts(self, proc_output):
108108
def test_backend_loads(self, proc_output):
109109
"""Test that TensorRT backend loads."""
110110
proc_output.assertWaitFor("Configuring TensorRT execution provider", timeout=15)
111-
proc_output.assertWaitFor("Initialized backend using provider: tensorrt", timeout=20)
111+
proc_output.assertWaitFor(
112+
"Initialized backend using provider: tensorrt", timeout=20
113+
)
112114

113115
def test_tensorrt_provider_configured(self, proc_output):
114116
"""Test that TensorRT execution provider is configured."""
@@ -127,9 +129,7 @@ def test_model_loads(self, proc_output):
127129

128130
def test_node_activates(self, proc_output):
129131
"""Test that the node activates successfully with TensorRT backend."""
130-
proc_output.assertWaitFor(
131-
"Deep object detection node activated", timeout=20
132-
)
132+
proc_output.assertWaitFor("Deep object detection node activated", timeout=20)
133133

134134
def test_no_tensorrt_errors(self, proc_output):
135135
"""Test that there are no TensorRT-related errors."""
@@ -140,9 +140,7 @@ def test_no_tensorrt_errors(self, proc_output):
140140
def test_tensorrt_detection_with_dummy_multiimage(self, proc_output):
141141
"""Test end-to-end TensorRT detection by publishing a dummy MultiImage and verifying output."""
142142
# Wait for node to be fully activated
143-
proc_output.assertWaitFor(
144-
"Deep object detection node activated", timeout=20
145-
)
143+
proc_output.assertWaitFor("Deep object detection node activated", timeout=20)
146144
time.sleep(1)
147145

148146
# Create publisher for MultiImage messages
@@ -188,7 +186,9 @@ def detection_callback(msg):
188186
multi_image_msg.images = [compressed_img]
189187

190188
# Publish MultiImage message
191-
self.node.get_logger().info("Publishing dummy MultiImage for TensorRT detection test")
189+
self.node.get_logger().info(
190+
"Publishing dummy MultiImage for TensorRT detection test"
191+
)
192192
multi_image_pub.publish(multi_image_msg)
193193

194194
# Spin to process callbacks

deep_object_detection/test/test_deep_object_detection_node.cpp

Lines changed: 13 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -75,8 +75,7 @@ class DeepObjectDetectionNodeTestFixture
7575
};
7676

7777
TEST_CASE_METHOD(
78-
DeepObjectDetectionNodeTestFixture, "DeepObjectDetectionNode: Construction and Basic State",
79-
"[node][construction]")
78+
DeepObjectDetectionNodeTestFixture, "DeepObjectDetectionNode: Construction and Basic State", "[node][construction]")
8079
{
8180
rclcpp::NodeOptions options;
8281
auto node = std::make_shared<DeepObjectDetectionNode>(options);
@@ -88,7 +87,8 @@ TEST_CASE_METHOD(
8887
}
8988

9089
TEST_CASE_METHOD(
91-
DeepObjectDetectionNodeTestFixture, "DeepObjectDetectionNode: Parameter Declaration and Defaults",
90+
DeepObjectDetectionNodeTestFixture,
91+
"DeepObjectDetectionNode: Parameter Declaration and Defaults",
9292
"[node][parameters]")
9393
{
9494
rclcpp::NodeOptions options;
@@ -185,16 +185,15 @@ TEST_CASE_METHOD(
185185
}
186186
}
187187

188-
TEST_CASE_METHOD(
189-
DeepObjectDetectionNodeTestFixture, "DeepObjectDetectionNode: Topic Configuration", "[node][topics]")
188+
TEST_CASE_METHOD(DeepObjectDetectionNodeTestFixture, "DeepObjectDetectionNode: Topic Configuration", "[node][topics]")
190189
{
191190
rclcpp::NodeOptions options;
192191
auto node = std::make_shared<DeepObjectDetectionNode>(options);
193192

194193
SECTION("Input topic can be configured")
195194
{
196-
auto params = std::vector<rclcpp::Parameter>{
197-
rclcpp::Parameter("input_topic", "/multi_camera_sync/multi_image_compressed")};
195+
auto params =
196+
std::vector<rclcpp::Parameter>{rclcpp::Parameter("input_topic", "/multi_camera_sync/multi_image_compressed")};
198197
auto result = node->set_parameters(params);
199198
REQUIRE(result[0].successful == true);
200199
REQUIRE(node->get_parameter("input_topic").as_string() == "/multi_camera_sync/multi_image_compressed");
@@ -222,7 +221,8 @@ TEST_CASE_METHOD(
222221
}
223222

224223
TEST_CASE_METHOD(
225-
DeepObjectDetectionNodeTestFixture, "DeepObjectDetectionNode: Preprocessing Parameter Validation",
224+
DeepObjectDetectionNodeTestFixture,
225+
"DeepObjectDetectionNode: Preprocessing Parameter Validation",
226226
"[node][preprocessing]")
227227
{
228228
rclcpp::NodeOptions options;
@@ -231,8 +231,7 @@ TEST_CASE_METHOD(
231231
SECTION("Preprocessing dimensions can be configured")
232232
{
233233
auto params = std::vector<rclcpp::Parameter>{
234-
rclcpp::Parameter("preprocessing.input_width", 1280),
235-
rclcpp::Parameter("preprocessing.input_height", 720)};
234+
rclcpp::Parameter("preprocessing.input_width", 1280), rclcpp::Parameter("preprocessing.input_height", 720)};
236235
auto result = node->set_parameters(params);
237236
REQUIRE(result[0].successful == true);
238237
REQUIRE(result[1].successful == true);
@@ -242,8 +241,7 @@ TEST_CASE_METHOD(
242241

243242
SECTION("Normalization type can be configured")
244243
{
245-
auto params = std::vector<rclcpp::Parameter>{
246-
rclcpp::Parameter("preprocessing.normalization_type", "imagenet")};
244+
auto params = std::vector<rclcpp::Parameter>{rclcpp::Parameter("preprocessing.normalization_type", "imagenet")};
247245
auto result = node->set_parameters(params);
248246
REQUIRE(result[0].successful == true);
249247
REQUIRE(node->get_parameter("preprocessing.normalization_type").as_string() == "imagenet");
@@ -259,7 +257,8 @@ TEST_CASE_METHOD(
259257
}
260258

261259
TEST_CASE_METHOD(
262-
DeepObjectDetectionNodeTestFixture, "DeepObjectDetectionNode: Postprocessing Parameter Validation",
260+
DeepObjectDetectionNodeTestFixture,
261+
"DeepObjectDetectionNode: Postprocessing Parameter Validation",
263262
"[node][postprocessing]")
264263
{
265264
rclcpp::NodeOptions options;
@@ -291,8 +290,7 @@ TEST_CASE_METHOD(
291290
}
292291

293292
TEST_CASE_METHOD(
294-
DeepObjectDetectionNodeTestFixture, "DeepObjectDetectionNode: Execution Provider Configuration",
295-
"[node][provider]")
293+
DeepObjectDetectionNodeTestFixture, "DeepObjectDetectionNode: Execution Provider Configuration", "[node][provider]")
296294
{
297295
rclcpp::NodeOptions options;
298296
auto node = std::make_shared<DeepObjectDetectionNode>(options);

deep_tools/camera_sync/include/camera_sync/multi_camera_sync_node.hpp

Lines changed: 1 addition & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -15,13 +15,6 @@
1515
#ifndef CAMERA_SYNC__MULTI_CAMERA_SYNC_NODE_HPP_
1616
#define CAMERA_SYNC__MULTI_CAMERA_SYNC_NODE_HPP_
1717

18-
#if __has_include(<cv_bridge/cv_bridge.hpp>)
19-
#include <cv_bridge/cv_bridge.hpp>
20-
#elif __has_include(<cv_bridge/cv_bridge.h>)
21-
#include <cv_bridge/cv_bridge.h>
22-
#else
23-
#error "cv_bridge headers not found"
24-
#endif
2518
#include <message_filters/subscriber.h>
2619
#include <message_filters/sync_policies/approximate_time.h>
2720
#include <message_filters/synchronizer.h>
@@ -31,6 +24,7 @@
3124
#include <string>
3225
#include <vector>
3326

27+
#include <cv_bridge/cv_bridge.hpp>
3428
#include <image_transport/image_transport.hpp>
3529
#include <rclcpp/rclcpp.hpp>
3630
#include <sensor_msgs/msg/compressed_image.hpp>

0 commit comments

Comments
 (0)