Skip to content
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 @@ -36,6 +36,7 @@

#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/compressed_image.hpp>
#include <image_transport/node_interfaces.hpp>
#include <image_transport/simple_publisher_plugin.hpp>

#include <rclcpp/node.hpp>
Expand Down Expand Up @@ -63,7 +64,7 @@ class CompressedDepthPublisher : public image_transport::SimplePublisherPlugin<C
protected:
// Overridden to set up reconfigure server
void advertiseImpl(
rclcpp::Node * node,
image_transport::RequiredInterfaces node_interfaces,
const std::string & base_topic,
rclcpp::QoS custom_qos,
rclcpp::PublisherOptions options) final;
Expand All @@ -73,7 +74,8 @@ class CompressedDepthPublisher : public image_transport::SimplePublisherPlugin<C
const PublisherT & publisher) const final;

rclcpp::Logger logger_;
rclcpp::Node * node_;
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_param_interface_;
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;

private:
std::vector<std::string> parameters_;
Expand Down
40 changes: 23 additions & 17 deletions compressed_depth_image_transport/src/compressed_depth_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,26 +103,26 @@ const struct ParameterDefinition kParameters[] =
};

void CompressedDepthPublisher::advertiseImpl(
rclcpp::Node * node,
image_transport::RequiredInterfaces node_interfaces,
const std::string & base_topic,
rclcpp::QoS custom_qos,
rclcpp::PublisherOptions options)
{
node_ = node;

node_param_interface_ = node_interfaces.get_node_parameters_interface();
node_base_interface_ = node_interfaces.get_node_base_interface();
typedef image_transport::SimplePublisherPlugin<sensor_msgs::msg::CompressedImage> Base;
Base::advertiseImpl(node, base_topic, custom_qos, options);
Base::advertiseImpl(node_interfaces, base_topic, custom_qos, options);

// Declare Parameters
uint ns_len = node->get_effective_namespace().length();
uint ns_prefix_len = ns_len > 1 ? ns_len + 1 : ns_len;
std::string param_base_name = base_topic.substr(ns_prefix_len);
unsigned int ns_len =
std::string(node_interfaces.get_node_base_interface()->get_namespace()).length();
std::string param_base_name = base_topic.substr(ns_len);
std::replace(param_base_name.begin(), param_base_name.end(), '/', '.');

if (ns_len > 1) {
// Add pre set parameter callback to handle deprecated parameters
pre_set_parameter_callback_handle_ =
node->add_pre_set_parameters_callback(std::bind(
node_param_interface_->add_pre_set_parameters_callback(std::bind(
&CompressedDepthPublisher::preSetParametersCallback, this, std::placeholders::_1));
}

Expand All @@ -136,11 +136,14 @@ void CompressedDepthPublisher::publish(
const PublisherT & publisher) const
{
// Fresh Configuration
std::string cfg_format = node_->get_parameter(parameters_[FORMAT]).get_value<std::string>();
double cfg_depth_max = node_->get_parameter(parameters_[DEPTH_MAX]).get_value<double>();
std::string cfg_format = node_param_interface_->get_parameter(
parameters_[FORMAT]).get_value<std::string>();
double cfg_depth_max = node_param_interface_->get_parameter(
parameters_[DEPTH_MAX]).get_value<double>();
double cfg_depth_quantization =
node_->get_parameter(parameters_[DEPTH_QUANTIZATION]).get_value<double>();
int cfg_png_level = node_->get_parameter(parameters_[PNG_LEVEL]).get_value<int64_t>();
node_param_interface_->get_parameter(parameters_[DEPTH_QUANTIZATION]).get_value<double>();
int cfg_png_level = node_param_interface_->get_parameter(
parameters_[PNG_LEVEL]).get_value<int64_t>();

sensor_msgs::msg::CompressedImage::SharedPtr compressed_image =
encodeCompressedDepthImage(message,
Expand All @@ -166,22 +169,25 @@ void CompressedDepthPublisher::declareParameter(
rclcpp::ParameterValue param_value;

try {
param_value = node_->declare_parameter(param_name, definition.defaultValue,
definition.descriptor);
param_value = node_param_interface_->declare_parameter(
param_name,
definition.defaultValue,
definition.descriptor);
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
RCLCPP_DEBUG(logger_, "%s was previously declared", definition.descriptor.name.c_str());
param_value = node_->get_parameter(param_name).get_parameter_value();
param_value = node_param_interface_->get_parameter(param_name).get_parameter_value();
}

// TODO(anyone): Remove deprecated parameters after Lyrical release
if (node_->get_effective_namespace().length() > 1) {
if (std::string(node_base_interface_->get_namespace()).length() > 1) {
// deprecated parameters starting with the dot character (e.g. .image_raw.compressed.format)
const std::string deprecated_dot_name = "." + base_name + "." + transport_name + "." +
definition.descriptor.name;
deprecated_parameters_.insert(deprecated_dot_name);

try {
node_->declare_parameter(deprecated_dot_name, param_value, definition.descriptor);
node_param_interface_->declare_parameter(deprecated_dot_name, param_value,
definition.descriptor);
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
RCLCPP_DEBUG(logger_, "%s was previously declared", definition.descriptor.name.c_str());
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@

#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/compressed_image.hpp>
#include <image_transport/node_interfaces.hpp>
#include <image_transport/simple_publisher_plugin.hpp>

#include <rclcpp/node.hpp>
Expand Down Expand Up @@ -63,9 +64,8 @@ class CompressedPublisher : public image_transport::SimplePublisherPlugin<Compre
}

protected:
// Overridden to set up reconfigure server
void advertiseImpl(
rclcpp::Node * node,
image_transport::RequiredInterfaces node_interfaces,
const std::string & base_topic,
rclcpp::QoS custom_qos,
rclcpp::PublisherOptions options) override;
Expand All @@ -75,7 +75,8 @@ class CompressedPublisher : public image_transport::SimplePublisherPlugin<Compre
const PublisherT & publisher) const override;

rclcpp::Logger logger_;
rclcpp::Node * node_;
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_param_interface_;
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;

private:
std::vector<std::string> parameters_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@

#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/compressed_image.hpp>
#include <image_transport/node_interfaces.hpp>
#include <image_transport/simple_subscriber_plugin.hpp>

#include "compressed_image_transport/compression_common.hpp"
Expand All @@ -64,7 +65,7 @@ class CompressedSubscriber final : public image_transport::SimpleSubscriberPlugi

protected:
void subscribeImpl(
rclcpp::Node *,
image_transport::RequiredInterfaces node_interfaces,
const std::string & base_topic,
const Callback & callback,
rclcpp::QoS custom_qos,
Expand All @@ -75,7 +76,7 @@ class CompressedSubscriber final : public image_transport::SimpleSubscriberPlugi
const Callback & user_cb) override;

rclcpp::Logger logger_;
rclcpp::Node * node_;
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_param_interface_;

private:
std::vector<std::string> parameters_;
Expand Down
47 changes: 28 additions & 19 deletions compressed_image_transport/src/compressed_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -131,25 +131,26 @@ const struct ParameterDefinition kParameters[] =
};

void CompressedPublisher::advertiseImpl(
rclcpp::Node * node,
image_transport::RequiredInterfaces node_interfaces,
const std::string & base_topic,
rclcpp::QoS custom_qos,
rclcpp::PublisherOptions options)
{
node_ = node;
node_param_interface_ = node_interfaces.get_node_parameters_interface();
node_base_interface_ = node_interfaces.get_node_base_interface();
typedef image_transport::SimplePublisherPlugin<sensor_msgs::msg::CompressedImage> Base;
Base::advertiseImpl(node, base_topic, custom_qos, options);
Base::advertiseImpl(node_interfaces, base_topic, custom_qos, options);

// Declare Parameters
uint ns_len = node->get_effective_namespace().length();
uint ns_prefix_len = ns_len > 1 ? ns_len + 1 : ns_len;
std::string param_base_name = base_topic.substr(ns_prefix_len);
unsigned int ns_len =
std::string(node_interfaces.get_node_base_interface()->get_namespace()).length();
std::string param_base_name = base_topic.substr(ns_len);
std::replace(param_base_name.begin(), param_base_name.end(), '/', '.');

if (ns_len > 1) {
// Add pre set parameter callback to handle deprecated parameters
pre_set_parameter_callback_handle_ =
node->add_pre_set_parameters_callback(std::bind(
node_param_interface_->add_pre_set_parameters_callback(std::bind(
&CompressedPublisher::preSetParametersCallback, this, std::placeholders::_1));
}

Expand All @@ -163,15 +164,21 @@ void CompressedPublisher::publish(
const PublisherT & publisher) const
{
// Fresh Configuration
std::string cfg_format = node_->get_parameter(parameters_[FORMAT]).get_value<std::string>();
int cfg_png_level = node_->get_parameter(parameters_[PNG_LEVEL]).get_value<int64_t>();
int cfg_jpeg_quality = node_->get_parameter(parameters_[JPEG_QUALITY]).get_value<int64_t>();
std::string cfg_format = node_param_interface_->get_parameter(
parameters_[FORMAT]).get_value<std::string>();
int cfg_png_level = node_param_interface_->get_parameter(
parameters_[PNG_LEVEL]).get_value<int64_t>();
int cfg_jpeg_quality = node_param_interface_->get_parameter(
parameters_[JPEG_QUALITY]).get_value<int64_t>();
bool cfg_jpeg_compress_bayer =
node_->get_parameter(parameters_[JPEG_COMPRESS_BAYER]).get_value<bool>();
node_param_interface_->get_parameter(parameters_[JPEG_COMPRESS_BAYER]).get_value<bool>();
std::string cfg_tiff_res_unit =
node_->get_parameter(parameters_[TIFF_RESOLUTION_UNIT]).get_value<std::string>();
int cfg_tiff_xdpi = node_->get_parameter(parameters_[TIFF_XDPI]).get_value<int64_t>();
int cfg_tiff_ydpi = node_->get_parameter(parameters_[TIFF_YDPI]).get_value<int64_t>();
node_param_interface_->get_parameter(
parameters_[TIFF_RESOLUTION_UNIT]).get_value<std::string>();
int cfg_tiff_xdpi = node_param_interface_->get_parameter(
parameters_[TIFF_XDPI]).get_value<int64_t>();
int cfg_tiff_ydpi = node_param_interface_->get_parameter(
parameters_[TIFF_YDPI]).get_value<int64_t>();

// Compressed image message
sensor_msgs::msg::CompressedImage compressed;
Expand Down Expand Up @@ -393,22 +400,24 @@ void CompressedPublisher::declareParameter(
rclcpp::ParameterValue param_value;

try {
param_value = node_->declare_parameter(param_name, definition.defaultValue,
definition.descriptor);
param_value = node_param_interface_->declare_parameter(
param_name, definition.defaultValue,
definition.descriptor);
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
RCLCPP_DEBUG(logger_, "%s was previously declared", definition.descriptor.name.c_str());
param_value = node_->get_parameter(param_name).get_parameter_value();
param_value = node_param_interface_->get_parameter(param_name).get_parameter_value();
}

// TODO(anyone): Remove deprecated parameters after Lyrical release
if (node_->get_effective_namespace().length() > 1) {
if (std::string(node_base_interface_->get_namespace()).length() > 1) {
// deprecated parameters starting with the dot character (e.g. .image_raw.compressed.format)
const std::string deprecated_dot_name = "." + base_name + "." + transport_name + "." +
definition.descriptor.name;
deprecated_parameters_.insert(deprecated_dot_name);

try {
node_->declare_parameter(deprecated_dot_name, param_value, definition.descriptor);
node_param_interface_->declare_parameter(deprecated_dot_name, param_value,
definition.descriptor);
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
RCLCPP_DEBUG(logger_, "%s was previously declared", definition.descriptor.name.c_str());
}
Expand Down
18 changes: 10 additions & 8 deletions compressed_image_transport/src/compressed_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,19 +68,20 @@ const struct ParameterDefinition kParameters[] =
};

void CompressedSubscriber::subscribeImpl(
rclcpp::Node * node,
image_transport::RequiredInterfaces node_interfaces,
const std::string & base_topic,
const Callback & callback,
rclcpp::QoS custom_qos,
rclcpp::SubscriptionOptions options)
{
node_ = node;
logger_ = node->get_logger();
node_param_interface_ = node_interfaces.get_node_parameters_interface();
logger_ = node_interfaces.get_node_logging_interface()->get_logger();
typedef image_transport::SimpleSubscriberPlugin<CompressedImage> Base;
Base::subscribeImpl(node, base_topic, callback, custom_qos, options);
Base::subscribeImpl(node_interfaces, base_topic, callback, custom_qos, options);

// Declare Parameters
uint ns_len = node->get_effective_namespace().length();
unsigned int ns_len =
std::string(node_interfaces.get_node_base_interface()->get_namespace()).length();
std::string param_base_name = base_topic.substr(ns_len);
std::replace(param_base_name.begin(), param_base_name.end(), '/', '.');

Expand Down Expand Up @@ -179,7 +180,8 @@ void CompressedSubscriber::internalCallback(

int CompressedSubscriber::imdecodeFlagFromConfig()
{
std::string mode = node_->get_parameter(parameters_[MODE]).get_value<std::string>();
std::string mode =
node_param_interface_->get_parameter(parameters_[MODE]).get_value<std::string>();

if (mode == "unchanged") {
return cv::IMREAD_UNCHANGED;
Expand Down Expand Up @@ -207,11 +209,11 @@ void CompressedSubscriber::declareParameter(
rclcpp::ParameterValue param_value;

try {
param_value = node_->declare_parameter(param_name, definition.defaultValue,
param_value = node_param_interface_->declare_parameter(param_name, definition.defaultValue,
definition.descriptor);
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
RCLCPP_DEBUG(logger_, "%s was previously declared", definition.descriptor.name.c_str());
param_value = node_->get_parameter(param_name).get_parameter_value();
param_value = node_param_interface_->get_parameter(param_name).get_parameter_value();
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/compressed_image.hpp>

#include <image_transport/node_interfaces.hpp>
#include <image_transport/simple_publisher_plugin.hpp>
#include <cv_bridge/cv_bridge.hpp>
#include <std_msgs/msg/header.hpp>
Expand All @@ -68,7 +69,7 @@ class TheoraPublisher

protected:
void advertiseImpl(
rclcpp::Node * node,
image_transport::RequiredInterfaces node_interfaces,
const std::string & base_topic,
rclcpp::QoS custom_qos,
rclcpp::PublisherOptions options) override;
Expand Down Expand Up @@ -104,7 +105,8 @@ class TheoraPublisher
mutable std::vector<theora_image_transport::msg::Packet> stream_header_;

rclcpp::Logger logger_;
rclcpp::Node * node_;
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_param_interface_;
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;

private:
std::vector<std::string> parameters_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@

#include <rclcpp/node.hpp>

#include <image_transport/node_interfaces.hpp>
#include <image_transport/simple_subscriber_plugin.hpp>
#include <theora_image_transport/msg/packet.hpp>

Expand All @@ -59,9 +60,8 @@ class TheoraSubscriber
std::string getTransportName() const override {return "theora";}

protected:
// Overridden to bump queue_size, otherwise we might lose headers
void subscribeImpl(
rclcpp::Node * node,
image_transport::RequiredInterfaces node_interfaces,
const std::string & base_topic,
const Callback & callback,
rclcpp::QoS custom_qos,
Expand Down Expand Up @@ -91,7 +91,7 @@ class TheoraSubscriber
sensor_msgs::msg::Image::SharedPtr latest_image_;

rclcpp::Logger logger_;
rclcpp::Node * node_;
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_param_interface_;

private:
std::vector<std::string> parameters_;
Expand Down
Loading