Skip to content

Commit 5bc9171

Browse files
authored
Quick build fix (#29)
1 parent 85d08ea commit 5bc9171

File tree

5 files changed

+7
-16
lines changed

5 files changed

+7
-16
lines changed

deep_tools/camera_sync/CMakeLists.txt

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,6 @@ find_package(rclcpp_lifecycle REQUIRED)
2424
find_package(rclcpp_components REQUIRED)
2525
find_package(lifecycle_msgs REQUIRED)
2626
find_package(sensor_msgs REQUIRED)
27-
find_package(message_filters REQUIRED)
2827
find_package(image_transport REQUIRED)
2928
find_package(cv_bridge REQUIRED)
3029
find_package(deep_msgs REQUIRED)
@@ -46,7 +45,6 @@ target_link_libraries(multi_camera_sync_component
4645
rclcpp_components::component_manager
4746
lifecycle_msgs::lifecycle_msgs__rosidl_typesupport_cpp
4847
sensor_msgs::sensor_msgs__rosidl_typesupport_cpp
49-
message_filters::message_filters
5048
image_transport::image_transport
5149
cv_bridge::cv_bridge
5250
deep_msgs::deep_msgs__rosidl_typesupport_cpp

deep_tools/camera_sync/DEVELOPING.md

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -17,11 +17,6 @@ The Macro:
1717
#endif
1818
```
1919

20-
### 2. Message Filters Synchronization Limitation
21-
**Problem**: `message_filters::Synchronizer` requires compile-time known number of topics.
22-
- **Limitation**: Cannot dynamically sync N cameras - must handle 2-6 cameras with separate synchronizers
23-
- **Implementation**: Switch statement creates different sync policies for each camera count
24-
2520
## Architecture Notes
2621
- **Component-only**: No standalone executable - use component loading only which is ideal to allow for IPC (zero-copy)
2722
- **Dual Mode**: Supports both raw and compressed image synchronization

deep_tools/camera_sync/README.md

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,10 @@
11
# Multi-Camera Synchronization Node
22

3-
A ROS2 node that uses message filters to time-synchronize N camera image messages, supporting both compressed and raw images.
3+
A ROS2 node that uses custom buffering to time-synchronize N camera image messages, supporting both compressed and raw images.
44

55
## Features
66

7-
- **Flexible camera count**: Supports 2-6 cameras simultaneously
7+
- **Flexible camera count**: Supports 2-12 cameras simultaneously
88
- **Image format support**: Works with both `sensor_msgs/Image` (raw) and `sensor_msgs/CompressedImage`
99
- **Configurable synchronization**: Adjustable time tolerance and queue sizes
1010
- **Real-time monitoring**: Synchronization statistics and rate monitoring
@@ -18,7 +18,7 @@ A ROS2 node that uses message filters to time-synchronize N camera image message
1818
| `camera_names` | string[] | `[]` | Names for cameras (auto-generated if empty) |
1919
| `use_compressed` | bool | `false` | Use compressed images instead of raw RGB |
2020
| `sync_tolerance_ms` | double | `50.0` | Max time difference for sync (milliseconds) |
21-
| `queue_size` | int | `10` | Message filter queue size |
21+
| `queue_size` | int | `10` | Buffer queue size |
2222
| `publish_sync_info` | bool | `true` | Publish synchronization statistics |
2323

2424
## Usage
@@ -35,10 +35,10 @@ All configuration changes can be passed through CLI. Here are some example argum
3535

3636
## How It Works
3737

38-
The node uses ROS2 message filters with approximate time synchronization policy to match images from multiple cameras based on their timestamps. Key components:
38+
The node uses ROS2 buffers with approximate time synchronization policy to match images from multiple cameras based on their timestamps. Key components:
3939

4040
1. **Message Subscribers**: Creates subscribers for each camera topic
41-
2. **Synchronizer**: Uses `message_filters::sync_policies::ApproximateTime` to match messages
41+
2. **Synchronizer**: Stores buffers from first subscriber and matches with other subscribers within timestamp sync tolerance to match messages
4242
3. **Callback & Publishing**: Creates MultiImage/MultiImageCompressed msgs with timestamp to batch the camera images together
4343
4. **Statistics**: Tracks synchronization rate and timing spread
4444

@@ -67,7 +67,6 @@ Example log output:
6767

6868
- `rclcpp` - ROS2 C++ client library
6969
- `sensor_msgs` - Standard sensor message types
70-
- `message_filters` - Time synchronization utilities
7170
- `image_transport` - Efficient image transmission
7271

7372
## Limitations

deep_tools/camera_sync/package.xml

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,6 @@
1212
<depend>rclcpp_lifecycle</depend>
1313
<depend>lifecycle_msgs</depend>
1414
<depend>sensor_msgs</depend>
15-
<depend>message_filters</depend>
1615
<depend>image_transport</depend>
1716
<depend>cv_bridge</depend>
1817
<depend>deep_msgs</depend>

deep_tools/camera_sync/src/multi_camera_sync_node.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -430,7 +430,7 @@ void MultiCameraSyncNode::tryPublishSyncedRawImages()
430430
// Publish synced images
431431
RCLCPP_DEBUG(this->get_logger(), "Publishing synced raw images (sync count: %ld)", ++sync_count_);
432432
processSynchronizedImages(timestamps);
433-
auto raw_msg = createMultiImageMessage<sensor_msgs::msg::Image, deep_msgs::msg::MultiImageRaw>(synced_images);
433+
auto raw_msg = createMultiImageMessage<sensor_msgs::msg::Image, deep_msgs::msg::MultiImage>(synced_images);
434434
multi_image_raw_pub_->publish(raw_msg);
435435
}
436436

@@ -534,7 +534,7 @@ void MultiCameraSyncNode::tryPublishSyncedCompressedImages()
534534
RCLCPP_DEBUG(this->get_logger(), "Publishing synced compressed images (sync count: %ld)", ++sync_count_);
535535
processSynchronizedImages(timestamps);
536536
auto compressed_msg =
537-
createMultiImageMessage<sensor_msgs::msg::CompressedImage, deep_msgs::msg::MultiImage>(synced_images);
537+
createMultiImageMessage<sensor_msgs::msg::CompressedImage, deep_msgs::msg::MultiImageCompressed>(synced_images);
538538
multi_image_compressed_pub_->publish(compressed_msg);
539539
}
540540

0 commit comments

Comments
 (0)