Skip to content

Commit 87df70f

Browse files
committed
fix bug with . needed for parameters again
1 parent 0e04d4c commit 87df70f

File tree

2 files changed

+16
-15
lines changed

2 files changed

+16
-15
lines changed

‎src/ffmpeg_publisher.cpp‎

Lines changed: 14 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -23,37 +23,38 @@ namespace ffmpeg_image_transport
2323
{
2424
using ParameterValue = ParameterDefinition::ParameterValue;
2525
using ParameterDescriptor = ParameterDefinition::ParameterDescriptor;
26+
using ParameterType = rcl_interfaces::msg::ParameterType;
2627

2728
static const ParameterDefinition params[] = {
2829
{ParameterValue("libx264"),
2930
ParameterDescriptor()
3031
.set__name("encoder")
31-
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_STRING)
32+
.set__type(ParameterType::PARAMETER_STRING)
3233
.set__description("ffmpeg encoder to use, see ffmpeg supported encoders")
3334
.set__read_only(false)},
3435
{ParameterValue(""),
3536
ParameterDescriptor()
3637
.set__name("encoder_av_options")
37-
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_STRING)
38+
.set__type(ParameterType::PARAMETER_STRING)
3839
.set__description("comma-separated list of AV options: profile:main,preset:ll")
3940
.set__read_only(false)},
4041
{ParameterValue(""), ParameterDescriptor()
4142
.set__name("pixel_format")
42-
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_STRING)
43+
.set__type(ParameterType::PARAMETER_STRING)
4344
.set__description("pixel format to use for encoding")
4445
.set__read_only(false)},
4546
{ParameterValue(static_cast<int>(-1)),
4647
ParameterDescriptor()
4748
.set__name("qmax")
48-
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER)
49+
.set__type(ParameterType::PARAMETER_INTEGER)
4950
.set__description("max video quantizer scale, see ffmpeg docs")
5051
.set__read_only(false)
5152
.set__integer_range(
5253
{rcl_interfaces::msg::IntegerRange().set__from_value(-1).set__to_value(1024).set__step(1)})},
5354
{ParameterValue(static_cast<int64_t>(-1)),
5455
ParameterDescriptor()
5556
.set__name("bit_rate")
56-
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER)
57+
.set__type(ParameterType::PARAMETER_INTEGER)
5758
.set__description("target bit rate, see ffmpeg docs")
5859
.set__read_only(false)
5960
.set__integer_range({rcl_interfaces::msg::IntegerRange()
@@ -63,7 +64,7 @@ static const ParameterDefinition params[] = {
6364
{ParameterValue(static_cast<int>(-1)),
6465
ParameterDescriptor()
6566
.set__name("gop_size")
66-
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER)
67+
.set__type(ParameterType::PARAMETER_INTEGER)
6768
.set__description("gop size (distance between keyframes)")
6869
.set__read_only(false)
6970
.set__integer_range({rcl_interfaces::msg::IntegerRange()
@@ -73,7 +74,7 @@ static const ParameterDefinition params[] = {
7374
{ParameterValue(static_cast<int>(0)),
7475
ParameterDescriptor()
7576
.set__name("max_b_frames")
76-
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER)
77+
.set__type(ParameterType::PARAMETER_INTEGER)
7778
.set__description("max number of b frames")
7879
.set__read_only(false)
7980
.set__integer_range({rcl_interfaces::msg::IntegerRange()
@@ -82,7 +83,7 @@ static const ParameterDefinition params[] = {
8283
.set__step(1)})},
8384
{ParameterValue(false), ParameterDescriptor()
8485
.set__name("encoder_measure_performance")
85-
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL)
86+
.set__type(ParameterType::PARAMETER_BOOL)
8687
.set__description("enable performance timing")
8788
.set__read_only(false)},
8889
};
@@ -156,10 +157,10 @@ void FFMPEGPublisher::packetReady(
156157
msg->pts = pts;
157158
msg->flags = flags;
158159
msg->data.assign(data, data + sz);
159-
#if defined(IMAGE_TRANSPORT_API_V1) || defined(IMAGE_TRANSPORT_API_V2)
160-
(*publishFunction_)(*msg);
161-
#else
160+
#ifdef IMAGE_TRANSPORT_USE_PUBLISHER_T
162161
(*publishFunction_)->publish(*msg);
162+
#else
163+
(*publishFunction_)(*msg);
163164
#endif
164165
}
165166

@@ -184,13 +185,13 @@ FFMPEGPublisher::QoSType FFMPEGPublisher::initialize(
184185
{
185186
// namespace handling code lifted from compressed_image_transport
186187
#ifdef IMAGE_TRANSPORT_USE_NODEINTERFACE
187-
uint ns_prefix_len = std::string(node.get_node_base_interface()->get_namespace()).length();
188+
uint ns_len = std::string(node.get_node_base_interface()->get_namespace()).length();
188189
#else
189190
uint ns_len = node->get_effective_namespace().length();
191+
#endif
190192
// if a namespace is given (ns_len > 1), then strip one more
191193
// character to avoid a leading "/" that will then become a "."
192194
uint ns_prefix_len = ns_len > 1 ? ns_len + 1 : ns_len;
193-
#endif
194195
std::string param_base_name = base_topic.substr(ns_prefix_len);
195196
std::replace(param_base_name.begin(), param_base_name.end(), '/', '.');
196197
paramNamespace_ = param_base_name + "." + getTransportName() + ".";

‎src/ffmpeg_subscriber.cpp‎

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -85,13 +85,13 @@ void FFMPEGSubscriber::initialize(NodeType node, const std::string & base_topic_
8585
#endif
8686

8787
#ifdef IMAGE_TRANSPORT_USE_NODEINTERFACE
88-
uint ns_prefix_len = std::string(node.get_node_base_interface()->get_namespace()).length();
88+
uint ns_len = std::string(node.get_node_base_interface()->get_namespace()).length();
8989
#else
9090
uint ns_len = node->get_effective_namespace().length();
91+
#endif
9192
// if a namespace is given (ns_len > 1), then strip one more
9293
// character to avoid a leading "/" that will then become a "."
9394
uint ns_prefix_len = ns_len > 1 ? ns_len + 1 : ns_len;
94-
#endif
9595
std::string param_base_name = base_topic.substr(ns_prefix_len);
9696
std::replace(param_base_name.begin(), param_base_name.end(), '/', '.');
9797
paramNamespace_ = param_base_name + "." + getTransportName() + ".";

0 commit comments

Comments
 (0)