Skip to content

Commit a8d42d6

Browse files
committed
rename map param to decoders, drop dot prefix, deal with humble brokenness
1 parent 646b248 commit a8d42d6

File tree

10 files changed

+112
-86
lines changed

10 files changed

+112
-86
lines changed

CMakeLists.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,9 @@ find_package(sensor_msgs REQUIRED)
3737
find_package(std_msgs REQUIRED)
3838

3939

40+
if(${image_transport_VERSION} VERSION_GREATER_EQUAL "6.0.0")
41+
add_definitions(-DIMAGE_TRANSPORT_RESOLVES_BASE_TOPIC)
42+
endif()
4043
if(${image_transport_VERSION} VERSION_GREATER_EQUAL "6.3.0")
4144
add_definitions(-DIMAGE_TRANSPORT_USE_QOS)
4245
endif()

README.md

Lines changed: 20 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,7 @@ Here is a list of the available encoding parameters:
7575
- ``encoder``: the libav (ffmpeg) encoder being used. The default is ``libx264``, which is on-CPU unaccelerated encoding.
7676
Depending on your hardware, your encoding options may include the hardware accelerated ``h264_nvenc`` or ``h264_vaapi``.
7777
You can list all available encoders with ``ffmpeg --codecs``. In the h264 row, look for ``(encoders)``.
78-
- ``av_options``: default is empty (""). Comma-separeted list of valid
78+
- ``encoder_av_options``: default is empty (""). Comma-separeted list of valid
7979
libav options in the form of (key:value), e.g.:``'preset:ll,profile:main,crf:0'``.
8080
See the ffmpeg documentation for [more](https://trac.ffmpeg.org/wiki/Encode/H.264).
8181
- ``gop_size``: The number of frames between keyframes. Default: 10.
@@ -87,34 +87,39 @@ Here is a list of the available encoding parameters:
8787
- ``qmax``: Max quantization rate. Defaults to 10.
8888
See [ffmpeg documentation](https://www.ffmpeg.org/ffmpeg-codecs.html).
8989
The larger this number, the worse the image looks, and the more efficient the encoding.
90-
- ``measure_performance``: For performance debugging (developers only). Defaults to false.
91-
- ``performance_interval``: How many frames to wait between logging performance data. Ignore.
90+
- ``encoder_measure_performance``: For performance debugging (developers only). Defaults to false.
9291

9392
The parameters are under the ``ffmpeg`` variable block. If you launch
9493
your publisher node (camera driver), you can give it a parameter list on the way like so:
9594
```
96-
parameters=[{'.image_raw.ffmpeg.encoder': 'hevc_nvenc',
97-
'.image_raw.ffmpeg.av_options': 'preset:ll,profile:main,crf:0'}]
95+
parameters=[{'image_raw.ffmpeg.encoder': 'hevc_nvenc',
96+
'image_raw.ffmpeg.encoder_av_options': 'preset:ll,profile:main,crf:0'}]
9897
```
9998
See the example launch file for a V4L USB camera (``usb_camera.launch.py``).
10099
If the above parameter settings don't work, use the ``ros2 param dump <your_node_name>``
101100
command to find out what the proper parameter path is.
102101

103102
### Subscriber (viewer)
104103

105-
The subscriber has only one parameter (``map.<some_encoding>``), which is the map between a codec and a comma-separated list of libav decoders that can be used for decoding.
106-
If you don't set the map parameter, the Subscriber plugin will try to decode with a default set of libav decoders that support the appropriate codec.
107-
The map is exposed as the ROS``ffmpeg.map`` parameter, which is prefixed by the image base name, e.g. ``camera.image_raw``.
108-
The easiest way to find the exact naming of the parameter is to run the node and to use ``ros2 param list`` to find the ``ffmpeg.map`` parameter.
104+
- ``decoder_av_options`` comma-separated list of libav options to pass
105+
to the decoder, like ``foo:bar,foobar:baz``. Default: empty string.
106+
- ``decoder_measure_performance`` enables performance
107+
measurements. Default: false.
108+
- ``decoders.<codec>.<av_source_pixel_format>.<cv_bridge_target_format>.<original_ros_encoding>`` specifies the decoders to use for a given FFMPEGPacket encoding.
109+
If no decoders are specified for the full encoding, a less specific parameter will be tested, i.e. ``decoders.<codec>.<av_source_pixel_format>.<cv_bridge_target_format>``, then ``decoders.<codec>.<av_source_pixel_format>``, and finally ``decoders.<codec>``.
110+
If all parameters are found to be empty, the Subscriber plugin will try to decode with a default set of libav decoders that support the appropriate codec.
111+
112+
All parameters are prefixed again by the image topic and the transport, just like for the publisher node.
113+
The easiest way to find the exact naming of the parameter is to run the node and to use ``ros2 param list`` to find the ``ffmpeg.decoders`` parameter.
109114
Please also refer to the republisher launch script example.
110115

111116
Typically ROS2 parameters are passed to a node by *initializing* the parameters before launching the node, and the node then reads the parameter when it *declares* the parameter.
112117
Unfortunately, this route is not available for the popular ``rqt`` based suite of image viewing tools such as ``rqt_image_view``, since ``rqt`` does not read command line arguments and therefore no parameters can be initialized. The only workaround there is to:
113118
1) start e.g. ``rqt_image_view``
114-
2) select the ffmpeg image transport in the drop down box. This will *declare* the ``map`` parameter so you can set it in the next step.
119+
2) select the ffmpeg image transport in the drop down box. This will *declare* the ``decoders`` parameter so you can set it in the next step.
115120
3) find the node name with ``ros2 node list`` and set the parameter using something like
116-
``ros2 param set <name_of_your_viewer_node> camera.image_raw.ffmpeg.map.hevc hevc_cuvid``. This assumes your viewer node is subscribing to the topic ``/camera/image_raw/ffmpeg``.
117-
4) again using the drop down box, switch to another image transport and back to ffmpeg. This will cause the ffmpeg transport plugin to apply the updated ``map`` parameter.
121+
``ros2 param set <name_of_your_viewer_node> camera.image_raw.ffmpeg.decoders.hevc hevc_cuvid``. This assumes your viewer node is subscribing to the topic ``/camera/image_raw/ffmpeg``.
122+
4) again using the drop down box, switch to another image transport and back to ffmpeg. This will cause the ffmpeg transport plugin to apply the updated ``decoders`` parameter.
118123

119124
### Republishing
120125

@@ -127,19 +132,19 @@ For example to first try to decode incoming ``hevc`` packets with the ``hevc_cuv
127132

128133
- ROS 2 Humble:
129134
```
130-
ros2 run image_transport republish ffmpeg in/ffmpeg:=image_raw/ffmpeg raw out:=image_raw/uncompressed --ros-args -p "ffmpeg_image_transport.map.hevc:=hevc_cuvid,hevc"
135+
ros2 run image_transport republish ffmpeg in/ffmpeg:=image_raw/ffmpeg raw out:=image_raw/uncompressed --ros-args -p "ffmpeg_image_transport.decoders.hevc:=hevc_cuvid,hevc"
131136
```
132137
- ROS 2 Jazzy:
133138
```
134-
ros2 run image_transport republish --ros-args -p in_transport:=ffmpeg -p out_transport:=raw --remap in/ffmpeg:=image_raw/ffmpeg --remap out:=image_raw/uncompressed -p "ffmpeg_image_transport.map.hevc:=hevc_cuvid,hevc"
139+
ros2 run image_transport republish --ros-args -p in_transport:=ffmpeg -p out_transport:=raw --remap in/ffmpeg:=image_raw/ffmpeg --remap out:=image_raw/uncompressed -p "ffmpeg_image_transport.decoders.hevc:=hevc_cuvid,hevc"
135140
```
136141

137142
Note: The commands below use the Humble syntax and need to be changed as shown here for Jazzy.
138143

139144
Republishing is generally not necessary so long as publisher and subscriber both properly use
140145
an image transport.
141146
Some nodes however, notably the rosbag player, do not support a proper transport, making republishing necessary.
142-
Please use the republishing launch file (``republish.launch.py``) in this repo as a starting point for how to set the decoding map.
147+
Please use the republishing launch file (``republish.launch.py``) in this repo as a starting point for how to set the decoders parameter.
143148

144149
#### Republishing raw images from rosbags in ffmpeg format
145150

include/ffmpeg_image_transport/ffmpeg_publisher.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -64,14 +64,14 @@ class FFMPEGPublisher : public FFMPEGPublisherPlugin
6464
uint32_t width, uint32_t height, uint64_t pts, uint8_t flags, uint8_t * data, size_t sz);
6565

6666
QoSType initialize(rclcpp::Node * node, const std::string & base_name, QoSType custom_qos);
67-
void declareParameter(
68-
rclcpp::Node * node, const std::string & base_name, const ParameterDefinition & definition);
67+
void declareParameter(rclcpp::Node * node, const ParameterDefinition & definition);
6968
void handleAVOptions(const std::string & opt);
7069
// variables ---------
7170
rclcpp::Logger logger_;
7271
const PublisherTFn * publishFunction_{NULL};
7372
ffmpeg_encoder_decoder::Encoder encoder_;
7473
uint32_t frameCounter_{0};
74+
std::string paramNamespace_;
7575
// ---------- configurable parameters
7676
int performanceInterval_{175}; // num frames between perf printouts
7777
bool measurePerformance_{false};

include/ffmpeg_image_transport/ffmpeg_subscriber.hpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -61,16 +61,15 @@ class FFMPEGSubscriber : public FFMPEGSubscriberPlugin
6161
void frameReady(const ImageConstPtr & img, bool /*isKeyFrame*/) const;
6262
void initialize(rclcpp::Node * node, const std::string & base_topic);
6363
std::string getDecodersFromMap(const std::string & encoding);
64-
void declareParameter(
65-
rclcpp::Node * node, const std::string & base_name, const ParameterDefinition & definition);
64+
void declareParameter(rclcpp::Node * node, const ParameterDefinition & definition);
6665
void handleAVOptions(const std::string & opt);
6766
// -------------- variables
6867
rclcpp::Logger logger_;
6968
rclcpp::Node * node_{nullptr};
7069
ffmpeg_encoder_decoder::Decoder decoder_;
7170
std::string decoderType_;
7271
const Callback * userCallback_{nullptr};
73-
std::string param_namespace_;
72+
std::string paramNamespace_;
7473
};
7574
} // namespace ffmpeg_image_transport
7675
#endif // FFMPEG_IMAGE_TRANSPORT__FFMPEG_SUBSCRIBER_HPP_

include/ffmpeg_image_transport/parameter_definition.hpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,8 +25,7 @@ struct ParameterDefinition
2525
using ParameterDescriptor = rcl_interfaces::msg::ParameterDescriptor;
2626
using ParameterValue = rclcpp::ParameterValue;
2727

28-
rclcpp::ParameterValue declare(
29-
rclcpp::Node * node, const std::string & baseName, const std::string & transportName) const;
28+
rclcpp::ParameterValue declare(rclcpp::Node * node, const std::string & paramBase) const;
3029
// ---- variables
3130
ParameterValue defaultValue;
3231
ParameterDescriptor descriptor;

launch/republish.launch.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -40,10 +40,10 @@ def launch_setup(context, *args, **kwargs):
4040
{
4141
"in_transport": LaunchConfig("in_transport"),
4242
"out_transport": LaunchConfig("out_transport"),
43-
".image_raw.ffmpeg.map.h264": "h264,h264_cuvid,h264_qsv,h264_v4l2m2m",
44-
".image_raw.ffmpeg.map.hevc": "hevc_cuvid,hevc_qsv,hevc_v4l2m2m,hevc",
45-
".image_raw.ffmpeg.map.av1": "libaom-av1,av1_cuvid,av1,av1_qs,libdav1d",
46-
".image_raw.ffmpeg.measure_performance": False,
43+
"image_raw.ffmpeg.decoders.h264": "h264,h264_cuvid,h264_qsv,h264_v4l2m2m",
44+
"image_raw.ffmpeg.decoders.hevc": "hevc_cuvid,hevc_qsv,hevc_v4l2m2m,hevc",
45+
"image_raw.ffmpeg.decoders.av1": "libaom-av1,av1_cuvid,av1,av1_qs,libdav1d",
46+
"image_raw.ffmpeg.decoder_measure_performance": False,
4747
}
4848
],
4949
# remap the 'in' topic to the topic under which the

src/ffmpeg_publisher.cpp

Lines changed: 13 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ static const ParameterDefinition params[] = {
3232
.set__read_only(false)},
3333
{ParameterValue(""),
3434
ParameterDescriptor()
35-
.set__name("av_options")
35+
.set__name("encoder_av_options")
3636
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_STRING)
3737
.set__description("comma-separated list of AV options: profile:main,preset:ll")
3838
.set__read_only(false)},
@@ -80,20 +80,10 @@ static const ParameterDefinition params[] = {
8080
.set__to_value(std::numeric_limits<int>::max())
8181
.set__step(1)})},
8282
{ParameterValue(false), ParameterDescriptor()
83-
.set__name("measure_performance")
83+
.set__name("encoder_measure_performance")
8484
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL)
8585
.set__description("enable performance timing")
8686
.set__read_only(false)},
87-
{ParameterValue(static_cast<int>(175)),
88-
ParameterDescriptor()
89-
.set__name("performance_interval")
90-
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER)
91-
.set__description("after how many frames to print perf info")
92-
.set__read_only(false)
93-
.set__integer_range({rcl_interfaces::msg::IntegerRange()
94-
.set__from_value(1)
95-
.set__to_value(std::numeric_limits<int>::max())
96-
.set__step(1)})},
9787
};
9888

9989
FFMPEGPublisher::FFMPEGPublisher() : logger_(rclcpp::get_logger("FFMPEGPublisher")) {}
@@ -110,16 +100,15 @@ void FFMPEGPublisher::shutdown()
110100

111101
// This code was lifted from compressed_image_transport
112102

113-
void FFMPEGPublisher::declareParameter(
114-
rclcpp::Node * node, const std::string & base_name, const ParameterDefinition & definition)
103+
void FFMPEGPublisher::declareParameter(rclcpp::Node * node, const ParameterDefinition & definition)
115104
{
116105
// transport scoped parameter (e.g. image_raw.compressed.format)
117-
const auto v = definition.declare(node, base_name, getTransportName());
106+
const auto v = definition.declare(node, paramNamespace_);
118107
const auto & n = definition.descriptor.name;
119108
if (n == "encoder") {
120109
encoder_.setEncoder(v.get<std::string>());
121110
RCLCPP_INFO_STREAM(logger_, "using libav encoder: " << v.get<std::string>());
122-
} else if (n == "av_options") {
111+
} else if (n == "encoder_av_options") {
123112
handleAVOptions(v.get<std::string>());
124113
} else if (n == "pixel_format") {
125114
encoder_.setAVSourcePixelFormat(v.get<std::string>());
@@ -131,11 +120,9 @@ void FFMPEGPublisher::declareParameter(
131120
encoder_.setBitRate(v.get<int>());
132121
} else if (n == "gop_size") {
133122
encoder_.setGOPSize(v.get<int>());
134-
} else if (n == "measure_performance") {
123+
} else if (n == "encoder_measure_performance") {
135124
measurePerformance_ = v.get<bool>();
136125
encoder_.setMeasurePerformance(v.get<bool>());
137-
} else if (n == "performance_interval") {
138-
performanceInterval_ = v.get<int>();
139126
} else {
140127
RCLCPP_ERROR_STREAM(logger_, "unknown parameter: " << n);
141128
}
@@ -196,12 +183,16 @@ FFMPEGPublisher::QoSType FFMPEGPublisher::initialize(
196183
rclcpp::Node * node, const std::string & base_topic, QoSType custom_qos)
197184
{
198185
// namespace handling code lifted from compressed_image_transport
199-
const uint ns_len = node->get_effective_namespace().length();
200-
std::string param_base_name = base_topic.substr(ns_len);
186+
uint ns_len = node->get_effective_namespace().length();
187+
// if a namespace is given (ns_len > 1), then strip one more
188+
// character to avoid a leading "/" that will then become a "."
189+
uint ns_prefix_len = ns_len > 1 ? ns_len + 1 : ns_len;
190+
std::string param_base_name = base_topic.substr(ns_prefix_len);
201191
std::replace(param_base_name.begin(), param_base_name.end(), '/', '.');
192+
paramNamespace_ = param_base_name + "." + getTransportName() + ".";
202193

203194
for (const auto & p : params) {
204-
declareParameter(node, param_base_name, p);
195+
declareParameter(node, p);
205196
}
206197
// bump queue size to 2 * distance between keyframes
207198
#ifdef IMAGE_TRANSPORT_USE_QOS

src/ffmpeg_subscriber.cpp

Lines changed: 28 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -30,12 +30,12 @@ using ffmpeg_encoder_decoder::utils::split_by_char;
3030

3131
static const ParameterDefinition params[] = {
3232
{PValue(""), PDescriptor()
33-
.set__name("av_options")
33+
.set__name("decoder_av_options")
3434
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_STRING)
3535
.set__description("comma-separated list of AV options: delay:0")
3636
.set__read_only(false)},
3737
{PValue(false), PDescriptor()
38-
.set__name("measure_performance")
38+
.set__name("decoder_measure_performance")
3939
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL)
4040
.set__description("enable performance timing")
4141
.set__read_only(false)}};
@@ -83,28 +83,35 @@ void FFMPEGSubscriber::subscribeImpl(
8383
#endif
8484
}
8585
#endif
86-
void FFMPEGSubscriber::initialize(rclcpp::Node * node, const std::string & base_topic)
86+
void FFMPEGSubscriber::initialize(rclcpp::Node * node, const std::string & base_topic_o)
8787
{
8888
node_ = node;
89+
#ifdef IMAGE_TRANSPORT_RESOLVES_BASE_TOPIC
90+
const std::string base_topic = base_topic_o;
91+
#else
92+
const std::string base_topic =
93+
node_->get_node_topics_interface()->resolve_topic_name(base_topic_o);
94+
#endif
8995
uint ns_len = node_->get_effective_namespace().length();
90-
std::string param_base_name = base_topic.substr(ns_len);
96+
// if a namespace is given (ns_len > 1), then strip one more
97+
// character to avoid a leading "/" that will then become a "."
98+
uint ns_prefix_len = ns_len > 1 ? ns_len + 1 : ns_len;
99+
std::string param_base_name = base_topic.substr(ns_prefix_len);
91100
std::replace(param_base_name.begin(), param_base_name.end(), '/', '.');
92-
param_namespace_ = param_base_name + "." + getTransportName() + ".";
101+
paramNamespace_ = param_base_name + "." + getTransportName() + ".";
93102

94103
for (const auto & p : params) {
95-
declareParameter(node, param_base_name, p);
104+
declareParameter(node, p);
96105
}
97106
}
98107

99-
void FFMPEGSubscriber::declareParameter(
100-
rclcpp::Node * node, const std::string & base_name, const ParameterDefinition & definition)
108+
void FFMPEGSubscriber::declareParameter(rclcpp::Node * node, const ParameterDefinition & definition)
101109
{
102-
// transport scoped parameter (e.g. image_raw.compressed.format)
103-
const auto v = definition.declare(node, base_name, getTransportName());
110+
const auto v = definition.declare(node, paramNamespace_);
104111
const auto & n = definition.descriptor.name;
105-
if (n == "av_options") {
112+
if (n == "decoder_av_options") {
106113
handleAVOptions(v.get<std::string>());
107-
} else if (n == "measure_performance") {
114+
} else if (n == "decoder_measure_performance") {
108115
decoder_.setMeasurePerformance(v.get<bool>());
109116
} else {
110117
RCLCPP_ERROR_STREAM(logger_, "unknown parameter: " << n);
@@ -115,23 +122,20 @@ std::string FFMPEGSubscriber::getDecodersFromMap(const std::string & encoding)
115122
{
116123
const auto x = split_by_char(encoding, ';');
117124
std::string decoders;
125+
// successively create parameters that are more and more generic,
126+
// i.e. hevc.yuv
118127
for (int i = static_cast<int>(x.size()); i > 0; --i) {
119128
std::string p_name;
120129
for (int j = 0; j < i; j++) {
121130
p_name += "." + x[j];
122131
}
123-
const std::string key = param_namespace_ + "map" + p_name;
124-
rcl_interfaces::msg::ParameterDescriptor pd;
125-
pd.set__name(p_name)
126-
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_STRING)
127-
.set__description("decoders for encoding: " + p_name)
128-
.set__read_only(false);
129-
try {
130-
decoders = node_->declare_parameter(key, rclcpp::ParameterValue(""), pd).get<std::string>();
131-
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
132-
RCLCPP_DEBUG_STREAM(logger_, "was previously declared: " << p_name);
133-
decoders = node_->get_parameter_or<std::string>(key, "");
134-
}
132+
ParameterDefinition pdef{
133+
PValue(""), PDescriptor()
134+
.set__name("decoders" + p_name)
135+
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_STRING)
136+
.set__description("decoders for encoding: " + p_name)
137+
.set__read_only(false)};
138+
decoders = pdef.declare(node_, paramNamespace_).get<std::string>();
135139
if (!decoders.empty()) {
136140
break;
137141
}

src/parameter_definition.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,11 +18,12 @@
1818
namespace ffmpeg_image_transport
1919
{
2020
rclcpp::ParameterValue ParameterDefinition::declare(
21-
rclcpp::Node * node, const std::string & baseName, const std::string & transportName) const
21+
rclcpp::Node * node, const std::string & paramBase) const
2222
{
2323
// transport scoped parameter (e.g. image_raw.compressed.format)
24-
const std::string paramName = baseName + "." + transportName + "." + descriptor.name;
24+
const std::string paramName = paramBase + descriptor.name;
2525
rclcpp::ParameterValue v;
26+
std::cout << "declaring parameter: " << paramName << std::endl;
2627
try {
2728
v = node->declare_parameter(paramName, defaultValue, descriptor);
2829
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {

0 commit comments

Comments
 (0)