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 @@ -139,11 +139,11 @@ Publisher create_publisher(
/// \return The advertised publisher
POINT_CLOUD_TRANSPORT_PUBLIC
Publisher create_publisher(
std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeInterfaces<
Copy link
Member

@SteveMacenski SteveMacenski Jul 7, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggestion: Given the repetition of this - you could typedef it to make this more readable. Though, I think also keeping it as-is is useful as a reference for later readers.

Its a trade off between accessibility to general ROS developers reading this and code cleanliness.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It would be better to keep it as it is to avoid possible name conflicts later on as well.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I will also point out that this is changing a public interface, so we usually do a tick-tock deprecation (same goes for all of the public APIs below).

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

These APIs were added on rolling, I know I already released the package but I would claim that It was unestable.

rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>> & node_interfaces,
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces,
const std::string & base_topic,
rclcpp::QoS custom_qos,
const rclcpp::PublisherOptions & options = rclcpp::PublisherOptions());
Expand Down Expand Up @@ -200,11 +200,11 @@ Subscriber create_subscription(
/// \return The subscriber
POINT_CLOUD_TRANSPORT_PUBLIC
Subscriber create_subscription(
std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>> & node_interfaces,
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces,
const std::string & base_topic,
const Subscriber::Callback & callback,
const std::string & transport,
Expand All @@ -223,11 +223,11 @@ class PointCloudTransport : public PointCloudTransportLoader

POINT_CLOUD_TRANSPORT_PUBLIC
explicit PointCloudTransport(
std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>> node_interfaces);
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces);

POINT_CLOUD_TRANSPORT_PUBLIC
~PointCloudTransport() override = default;
Expand All @@ -237,9 +237,7 @@ class PointCloudTransport : public PointCloudTransportLoader
{
std::string ret;
if (nullptr == transport_hints) {
auto ni_param = node_interfaces_->get_node_parameters_interface();
TransportHints th(std::make_shared<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeParametersInterface>>(ni_param));
TransportHints th(node_interfaces_);
ret = th.getTransport();
} else {
ret = transport_hints->getTransport();
Expand Down Expand Up @@ -488,11 +486,11 @@ class PointCloudTransport : public PointCloudTransportLoader
}

private:
std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>> node_interfaces_;
rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces_;
};

} // namespace point_cloud_transport
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,12 +65,10 @@ class Publisher
rmw_qos_profile_t custom_qos,
const rclcpp::PublisherOptions & options = rclcpp::PublisherOptions())
: Publisher(
std::make_shared<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>>(*node),
base_topic, loader, rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos),
*node,
base_topic,
loader,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos),
options)
{}

Expand All @@ -89,11 +87,11 @@ class Publisher

POINT_CLOUD_TRANSPORT_PUBLIC
Publisher(
std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>> node_interfaces,
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces,
const std::string & base_topic,
PubLoaderPtr loader,
rclcpp::QoS custom_qos,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,11 +88,11 @@ class PublisherPlugin

POINT_CLOUD_TRANSPORT_PUBLIC
void advertise(
std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>> node_interfaces,
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces,
const std::string & base_topic,
rclcpp::QoS custom_qos,
const rclcpp::PublisherOptions & options = rclcpp::PublisherOptions());
Expand Down Expand Up @@ -142,13 +142,10 @@ class PublisherPlugin
const rclcpp::PublisherOptions & options = rclcpp::PublisherOptions())
{
advertiseImpl(
std::make_shared<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>>(*node),
base_topic, rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos),
options);
*node,
base_topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos),
options);
}

[[deprecated("Use advertiseImpl(rclcpp::node_interfaces..., rclcpp::QoS, ...) instead")]]
Expand All @@ -163,17 +160,17 @@ class PublisherPlugin
const rclcpp::PublisherOptions & options = rclcpp::PublisherOptions())
{
advertiseImpl(
node_interfaces, base_topic,
*node_interfaces, base_topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos),
options);
}

virtual void advertiseImpl(
std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>> node_interfaces,
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces,
const std::string & base_topic,
rclcpp::QoS custom_qos,
const rclcpp::PublisherOptions & options = rclcpp::PublisherOptions()) = 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -96,13 +96,13 @@ class SimplePublisherPlugin : public point_cloud_transport::PublisherPlugin
{
if (simple_impl_) {
uint ns_len = strlen(simple_impl_->node_interfaces_
->get_node_base_interface()->get_namespace());
.get_node_base_interface()->get_namespace());
std::string param_base_name = getTopic().substr(ns_len);
std::replace(param_base_name.begin(), param_base_name.end(), '/', '.');

std::string param_name = param_base_name + "." + parameter_name;
rclcpp::Parameter param;
if (simple_impl_->node_interfaces_->get_node_parameters_interface()
if (simple_impl_->node_interfaces_.get_node_parameters_interface()
->get_parameter(param_name, param))
{
value = param.get_value<T>();
Expand All @@ -121,7 +121,7 @@ class SimplePublisherPlugin : public point_cloud_transport::PublisherPlugin
if (simple_impl_) {
// Declare Parameters
uint ns_len = strlen(simple_impl_->node_interfaces_
->get_node_base_interface()->get_namespace());
.get_node_base_interface()->get_namespace());
std::string param_base_name = getTopic().substr(ns_len);
std::replace(param_base_name.begin(), param_base_name.end(), '/', '.');

Expand All @@ -131,7 +131,7 @@ class SimplePublisherPlugin : public point_cloud_transport::PublisherPlugin
param_descriptor.name = param_name;

try {
simple_impl_->node_interfaces_->get_node_parameters_interface()
simple_impl_->node_interfaces_.get_node_parameters_interface()
->declare_parameter(param_name, rclcpp::ParameterValue(value));
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
RCLCPP_DEBUG(
Expand All @@ -149,7 +149,7 @@ class SimplePublisherPlugin : public point_cloud_transport::PublisherPlugin
{
if (simple_impl_) {
simple_impl_->on_set_parameters_callback_handle_ =
simple_impl_->node_interfaces_->get_node_parameters_interface()
simple_impl_->node_interfaces_.get_node_parameters_interface()
->add_on_set_parameters_callback(param_change_callback);
}
}
Expand Down Expand Up @@ -227,16 +227,16 @@ class SimplePublisherPlugin : public point_cloud_transport::PublisherPlugin
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
const rclcpp::PublisherOptions & options = rclcpp::PublisherOptions()) override
{
advertiseImpl(node_interfaces, base_topic,
advertiseImpl(*node_interfaces, base_topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos), options);
}

void advertiseImpl(
std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>> node_interfaces,
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces,
const std::string & base_topic,
rclcpp::QoS custom_qos,
const rclcpp::PublisherOptions & options = rclcpp::PublisherOptions()) override
Expand All @@ -245,8 +245,8 @@ class SimplePublisherPlugin : public point_cloud_transport::PublisherPlugin
simple_impl_ = std::make_unique<SimplePublisherPluginImpl>(node_interfaces);

RCLCPP_DEBUG(simple_impl_->logger_, "getTopicToAdvertise: %s", transport_topic.c_str());
auto node_parameters = node_interfaces->get_node_parameters_interface();
auto node_topics = node_interfaces->get_node_topics_interface();
auto node_parameters = node_interfaces.get_node_parameters_interface();
auto node_topics = node_interfaces.get_node_topics_interface();
// simple_impl_->pub_ = node->create_publisher<M>(transport_topic, qos, options);
simple_impl_->pub_ = rclcpp::create_publisher<M>(
node_parameters, node_topics, transport_topic, custom_qos, options);
Expand Down Expand Up @@ -315,21 +315,21 @@ class SimplePublisherPlugin : public point_cloud_transport::PublisherPlugin
struct SimplePublisherPluginImpl
{
explicit SimplePublisherPluginImpl(
std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>> node_interfaces)
:node_interfaces_(std::move(node_interfaces)),
logger_(node_interfaces_->get_node_logging_interface()->get_logger())
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces)
:node_interfaces_(node_interfaces),
logger_(node_interfaces_.get_node_logging_interface()->get_logger())
{
}

std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>> node_interfaces_;
rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces_;
rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_handle_;
rclcpp::Logger logger_;
typename rclcpp::Publisher<M>::SharedPtr pub_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,14 +93,14 @@ class SimpleSubscriberPlugin : public SubscriberPlugin
bool getParam(const std::string & parameter_name, T & value) const
{
if (impl_) {
uint ns_len = strlen(impl_->node_interfaces_->get_node_base_interface()->get_namespace());
uint ns_len = strlen(impl_->node_interfaces_.get_node_base_interface()->get_namespace());
std::string param_base_name = getTopic().substr(ns_len);
std::replace(param_base_name.begin(), param_base_name.end(), '/', '.');

std::string param_name = param_base_name + "." + parameter_name;

rclcpp::Parameter param;
if (impl_->node_interfaces_->get_node_parameters_interface()
if (impl_->node_interfaces_.get_node_parameters_interface()
->get_parameter(param_name, param))
{
value = param.get_value<T>();
Expand All @@ -117,7 +117,7 @@ class SimpleSubscriberPlugin : public SubscriberPlugin
rcl_interfaces::msg::ParameterDescriptor())
{
if (impl_) {
uint ns_len = strlen(impl_->node_interfaces_->get_node_base_interface()->get_namespace());
uint ns_len = strlen(impl_->node_interfaces_.get_node_base_interface()->get_namespace());
std::string param_base_name = getTopic().substr(ns_len);
std::replace(param_base_name.begin(), param_base_name.end(), '/', '.');

Expand All @@ -127,7 +127,7 @@ class SimpleSubscriberPlugin : public SubscriberPlugin
param_descriptor.name = param_name;

try {
impl_->node_interfaces_->get_node_parameters_interface()
impl_->node_interfaces_.get_node_parameters_interface()
->declare_parameter(param_name, rclcpp::ParameterValue(value));
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
RCLCPP_DEBUG(
Expand All @@ -146,7 +146,7 @@ class SimpleSubscriberPlugin : public SubscriberPlugin
{
if (impl_) {
impl_->on_set_parameters_callback_handle_ =
impl_->node_interfaces_->get_node_parameters_interface()
impl_->node_interfaces_.get_node_parameters_interface()
->add_on_set_parameters_callback(param_change_callback);
}
}
Expand Down Expand Up @@ -223,7 +223,7 @@ class SimpleSubscriberPlugin : public SubscriberPlugin
const Callback & callback,
rmw_qos_profile_t custom_qos) override
{
subscribeImpl(node_interfaces, base_topic, callback,
subscribeImpl(*node_interfaces, base_topic, callback,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos));
}

Expand All @@ -238,26 +238,23 @@ class SimpleSubscriberPlugin : public SubscriberPlugin
rmw_qos_profile_t custom_qos,
rclcpp::SubscriptionOptions options) override
{
subscribeImpl(node_interfaces, base_topic, callback,
subscribeImpl(*node_interfaces, base_topic, callback,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos), options);
}

void subscribeImpl(
std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>> node_interfaces,
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces,
const std::string & base_topic,
const Callback & callback,
rclcpp::QoS custom_qos) override
{
if (!node_interfaces) {
throw std::runtime_error("node_interfaces is null");
}
impl_ = std::make_unique<Impl>(node_interfaces);
auto node_parameters = node_interfaces->get_node_parameters_interface();
auto node_topics = node_interfaces->get_node_topics_interface();
auto node_parameters = node_interfaces.get_node_parameters_interface();
auto node_topics = node_interfaces.get_node_topics_interface();
impl_->sub_ = rclcpp::create_subscription<M>(
node_parameters, node_topics,
getTopicToSubscribe(base_topic), custom_qos,
Expand All @@ -268,19 +265,19 @@ class SimpleSubscriberPlugin : public SubscriberPlugin
}

void subscribeImpl(
std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>> node_interfaces,
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces,
const std::string & base_topic,
const Callback & callback,
rclcpp::QoS custom_qos,
rclcpp::SubscriptionOptions options) override
{
impl_ = std::make_unique<Impl>(node_interfaces);
auto node_parameters = node_interfaces->get_node_parameters_interface();
auto node_topics = node_interfaces->get_node_topics_interface();
auto node_parameters = node_interfaces.get_node_parameters_interface();
auto node_topics = node_interfaces.get_node_topics_interface();
impl_->sub_ = rclcpp::create_subscription<M>(
node_parameters, node_topics,
getTopicToSubscribe(base_topic), custom_qos,
Expand All @@ -295,22 +292,22 @@ class SimpleSubscriberPlugin : public SubscriberPlugin
struct Impl
{
explicit Impl(
std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>> node_interfaces)
:node_interfaces_(std::move(node_interfaces)),
logger_(node_interfaces_->get_node_logging_interface()->get_logger())
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces)
:node_interfaces_(node_interfaces),
logger_(node_interfaces_.get_node_logging_interface()->get_logger())
{
}

rclcpp::SubscriptionBase::SharedPtr sub_;
std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface>> node_interfaces_;
rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces_;
rclcpp::Logger logger_;
rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_handle_;
};
Expand Down
Loading