11 #define NODE_CLASS_NAME TexturePointCloudNode 12 #define NODE_NAME "texture_point_cloud" 16 #include <image_transport/image_transport.hpp> 17 #include <image_transport/transport_hints.hpp> 32 ::std::string
const& topic_name)
38 ::std::string
const& topic_name)
45 void (T::*callback)(sensor_msgs::msg::ImageConstPtr
const&),
50 std::bind(callback,
object, ::std::placeholders::_1),
51 ensenso::image_transport::get_default_transport(nh));
65 ::std::string
const& topic_name)
72 ::std::string
const& topic_name)
75 return imageTransport.
advertise(topic_name, 1);
80 void (T::*callback)(sensor_msgs::msg::ImageConstPtr
const&),
84 return imageTransport.
subscribe(topic_name, 10, callback,
object);
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
inline ::image_transport::Subscriber create_subscription(ensenso::ros::NodeHandle &nh, ::std::string const &topic_name, void(T::*callback)(sensor_msgs::msg::ImageConstPtr const &), T *object)
const std::string & getTransport() const
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
inline ::image_transport::CameraPublisher create_camera_publisher(ensenso::ros::NodeHandle const &nh, ::std::string const &topic_name)
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
::ros::NodeHandle NodeHandle
::std::unique_ptr< ::ros::Publisher > Publisher
inline ::image_transport::Publisher create_publisher(ensenso::ros::NodeHandle const &nh, ::std::string const &topic_name)