core.h
Go to the documentation of this file.
1 #pragma once
2 
4 
5 #ifdef ROS2 /**********************************************************************************************************/
6 #include "rclcpp/rclcpp.hpp"
7 
8 #include <experimental/optional>
9 
10 namespace ensenso
11 {
12 namespace std
13 {
14 using ::std::bind;
15 using ::std::function;
16 using ::std::make_shared;
18 using ::std::experimental::optional;
19 } // namespace std
20 
21 namespace ros
22 {
23 template <typename T>
24 using Publisher = typename ::rclcpp::Publisher<T>::SharedPtr;
25 
26 template <typename T>
27 using Subscription = typename ::rclcpp::Subscription<T>::SharedPtr;
28 
29 template <typename T>
30 inline ensenso::ros::Publisher<T> create_publisher(ensenso::ros::NodeHandle& nh, ::std::string const& topic_name,
31  int queue_size)
32 {
33  return nh->node()->create_publisher<T>(topic_name, queue_size);
34 }
35 
36 template <typename T, typename C, typename M>
37 inline ensenso::ros::Subscription<T> create_subscription(ensenso::ros::NodeHandle& nh, ::std::string const& topic_name,
38  int queue_size, void (C::*callback)(M), C* object)
39 {
40  return nh->node()->create_subscription<T>(topic_name, queue_size,
41  ::std::bind(callback, object, ::std::placeholders::_1));
42 }
43 
44 inline ::std::string get_node_name(NodeHandle& nh)
45 {
46  return ::std::string(nh->get_base_interface()->get_name());
47 }
48 
49 template <typename T>
50 inline bool get_parameter(NodeHandle& nh, const char* name, T& parameter)
51 {
52  try
53  {
54  return nh->node()->get_parameter(name, parameter);
55  }
56  catch (...)
57  {
58  return false;
59  }
60 }
61 
62 template <typename T>
63 inline bool get_parameter(NodeHandle& nh, ::std::string const& name, T& parameter)
64 {
65  return get_parameter(nh, name.c_str(), parameter);
66 }
67 
68 inline bool ok()
69 {
70  return rclcpp::ok();
71 }
72 } // namespace ros
73 } // namespace ensenso
74 
75 #include <rcpputils/asserts.hpp>
76 #define ENSENSO_ASSERT(cond) rcpputils::assert_true(cond)
77 
78 #else /*****ROS1*******************************************************************************************************/
79 #include <boost/optional.hpp>
80 #include <boost/bind.hpp>
81 #include <boost/function.hpp>
82 #include <boost/make_shared.hpp>
83 #include <memory>
84 
85 #include <ros/ros.h>
86 namespace ensenso
87 {
88 namespace std
89 {
90 using boost::bind;
91 using boost::function;
92 using boost::make_shared;
93 using boost::optional;
94 
95 template <typename T>
97 
98 template <typename T, typename... Args>
99 ::std::unique_ptr<T> make_unique(Args&&... args)
100 {
101  return ::std::unique_ptr<T>(new T(::std::forward<Args>(args)...));
102 }
103 
104 /* Source for do_release and to_std:
105  * https://stackoverflow.com/questions/6326757/conversion-from-boostshared-ptr-to-stdshared-ptr
106  */
107 template <typename T>
108 void do_release(typename boost::shared_ptr<T> const&, T*)
109 {
110 }
111 
112 template <typename T>
113 typename std::shared_ptr<T> to_std(typename boost::shared_ptr<T> const& p)
114 {
115  return std::shared_ptr<T>(p.get(), boost::bind(&do_release<T>, p, _1));
116 }
117 } // namespace std
118 
119 namespace ros
120 {
121 template <typename T>
122 using Publisher = ::std::unique_ptr< ::ros::Publisher>;
123 
124 template <typename T>
126 
127 template <typename T>
128 inline ensenso::ros::Publisher<T> create_publisher(ensenso::ros::NodeHandle& nh, ::std::string const& topic_name,
129  int queue_size)
130 {
131  return ensenso::std::make_unique< ::ros::Publisher>(nh.advertise<T>(topic_name, queue_size));
132 }
133 
134 template <typename T, typename C, typename M>
136  int queue_size, void (C::*callback)(M), C* object)
137 {
138  return nh.subscribe(topic_name, queue_size, callback, object);
139 }
140 
141 inline ::std::string get_node_name(NodeHandle& nh)
142 {
143  (void)nh;
144  return ::ros::this_node::getName();
145 }
146 
147 template <typename T>
148 inline bool get_parameter(NodeHandle& nh, const char* name, T& parameter)
149 {
150  return nh.getParam(name, parameter);
151 }
152 
153 template <typename T>
154 inline bool get_parameter(NodeHandle& nh, const ::std::string& name, T& parameter)
155 {
156  return nh.getParam(name, parameter);
157 }
158 
159 inline bool ok()
160 {
161  return ros::ok();
162 }
163 } // namespace ros
164 } // namespace ensenso
165 
166 #define ENSENSO_ASSERT(cond) ROS_ASSERT(cond)
167 #endif
ensenso::std::shared_ptr
::std::shared_ptr< T > shared_ptr
Definition: core.h:96
boost::shared_ptr
ensenso::std::make_unique
::std::unique_ptr< T > make_unique(Args &&... args)
Definition: core.h:99
ros
ros.h
ensenso::std::do_release
void do_release(typename boost::shared_ptr< T > const &, T *)
Definition: core.h:108
ensenso
Definition: point_cloud_utilities.h:5
ensenso::std::to_std
std::shared_ptr< T > to_std(typename boost::shared_ptr< T > const &p)
Definition: core.h:113
ensenso::ros::Subscription
::ros::Subscriber Subscription
Definition: core.h:125
ensenso::ros::get_node_name
inline ::std::string get_node_name(NodeHandle &nh)
Definition: core.h:141
ensenso::ros::get_parameter
bool get_parameter(NodeHandle &nh, const char *name, T &parameter)
Definition: core.h:148
ensenso::ros::create_publisher
ensenso::ros::Publisher< T > create_publisher(ensenso::ros::NodeHandle &nh, ::std::string const &topic_name, int queue_size)
Definition: core.h:128
ensenso::ros::NodeHandle
::ros::NodeHandle NodeHandle
Definition: node.h:215
ensenso::ros::ok
bool ok()
Definition: core.h:159
std
ensenso::ros::Publisher
::std::unique_ptr< ::ros::Publisher > Publisher
Definition: core.h:122
args
ros::Subscriber
ensenso::ros::create_subscription
ensenso::ros::Subscription< T > create_subscription(ensenso::ros::NodeHandle &nh, ::std::string const &topic_name, int queue_size, void(C::*callback)(M), C *object)
Definition: core.h:135
node_handle.h


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