Skip to content

Commit

Permalink
Fixed clang issues
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde committed Feb 14, 2024
1 parent 995df56 commit 8b87df6
Show file tree
Hide file tree
Showing 8 changed files with 38 additions and 15 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -264,25 +264,25 @@ class PointCloudTransport : public PointCloudTransportLoader
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)
bool /*allow_concurrent_callbacks*/ = false)
{
return subscribe(
base_topic, custom_qos, std::bind(
fp,
obj.get(), std::placeholders::_1), VoidPtr(), transport_hints);
obj, std::placeholders::_1), VoidPtr(), transport_hints);
}

template<class T>
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)
bool /*allow_concurrent_callbacks*/ = false)
{
return subscribe(
base_topic, queue_size, std::bind(
fp,
obj.get(), std::placeholders::_1), VoidPtr(), transport_hints);
obj, std::placeholders::_1), VoidPtr(), transport_hints);
}

//! Subscribe to a point cloud topic, version for class member function with shared_ptr.
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 Down Expand Up @@ -92,7 +94,7 @@ class PublisherPlugin

//! 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;

//! 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
virtual std::string getTransportName() const override
{
return "raw";
}
Expand All @@ -65,27 +65,27 @@ class RawPublisher
{
}

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

protected:
virtual 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(
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
virtual 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 @@ -199,7 +199,7 @@ class SimplePublisherPlugin : public point_cloud_transport::PublisherPlugin
virtual 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
2 changes: 1 addition & 1 deletion point_cloud_transport/src/publisher_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ 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

0 comments on commit 8b87df6

Please sign in to comment.