Skip to content

Fix publisher advertiseImpl() and subscribeImpl() for compressed_image_transport, compressed_depth_transport and theora_image_transport #106

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -50,12 +50,13 @@ class CompressedDepthPublisher : public image_transport::SimplePublisherPlugin<s

protected:
// Overridden to set up reconfigure server
virtual void advertiseImpl(
void advertiseImpl(
rclcpp::Node * node,
const std::string &base_topic,
rmw_qos_profile_t custom_qos) override final;
rmw_qos_profile_t custom_qos,
rclcpp::PublisherOptions options) override final;

virtual void publish(const sensor_msgs::msg::Image& message,
void publish(const sensor_msgs::msg::Image& message,
const PublishFn& publish_fn) const override final;

struct Config {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,10 +60,11 @@ namespace compressed_depth_image_transport
void CompressedDepthPublisher::advertiseImpl(
rclcpp::Node * node,
const std::string& base_topic,
rmw_qos_profile_t custom_qos)
rmw_qos_profile_t custom_qos,
rclcpp::PublisherOptions options)
{
typedef image_transport::SimplePublisherPlugin<sensor_msgs::msg::CompressedImage> Base;
Base::advertiseImpl(node, base_topic, custom_qos);
Base::advertiseImpl(node, base_topic, custom_qos, options);

node->get_parameter_or<int>("png_level", config_.png_level, kDefaultPngLevel);
node->get_parameter_or<double>("depth_max", config_.depth_max, kDefaultDepthMax);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,9 @@ class CompressedPublisher : public image_transport::SimplePublisherPlugin<Compre
{
public:
CompressedPublisher(): logger_(rclcpp::get_logger("CompressedPublisher")) {}
virtual ~CompressedPublisher() = default;
~CompressedPublisher() override = default;

virtual std::string getTransportName() const
std::string getTransportName() const override
{
return "compressed";
}
Expand All @@ -60,7 +60,8 @@ class CompressedPublisher : public image_transport::SimplePublisherPlugin<Compre
void advertiseImpl(
rclcpp::Node* node,
const std::string& base_topic,
rmw_qos_profile_t custom_qos) override;
rmw_qos_profile_t custom_qos,
rclcpp::PublisherOptions options) override;

void publish(const sensor_msgs::msg::Image& message,
const PublishFn& publish_fn) const;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,12 +55,6 @@ class CompressedSubscriber final : public image_transport::SimpleSubscriberPlugi
}

protected:
// Overridden to set up reconfigure server
void subscribeImpl(
rclcpp::Node * ,
const std::string& base_topic,
const Callback& callback,
rmw_qos_profile_t custom_qos) override;

void subscribeImpl(
rclcpp::Node * ,
Expand Down
5 changes: 3 additions & 2 deletions compressed_image_transport/src/compressed_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,10 +61,11 @@ namespace compressed_image_transport
void CompressedPublisher::advertiseImpl(
rclcpp::Node* node,
const std::string& base_topic,
rmw_qos_profile_t custom_qos)
rmw_qos_profile_t custom_qos,
rclcpp::PublisherOptions options)
{
typedef image_transport::SimplePublisherPlugin<sensor_msgs::msg::CompressedImage> Base;
Base::advertiseImpl(node, base_topic, custom_qos);
Base::advertiseImpl(node, base_topic, custom_qos, options);

uint ns_len = node->get_effective_namespace().length();
std::string param_base_name = base_topic.substr(ns_len);
Expand Down
11 changes: 1 addition & 10 deletions compressed_image_transport/src/compressed_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,15 +57,6 @@ using CompressedImage = sensor_msgs::msg::CompressedImage;
namespace compressed_image_transport
{

void CompressedSubscriber::subscribeImpl(
rclcpp::Node * node,
const std::string& base_topic,
const Callback& callback,
rmw_qos_profile_t custom_qos)
{
this->subscribeImpl(node, base_topic, callback, custom_qos, rclcpp::SubscriptionOptions{});
}

void CompressedSubscriber::subscribeImpl(
rclcpp::Node * node,
const std::string& base_topic,
Expand All @@ -75,7 +66,7 @@ void CompressedSubscriber::subscribeImpl(
{
logger_ = node->get_logger();
typedef image_transport::SimpleSubscriberPlugin<CompressedImage> Base;
Base::subscribeImplWithOptions(node, base_topic, callback, custom_qos, options);
Base::subscribeImpl(node, base_topic, callback, custom_qos, options);
uint ns_len = node->get_effective_namespace().length();
std::string param_base_name = base_topic.substr(ns_len);
std::replace(param_base_name.begin(), param_base_name.end(), '/', '.');
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,17 +50,17 @@ class TheoraPublisher : public image_transport::SimplePublisherPlugin<theora_ima
{
public:
TheoraPublisher();
virtual ~TheoraPublisher();
~TheoraPublisher() override;

// Return the system unique string representing the theora transport type
virtual std::string getTransportName() const { return "theora"; }
std::string getTransportName() const override { return "theora"; }

protected:
virtual void advertiseImpl(
void advertiseImpl(
rclcpp::Node* node,
const std::string &base_topic,
uint32_t queue_size,
rmw_qos_profile_t custom_qos);
rmw_qos_profile_t custom_qos,
rclcpp::PublisherOptions options) override;

// TODO: Callback to send header packets to new clients
// virtual void connectCallback(const ros::SingleSubscriberPublisher& pub);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,12 +51,12 @@ class TheoraSubscriber : public image_transport::SimpleSubscriberPlugin<theora_i

protected:
// Overridden to bump queue_size, otherwise we might lose headers
virtual void subscribeImpl(
void subscribeImpl(
rclcpp::Node* node,
const std::string &base_topic,
const Callback & callback,
uint32_t queue_size,
rmw_qos_profile_t custom_qos);
rmw_qos_profile_t custom_qos,
rclcpp::SubscriptionOptions options) override;

// The function that does the actual decompression and calls a user supplied
// callback with the resulting image
Expand Down
13 changes: 3 additions & 10 deletions theora_image_transport/src/theora_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,20 +74,13 @@ TheoraPublisher::~TheoraPublisher()
void TheoraPublisher::advertiseImpl(
rclcpp::Node *node,
const std::string &base_topic,
uint32_t queue_size,
rmw_qos_profile_t custom_qos)
rmw_qos_profile_t custom_qos,
rclcpp::PublisherOptions options)
{
logger_ = node->get_logger();
// queue_size doesn't account for the 3 header packets, so we correct (with a little extra) here.
// ported this to ROS2 using the history policy that determines how messages
// are saved until the message is taken by the reader. KEEP_ALL saves all
// messages until they are taken. KEEP_LAST enforces a limit on the number of
// messages that are saved, specified by the "depth" parameter.
custom_qos.history = rmw_qos_profile_default.history;
custom_qos.depth = queue_size + 4;

typedef image_transport::SimplePublisherPlugin<theora_image_transport::msg::Packet> Base;
Base::advertiseImpl(node, base_topic, custom_qos);
Base::advertiseImpl(node, base_topic, custom_qos, options);
}

// TODO(ros2): this method should be called when configuration change through
Expand Down
13 changes: 3 additions & 10 deletions theora_image_transport/src/theora_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,20 +69,13 @@ void TheoraSubscriber::subscribeImpl(
rclcpp::Node * node,
const std::string &base_topic,
const Callback & callback,
uint32_t queue_size,
rmw_qos_profile_t custom_qos)
rmw_qos_profile_t custom_qos,
rclcpp::SubscriptionOptions options)
{
logger_ = node->get_logger();
// queue_size doesn't account for the 3 header packets, so we correct (with a little extra) here.
// ported this to ROS2 using the history policy that determines how messages
// are saved until the message is taken by the reader. KEEP_ALL saves all
// messages until they are taken. KEEP_LAST enforces a limit on the number of
// messages that are saved, specified by the "depth" parameter.
custom_qos.history = rmw_qos_profile_default.history;
custom_qos.depth = queue_size + 4;

typedef image_transport::SimpleSubscriberPlugin<theora_image_transport::msg::Packet> Base;
Base::subscribeImpl(node, base_topic, callback, custom_qos);
Base::subscribeImpl(node, base_topic, callback, custom_qos, options);
}

// TODO: port this check to ROS2 user events
Expand Down