Program Listing for File point_cloud_transport.hpp
↰ Return to documentation for file (include/point_cloud_transport/point_cloud_transport.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__POINT_CLOUD_TRANSPORT_HPP_
#define POINT_CLOUD_TRANSPORT__POINT_CLOUD_TRANSPORT_HPP_
#include <functional>
#include <memory>
#include <string>
#include <unordered_map>
#include <vector>
#include "rclcpp/node.hpp"
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <point_cloud_transport/loader_fwds.hpp>
#include <point_cloud_transport/publisher.hpp>
#include <point_cloud_transport/single_subscriber_publisher.hpp>
#include <point_cloud_transport/subscriber.hpp>
#include <point_cloud_transport/transport_hints.hpp>
#include "point_cloud_transport/visibility_control.hpp"
namespace point_cloud_transport
{
class PointCloudTransportLoader
{
public:
POINT_CLOUD_TRANSPORT_PUBLIC
PointCloudTransportLoader();
POINT_CLOUD_TRANSPORT_PUBLIC
virtual ~PointCloudTransportLoader();
POINT_CLOUD_TRANSPORT_PUBLIC
std::vector<std::string> getDeclaredTransports() const;
POINT_CLOUD_TRANSPORT_PUBLIC
std::unordered_map<std::string, std::string> getLoadableTransports() const;
POINT_CLOUD_TRANSPORT_PUBLIC
PubLoaderPtr getPublisherLoader() const;
POINT_CLOUD_TRANSPORT_PUBLIC
SubLoaderPtr getSubscriberLoader() const;
POINT_CLOUD_TRANSPORT_PUBLIC
point_cloud_transport::PubLoaderPtr getPubLoader();
POINT_CLOUD_TRANSPORT_PUBLIC
point_cloud_transport::SubLoaderPtr getSubLoader();
protected:
point_cloud_transport::PubLoaderPtr pub_loader_;
point_cloud_transport::SubLoaderPtr sub_loader_;
};
POINT_CLOUD_TRANSPORT_PUBLIC
Publisher create_publisher(
std::shared_ptr<rclcpp::Node> node,
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
const rclcpp::PublisherOptions & options = rclcpp::PublisherOptions());
POINT_CLOUD_TRANSPORT_PUBLIC
Subscriber create_subscription(
std::shared_ptr<rclcpp::Node> node,
const std::string & base_topic,
const Subscriber::Callback & callback,
const std::string & transport,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions());
class PointCloudTransport : public PointCloudTransportLoader
{
using VoidPtr = std::shared_ptr<void>;
public:
POINT_CLOUD_TRANSPORT_PUBLIC
explicit PointCloudTransport(rclcpp::Node::SharedPtr node);
POINT_CLOUD_TRANSPORT_PUBLIC
~PointCloudTransport() override = default;
POINT_CLOUD_TRANSPORT_PUBLIC
std::string getTransportOrDefault(const TransportHints * transport_hints)
{
std::string ret;
if (nullptr == transport_hints) {
TransportHints th(node_);
ret = th.getTransport();
} else {
ret = transport_hints->getTransport();
}
return ret;
}
POINT_CLOUD_TRANSPORT_PUBLIC
Publisher advertise(
const std::string & base_topic,
uint32_t queue_size)
{
rclcpp::PublisherOptions options = rclcpp::PublisherOptions();
rmw_qos_profile_t custom_qos = rmw_qos_profile_sensor_data;
custom_qos.depth = queue_size;
return Publisher(node_, base_topic, pub_loader_, custom_qos, options);
}
POINT_CLOUD_TRANSPORT_PUBLIC
Publisher advertise(
const std::string & base_topic,
uint32_t queue_size,
const rclcpp::PublisherOptions & options)
{
rmw_qos_profile_t custom_qos = rmw_qos_profile_sensor_data;
custom_qos.depth = queue_size;
return Publisher(node_, base_topic, pub_loader_, custom_qos, options);
}
POINT_CLOUD_TRANSPORT_PUBLIC
Publisher advertise(
const std::string & base_topic,
rmw_qos_profile_t custom_qos,
const rclcpp::PublisherOptions & options = rclcpp::PublisherOptions())
{
return Publisher(node_, base_topic, pub_loader_, custom_qos, options);
}
// //! Subscribe to a point cloud topic, version for arbitrary std::function object.
// POINT_CLOUD_TRANSPORT_PUBLIC
// point_cloud_transport::Subscriber subscribe(
// const std::string & base_topic,
// uint32_t queue_size,
// const std::function<void(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &)> & callback)
// {
// rmw_qos_profile_t custom_qos = rmw_qos_profile_sensor_data;
// custom_qos.depth = queue_size;
// return subscribe(
// base_topic, custom_qos, callback, {}, nullptr);
// }
// TODO(ros2) Implement when SubscriberStatusCallback is available
// point_cloud_transport::Publisher advertise(const std::string& base_topic, uint32_t queue_size,
// const point_cloud_transport::SubscriberStatusCallback& connect_cb,
// const point_cloud_transport::SubscriberStatusCallback& disconnect_cb = {},
// const ros::VoidPtr& tracked_object = {}, bool latch = false);
POINT_CLOUD_TRANSPORT_PUBLIC
point_cloud_transport::Subscriber subscribe(
const std::string & base_topic, rmw_qos_profile_t custom_qos,
const std::function<void(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &)> & callback,
const VoidPtr & tracked_object = {},
const point_cloud_transport::TransportHints * transport_hints = nullptr)
{
(void)tracked_object;
rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions();
return Subscriber(
node_, base_topic, callback, sub_loader_,
getTransportOrDefault(transport_hints), custom_qos, options);
}
POINT_CLOUD_TRANSPORT_PUBLIC
point_cloud_transport::Subscriber subscribe(
const std::string & base_topic, uint32_t queue_size,
const std::function<void(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &)> & callback,
const VoidPtr & tracked_object = {},
const point_cloud_transport::TransportHints * transport_hints = nullptr)
{
rmw_qos_profile_t custom_qos = rmw_qos_profile_sensor_data;
custom_qos.depth = queue_size;
return subscribe(
base_topic, custom_qos, callback, tracked_object, transport_hints);
}
POINT_CLOUD_TRANSPORT_PUBLIC
point_cloud_transport::Subscriber subscribe(
const std::string & base_topic, rmw_qos_profile_t custom_qos,
void (* fp)(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &),
const point_cloud_transport::TransportHints * transport_hints = nullptr)
{
return subscribe(
base_topic, custom_qos,
std::function<void(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &)>(fp),
VoidPtr(), transport_hints);
}
POINT_CLOUD_TRANSPORT_PUBLIC
point_cloud_transport::Subscriber subscribe(
const std::string & base_topic, uint32_t queue_size,
void (* fp)(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &),
const point_cloud_transport::TransportHints * transport_hints = nullptr)
{
return subscribe(
base_topic, queue_size,
std::function<void(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &)>(fp),
VoidPtr(), transport_hints);
}
template<class T>
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)
{
return subscribe(
base_topic, custom_qos, std::bind(
fp,
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)
{
return subscribe(
base_topic, queue_size, std::bind(
fp,
obj, std::placeholders::_1), VoidPtr(), transport_hints);
}
template<class T>
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,
const std::shared_ptr<T> & obj,
const point_cloud_transport::TransportHints * transport_hints = nullptr)
{
return subscribe(
base_topic, custom_qos, std::bind(
fp,
obj, std::placeholders::_1), obj, 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,
const std::shared_ptr<T> & obj,
const point_cloud_transport::TransportHints * transport_hints = nullptr)
{
return subscribe(
base_topic, queue_size, std::bind(
fp,
obj, std::placeholders::_1), obj, transport_hints);
}
private:
rclcpp::Node::SharedPtr node_;
};
} // namespace point_cloud_transport
#endif // POINT_CLOUD_TRANSPORT__POINT_CLOUD_TRANSPORT_HPP_