Skip to content
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

Fixed clang issues #55

Merged
merged 5 commits into from
Feb 19, 2024
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 @@ -263,8 +263,7 @@ class PointCloudTransport : public PointCloudTransportLoader
point_cloud_transport::Subscriber subscribe(
const std::string & base_topic, rmw_qos_profile_t custom_qos,
void (T::* fp)(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &) const, T * obj,
const point_cloud_transport::TransportHints * transport_hints = nullptr,
bool allow_concurrent_callbacks = false)
const point_cloud_transport::TransportHints * transport_hints = nullptr)
{
return subscribe(
base_topic, custom_qos, std::bind(
Expand All @@ -276,8 +275,7 @@ class PointCloudTransport : public PointCloudTransportLoader
point_cloud_transport::Subscriber subscribe(
const std::string & base_topic, uint32_t queue_size,
void (T::* fp)(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &) const, T * obj,
const point_cloud_transport::TransportHints * transport_hints = nullptr,
bool allow_concurrent_callbacks = false)
const point_cloud_transport::TransportHints * transport_hints = nullptr)
{
return subscribe(
base_topic, queue_size, std::bind(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,8 @@ class PublisherPlugin
PublisherPlugin(const PublisherPlugin &) = delete;
PublisherPlugin & operator=(const PublisherPlugin &) = delete;

virtual ~PublisherPlugin() {}

//! Get a string identifier for the transport provided by this plugin
virtual std::string getTransportName() const = 0;

Expand All @@ -85,14 +87,14 @@ class PublisherPlugin
/// or an error message.
///
POINT_CLOUD_TRANSPORT_PUBLIC
virtual EncodeResult encode(const sensor_msgs::msg::PointCloud2 & raw) const;
virtual EncodeResult encode(const sensor_msgs::msg::PointCloud2 & raw) const = 0;

//! Publish a point cloud using the transport associated with this PublisherPlugin.
virtual void publish(const sensor_msgs::msg::PointCloud2 & message) const = 0;

//! Publish a point cloud using the transport associated with this PublisherPlugin.
POINT_CLOUD_TRANSPORT_PUBLIC
virtual void publish(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & message) const;
virtual void publishPtr(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & message) const;
Copy link
Contributor

Choose a reason for hiding this comment

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

Out of curiosity, why rename this?

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Two main reasons:

  • I was getting this warning
hidden overloaded virtual function 'point_cloud_transport::PublisherPlugin::publish' declared here: different number of parameters (1 vs 2)
  • To have the same API as image_Transport


//! Shutdown any advertisements associated with this PublisherPlugin.
virtual void shutdown() = 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class RawPublisher
public:
virtual ~RawPublisher() {}

virtual std::string getTransportName() const
std::string getTransportName() const override
{
return "raw";
}
Expand All @@ -66,26 +66,27 @@ class RawPublisher
}

RawPublisher::TypedEncodeResult encodeTyped(const sensor_msgs::msg::PointCloud2 & raw) const
override
{
return raw;
}

protected:
virtual void publish(
void publish(
const sensor_msgs::msg::PointCloud2 & message,
const PublishFn & publish_fn) const
const PublishFn & publish_fn) const override
{
publish_fn(message);
}

virtual void publish(
void publish(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & message_ptr,
const PublishFn & publish_fn) const
const PublishFn & publish_fn) const override
{
publish_fn(*message_ptr);
}

virtual std::string getTopicToAdvertise(const std::string & base_topic) const
std::string getTopicToAdvertise(const std::string & base_topic) const override
{
return base_topic;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ class RawSubscriber

POINT_CLOUD_TRANSPORT_PUBLIC
SubscriberPlugin::DecodeResult decodeTyped(
const sensor_msgs::msg::PointCloud2 & compressed) const;
const sensor_msgs::msg::PointCloud2 & compressed) const override;

POINT_CLOUD_TRANSPORT_PUBLIC
std::string getDataType() const override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -196,10 +196,10 @@ class SimplePublisherPlugin : public point_cloud_transport::PublisherPlugin
protected:
std::string base_topic_;

virtual void advertiseImpl(
void advertiseImpl(
std::shared_ptr<rclcpp::Node> node, const std::string & base_topic,
rmw_qos_profile_t custom_qos,
const rclcpp::PublisherOptions & options)
const rclcpp::PublisherOptions & options) override
{
std::string transport_topic = getTopicToAdvertise(base_topic);
simple_impl_ = std::make_unique<SimplePublisherPluginImpl>(node);
Expand Down Expand Up @@ -237,6 +237,27 @@ class SimplePublisherPlugin : public point_cloud_transport::PublisherPlugin
}
}

///
/// \brief Publish a point cloud using the specified publish function.
///
/// The PublishFn publishes the transport-specific message type. This indirection allows
/// SimplePublisherPlugin to use this function for both normal broadcast publishing and
/// single subscriber publishing (in subscription callbacks).
///
virtual void publish(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & message,
const PublishFn & publish_fn) const
{
const auto res = this->encodeTyped(*message.get());
if (!res) {
RCLCPP_ERROR(
this->getLogger(), "Error encoding message by transport %s: %s.",
this->getTransportName().c_str(), res.error().c_str());
} else if (res.value()) {
publish_fn(res.value().value());
}
}

///
/// \brief Return the communication topic name for a given base topic.
///
Expand Down
2 changes: 1 addition & 1 deletion point_cloud_transport/src/publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,7 +209,7 @@ void Publisher::publish(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & me

for (const auto & pub : impl_->publishers_) {
if (pub->getNumSubscribers() > 0) {
pub->publish(message);
pub->publishPtr(message);
}
}
}
Expand Down
9 changes: 2 additions & 7 deletions point_cloud_transport/src/publisher_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,6 @@
namespace point_cloud_transport
{

PublisherPlugin::EncodeResult PublisherPlugin::encode(const sensor_msgs::msg::PointCloud2 & raw)
const
{
return this->encode(raw);
}

Comment on lines -41 to -46
Copy link
Contributor

Choose a reason for hiding this comment

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

Oh, I see. Yeah, clang is totally right about the old code; any call to this function will just have it call itself. What we really wanted is to have this as a pure virtual function, which this change now does. So I think this is good now.

void PublisherPlugin::advertise(
std::shared_ptr<rclcpp::Node> node,
const std::string & base_topic,
Expand All @@ -53,7 +47,8 @@ void PublisherPlugin::advertise(
advertiseImpl(node, base_topic, custom_qos, options);
}

void PublisherPlugin::publish(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & message) const
void PublisherPlugin::publishPtr(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & message)
const
{
publish(*message);
}
Expand Down
2 changes: 1 addition & 1 deletion point_cloud_transport/src/republish.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ void Republisher::initialize()
typedef void (point_cloud_transport::PublisherPlugin::* PublishMemFn)(
const sensor_msgs::msg::
PointCloud2::ConstSharedPtr &) const;
PublishMemFn pub_mem_fn = &point_cloud_transport::PublisherPlugin::publish;
PublishMemFn pub_mem_fn = &point_cloud_transport::PublisherPlugin::publishPtr;

RCLCPP_INFO(this->get_logger(), "Loading %s subscriber", in_topic.c_str());

Expand Down
Loading