Skip to content

Commit 2cc1245

Browse files
committed
adjust to latest image transport API changes
1 parent 24e90f7 commit 2cc1245

File tree

7 files changed

+56
-12
lines changed

7 files changed

+56
-12
lines changed

‎CMakeLists.txt‎

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,12 @@ endif()
1515
if(DEFINED ENV{ROS_DISTRO})
1616
if($ENV{ROS_DISTRO} STREQUAL "foxy" OR
1717
$ENV{ROS_DISTRO} STREQUAL "galactic")
18-
add_definitions(-DUSE_OLD_IMAGE_TRANSPORT_API)
19-
endif()
18+
add_definitions(-DIMAGE_TRANSPORT_API_V1)
19+
elseif($ENV{ROS_DISTRO} STREQUAL "humble")
20+
add_definitions(-DIMAGE_TRANSPORT_API_V2)
21+
else()
22+
add_definitions(-DIMAGE_TRANSPORT_API_V3)
23+
endif()
2024
else()
2125
message(ERROR "ROS_DISTRO environment variable is not set!")
2226
endif()

‎README.md‎

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,12 @@ and therefore must be installed on both sides to be useful.
1717

1818
## Supported systems
1919

20-
Tested on Ubuntu 20.04 and ROS2 Galactic.
20+
Tested on:
21+
22+
- Ubuntu 20.04 and ROS2 Galactic
23+
- Ubuntu 22.04 and ROS2 Humble
24+
25+
Should also compile under ROS2 Iron.
2126

2227
## Installation
2328

‎include/ffmpeg_image_transport/ffmpeg_publisher.hpp‎

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,13 +34,19 @@ class FFMPEGPublisher : public FFMPEGPublisherPlugin
3434
std::string getTransportName() const override { return "ffmpeg"; }
3535

3636
protected:
37+
#if defined(IMAGE_TRANSPORT_API_V1) || defined(IMAGE_TRANSPORT_API_V2)
3738
void advertiseImpl(
3839
rclcpp::Node * node, const std::string & base_topic, rmw_qos_profile_t custom_qos) override;
39-
40+
#else
41+
void advertiseImpl(
42+
rclcpp::Node * node, const std::string & base_topic, rmw_qos_profile_t custom_qos,
43+
rclcpp::PublisherOptions opt) override;
44+
#endif
4045
void publish(const Image & message, const PublishFn & publish_fn) const override;
4146

4247
private:
4348
void packetReady(const FFMPEGPacketConstPtr & pkt);
49+
rmw_qos_profile_t initialize(rclcpp::Node * node, rmw_qos_profile_t custom_qos);
4450
// variables ---------
4551
rclcpp::Logger logger_;
4652
const PublishFn * publishFunction_{NULL};

‎include/ffmpeg_image_transport/ffmpeg_subscriber.hpp‎

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -36,17 +36,15 @@ class FFMPEGSubscriber : public FFMPEGSubscriberPlugin
3636

3737
protected:
3838
void internalCallback(const FFMPEGPacketConstPtr & msg, const Callback & user_cb) override;
39+
40+
#ifdef IMAGE_TRANSPORT_API_V1
3941
void subscribeImpl(
4042
rclcpp::Node * node, const std::string & base_topic, const Callback & callback,
4143
rmw_qos_profile_t custom_qos) override;
42-
43-
#ifndef USE_OLD_IMAGE_TRANSPORT_API
44+
#else
4445
void subscribeImpl(
4546
rclcpp::Node * node, const std::string & base_topic, const Callback & callback,
46-
rmw_qos_profile_t custom_qos, rclcpp::SubscriptionOptions) override
47-
{
48-
subscribeImpl(node, base_topic, callback, custom_qos);
49-
}
47+
rmw_qos_profile_t custom_qos, rclcpp::SubscriptionOptions) override;
5048
#endif
5149

5250
private:

‎package.xml‎

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
<buildtool_depend>ament_cmake_ros</buildtool_depend>
1818
<buildtool_depend>ament_cmake_clang_format</buildtool_depend>
1919
<buildtool_depend>pkg-config</buildtool_depend>
20+
<buildtool_depend>ros_environment</buildtool_depend>
2021

2122
<depend>cv_bridge</depend>
2223
<depend>image_transport</depend>

‎src/ffmpeg_publisher.cpp‎

Lines changed: 17 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -27,8 +27,24 @@ FFMPEGPublisher::~FFMPEGPublisher() {}
2727

2828
void FFMPEGPublisher::packetReady(const FFMPEGPacketConstPtr & pkt) { (*publishFunction_)(*pkt); }
2929

30+
#if defined(IMAGE_TRANSPORT_API_V1) || defined(IMAGE_TRANSPORT_API_V2)
3031
void FFMPEGPublisher::advertiseImpl(
3132
rclcpp::Node * node, const std::string & base_topic, rmw_qos_profile_t custom_qos)
33+
{
34+
auto qos = initialize(node, custom_qos);
35+
FFMPEGPublisherPlugin::advertiseImpl(node, base_topic, qos);
36+
}
37+
#else
38+
void FFMPEGPublisher::advertiseImpl(
39+
rclcpp::Node * node, const std::string & base_topic, rmw_qos_profile_t custom_qos,
40+
rclcpp::PublisherOptions opt)
41+
{
42+
auto qos = initialize(node, custom_qos);
43+
FFMPEGPublisherPlugin::advertiseImpl(node, base_topic, qos, opt);
44+
}
45+
#endif
46+
47+
rmw_qos_profile_t FFMPEGPublisher::initialize(rclcpp::Node * node, rmw_qos_profile_t custom_qos)
3248
{
3349
encoder_.setParameters(node);
3450
const std::string ns = "ffmpeg_image_transport.";
@@ -38,8 +54,7 @@ void FFMPEGPublisher::advertiseImpl(
3854

3955
// bump queue size to 2 * distance between keyframes
4056
custom_qos.depth = std::max(static_cast<int>(custom_qos.depth), 2 * encoder_.getGOPSize());
41-
42-
FFMPEGPublisherPlugin::advertiseImpl(node, base_topic, custom_qos);
57+
return (custom_qos);
4358
}
4459

4560
void FFMPEGPublisher::publish(const Image & msg, const PublishFn & publish_fn) const

‎src/ffmpeg_subscriber.cpp‎

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,13 +39,28 @@ FFMPEGSubscriber::~FFMPEGSubscriber() {}
3939

4040
void FFMPEGSubscriber::frameReady(const ImageConstPtr & img, bool) const { (*userCallback_)(img); }
4141

42+
#ifdef IMAGE_TRANSPORT_API_V1
4243
void FFMPEGSubscriber::subscribeImpl(
4344
rclcpp::Node * node, const std::string & base_topic, const Callback & callback,
4445
rmw_qos_profile_t custom_qos)
4546
{
4647
initialize(node);
4748
FFMPEGSubscriberPlugin::subscribeImpl(node, base_topic, callback, custom_qos);
4849
}
50+
#else
51+
void FFMPEGSubscriber::subscribeImpl(
52+
rclcpp::Node * node, const std::string & base_topic, const Callback & callback,
53+
rmw_qos_profile_t custom_qos, rclcpp::SubscriptionOptions opt)
54+
{
55+
initialize(node);
56+
#ifdef IMAGE_TRANSPORT_API_V2
57+
(void)opt; // to suppress compiler warning
58+
FFMPEGSubscriberPlugin::subscribeImpl(node, base_topic, callback, custom_qos);
59+
#else
60+
FFMPEGSubscriberPlugin::subscribeImpl(node, base_topic, callback, custom_qos, opt);
61+
#endif
62+
}
63+
#endif
4964

5065
void FFMPEGSubscriber::initialize(rclcpp::Node * node)
5166
{

0 commit comments

Comments
 (0)