image_transport.h
Go to the documentation of this file.
1 #pragma once
2 
5 
7 
8 #include <mutex>
9 #include <string>
10 
11 #define NODE_CLASS_NAME TexturePointCloudNode
12 #define NODE_NAME "texture_point_cloud"
13 
14 #ifdef ROS2 /**********************************************************************************************************/
15 
16 #include <image_transport/image_transport.hpp>
17 #include <image_transport/transport_hints.hpp>
18 
19 namespace ensenso
20 {
21 namespace image_transport
22 {
23 // https://github.com/ros-perception/image_common/blob/galactic/image_transport/src/image_transport.cpp
24 // https://github.com/ros-perception/image_common/blob/galactic/image_transport/include/image_transport/transport_hints.hpp
25 inline ::std::string get_default_transport(ensenso::ros::NodeHandle& nh)
26 {
27  ::image_transport::TransportHints transportHints(nh->node());
28  return transportHints.getTransport();
29 }
30 
31 inline ::image_transport::CameraPublisher create_camera_publisher(ensenso::ros::NodeHandle const& nh,
32  ::std::string const& topic_name)
33 {
35 }
36 
38  ::std::string const& topic_name)
39 {
40  return ::image_transport::create_publisher(nh->node(), topic_name);
41 }
42 
43 template <typename T>
44 inline ::image_transport::Subscriber create_subscription(ensenso::ros::NodeHandle& nh, ::std::string const& topic_name,
45  void (T::*callback)(sensor_msgs::msg::ImageConstPtr const&),
46  T* object)
47 {
48  /* https://github.com/ros-perception/image_common/issues/121 */
49  return ::image_transport::create_subscription(nh->node(), topic_name,
50  std::bind(callback, object, ::std::placeholders::_1),
51  ensenso::image_transport::get_default_transport(nh));
52 }
53 
54 } // namespace image_transport
55 } // namespace ensenso
56 
57 #else /***ROS1*********************************************************************************************************/
59 
60 namespace ensenso
61 {
62 namespace image_transport
63 {
64 inline ::image_transport::CameraPublisher create_camera_publisher(ensenso::ros::NodeHandle const& nh,
65  ::std::string const& topic_name)
66 {
67  ::image_transport::ImageTransport imageTransport(nh);
68  return imageTransport.advertiseCamera(topic_name, 1);
69 }
70 
72  ::std::string const& topic_name)
73 {
74  ::image_transport::ImageTransport imageTransport(nh);
75  return imageTransport.advertise(topic_name, 1);
76 }
77 
78 template <typename T>
79 inline ::image_transport::Subscriber create_subscription(ensenso::ros::NodeHandle& nh, ::std::string const& topic_name,
80  void (T::*callback)(sensor_msgs::msg::ImageConstPtr const&),
81  T* object)
82 {
83  ::image_transport::ImageTransport imageTransport(nh);
84  return imageTransport.subscribe(topic_name, 10, callback, object);
85 }
86 } // namespace image_transport
87 } // namespace ensenso
88 #endif
image_transport::ImageTransport
ensenso::image_transport::create_subscription
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)
Definition: image_transport.h:79
image_transport::TransportHints::getTransport
const std::string & getTransport() const
ensenso
Definition: point_cloud_utilities.h:5
namespace.h
image_transport::ImageTransport::advertiseCamera
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::ImageTransport::advertise
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ensenso::image_transport::create_camera_publisher
inline ::image_transport::CameraPublisher create_camera_publisher(ensenso::ros::NodeHandle const &nh, ::std::string const &topic_name)
Definition: image_transport.h:64
image_transport::ImageTransport::subscribe
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())
ensenso::ros::NodeHandle
::ros::NodeHandle NodeHandle
Definition: node.h:215
image.h
image_transport.h
ensenso::image_transport::create_publisher
inline ::image_transport::Publisher create_publisher(ensenso::ros::NodeHandle const &nh, ::std::string const &topic_name)
Definition: image_transport.h:71
image_transport
ensenso::ros::Publisher
::std::unique_ptr< ::ros::Publisher > Publisher
Definition: core.h:122
image_transport::TransportHints
node_handle.h


ensenso_camera
Author(s): Ensenso
autogenerated on Wed Apr 2 2025 02:37:46