Program Listing for File subscriber_plugin.hpp
↰ Return to documentation for file (include/point_cloud_transport/subscriber_plugin.hpp
)
// Copyright (c) 2023, Czech Technical University in Prague
// Copyright (c) 2019, paplhjak
// Copyright (c) 2009, Willow Garage, Inc.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the copyright holder nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
#ifndef POINT_CLOUD_TRANSPORT__SUBSCRIBER_PLUGIN_HPP_
#define POINT_CLOUD_TRANSPORT__SUBSCRIBER_PLUGIN_HPP_
#include <list>
#include <memory>
#include <string>
#include <optional>
#include "rclcpp/macros.hpp"
#include "rclcpp/node.hpp"
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <rcpputils/tl_expected/expected.hpp>
#include <point_cloud_transport/transport_hints.hpp>
#include "point_cloud_transport/visibility_control.hpp"
namespace point_cloud_transport
{
class POINT_CLOUD_TRANSPORT_PUBLIC SubscriberPlugin
{
public:
typedef tl::expected<std::optional<sensor_msgs::msg::PointCloud2::ConstSharedPtr>,
std::string> DecodeResult;
SubscriberPlugin() = default;
SubscriberPlugin(const SubscriberPlugin &) = delete;
SubscriberPlugin & operator=(const SubscriberPlugin &) = delete;
virtual ~SubscriberPlugin() = default;
typedef std::function<void (const sensor_msgs::msg::PointCloud2::ConstSharedPtr &)> Callback;
virtual std::string getTransportName() const = 0;
virtual DecodeResult decode(const std::shared_ptr<rclcpp::SerializedMessage> & compressed) const =
0;
void subscribe(
std::shared_ptr<rclcpp::Node> node, const std::string & base_topic,
const Callback & callback,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions())
{
return subscribeImpl(node, base_topic, callback, custom_qos, options);
}
void subscribe(
std::shared_ptr<rclcpp::Node> node, const std::string & base_topic,
void (* fp)(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &),
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions())
{
return subscribe(
node, base_topic,
std::function<void(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &)>(fp),
custom_qos, options);
}
template<class T>
void subscribe(
std::shared_ptr<rclcpp::Node> node, const std::string & base_topic,
void (T::* fp)(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &), T * obj,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions())
{
return subscribe(
node, base_topic,
std::bind(fp, obj, std::placeholders::_1), custom_qos, options);
}
virtual std::string getTopic() const = 0;
virtual uint32_t getNumPublishers() const = 0;
virtual void shutdown() = 0;
virtual std::string getDataType() const = 0;
virtual void declareParameters() = 0;
virtual std::string getTopicToSubscribe(const std::string & base_topic) const = 0;
static std::string getLookupName(const std::string & transport_type)
{
return "point_cloud_transport/" + transport_type + "_sub";
}
protected:
virtual void subscribeImpl(
std::shared_ptr<rclcpp::Node> node,
const std::string & base_topic,
const Callback & callback,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default) = 0;
virtual void subscribeImpl(
std::shared_ptr<rclcpp::Node> node,
const std::string & base_topic,
const Callback & callback,
rmw_qos_profile_t custom_qos,
rclcpp::SubscriptionOptions options) = 0;
};
} // namespace point_cloud_transport
#endif // POINT_CLOUD_TRANSPORT__SUBSCRIBER_PLUGIN_HPP_