-
Notifications
You must be signed in to change notification settings - Fork 4
/
Copy pathrepublisher.yaml
54 lines (48 loc) · 2.5 KB
/
republisher.yaml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
# Copyright (c) 2024-2025, Personal Robotics Laboratory
# License: BSD 3-Clause. See LICENSE.md file in root directory.
# NOTE: You have to change this node name if you change the node name in the launchfile.
republisher:
ros__parameters:
# The name of the topics to republish from
from_topics:
- /local/camera/aligned_depth_to_color/image_raw/compressedDepth
# The types of topics to republish from
in_topic_types:
- sensor_msgs.msg.CompressedImage
# If the republisher should convert types, specify the output type.
# Currently, the republisher only supports conversions from
# Image->CompressedImage and vice-versa.
out_topic_types:
- sensor_msgs.msg.Image
# The name of the topics to republish to. NOTE: the `prefix` in the launchfile
# must match the below pattern!
to_topics:
- /local/camera/aligned_depth_to_color/depth_octomap
# The target rates (Hz) for the republished topics. Rates <= 0 will publish
# every message.
target_rates:
- 0
# The names of a post-processing functions to apply to the message before
# republishing it. Current options are:
# - temporal: Stores the last `temporal_window_size` images and publishes
# the last image, masking out pixels that are zero in *any* of the images
# in the window.
# - spatial: Applies the opening morphological operation to the mask of
# (non-)zero pixels in the image, with a square kernel of size `spatial_num_pixels`.
# - mask: Applies the mask stored in `mask_relative_path` to the image.
# - threshold: Masks out pixels whose values are outside of the specified
# range. This is intended to be used only with single-channel (e.g., depth) images.
# Any of these post-processing functions can be combined in a comma-separated list.
# If an empty string, no post-processors are applied.
post_processors:
- threshold,mask,temporal,spatial # Apply filters to the depth image for the Octomap
# The binary mask used for "mask" post-processing. This mask will get scaled,
# possibly disproportionately, to the same of the image.
mask_relative_path: model/fork_handle_mask.png
# The size of the temporal window for the "temporal" post-processor.
temporal_window_size: 5
# The size of the square kernel for the "spatial" post-processor.
spatial_num_pixels: 10
# The min/max pixel value to be included in the threshold. For depth images, the units are mm.
threshold_min: 350
threshold_max: 2500