include
ensenso_camera
ros2
node.h
Go to the documentation of this file.
1
#pragma once
2
3
#include "
ensenso_camera/ros2/node_handle.h
"
4
5
// ---------------------------------------------------------------------------------------------------------------------
6
// Code from ROS2 visibility_control.h
7
// ---------------------------------------------------------------------------------------------------------------------
8
9
#ifdef ROS2
/**********************************************************************************************************/
10
#ifndef ENSENSO_CAMERA__VISIBILITY_CONTROL_H_
11
#define ENSENSO_CAMERA__VISIBILITY_CONTROL_H_
12
13
#ifdef __cplusplus
14
extern
"C"
{
15
#endif
16
17
// This logic was borrowed (then namespaced) from the examples on the gcc wiki:
18
// https://gcc.gnu.org/wiki/Visibility
19
20
#if defined _WIN32 || defined __CYGWIN__
21
#ifdef __GNUC__
22
#define ENSENSO_CAMERA_EXPORT __attribute__((dllexport))
23
#define ENSENSO_CAMERA_IMPORT __attribute__((dllimport))
24
#else
25
#define ENSENSO_CAMERA_EXPORT __declspec(dllexport)
26
#define ENSENSO_CAMERA_IMPORT __declspec(dllimport)
27
#endif
28
#ifdef ENSENSO_CAMERA_BUILDING_DLL
29
#define ENSENSO_CAMERA_PUBLIC ENSENSO_CAMERA_EXPORT
30
#else
31
#define ENSENSO_CAMERA_PUBLIC ENSENSO_CAMERA_IMPORT
32
#endif
33
#define ENSENSO_CAMERA_PUBLIC_TYPE ENSENSO_CAMERA_PUBLIC
34
#define ENSENSO_CAMERA_LOCAL
35
#else
36
#define ENSENSO_CAMERA_EXPORT __attribute__((visibility("default")))
37
#define ENSENSO_CAMERA_IMPORT
38
#if __GNUC__ >= 4
39
#define ENSENSO_CAMERA_PUBLIC __attribute__((visibility("default")))
40
#define ENSENSO_CAMERA_LOCAL __attribute__((visibility("hidden")))
41
#else
42
#define ENSENSO_CAMERA_PUBLIC
43
#define ENSENSO_CAMERA_LOCAL
44
#endif
45
#define ENSENSO_CAMERA_PUBLIC_TYPE
46
#endif
47
48
#ifdef __cplusplus
49
}
50
#endif
51
52
#endif // ENSENSO_CAMERA__VISIBILITY_CONTROL_H_
53
#endif // ROS2
54
55
// ---------------------------------------------------------------------------------------------------------------------
56
// Macros for unifying ROS1 nodelets and ROS2 nodes (which can be run as components)
57
// ---------------------------------------------------------------------------------------------------------------------
58
59
#ifdef ROS2
/**********************************************************************************************************/
60
#include "rclcpp_components/register_node_macro.hpp"
61
62
#define GENERATE_NODE_CLASS(ClassName) \
63
class ClassName##Node : public rclcpp::Node \
64
{ \
65
public: \
66
ENSENSO_CAMERA_PUBLIC \
67
explicit ClassName##Node(rclcpp::NodeOptions const& options = rclcpp::NodeOptions()); \
68
~ClassName##Node(); \
69
\
70
private: \
71
std::string cameraType; \
72
std::unique_ptr<ClassName> camera; \
73
};
74
75
#define GENERATE_NODE_CLASS_IMPL(ClassName, CameraType) \
76
ClassName##Node::ClassName##Node(rclcpp::NodeOptions const& options) \
77
: Node(#ClassName "Node", options), cameraType(CameraType) \
78
{ \
79
DECLARE_NODE_PARAMETERS(this); \
80
\
81
auto nh = create_node_handle(this); \
82
ensenso::ros::NodeHandleWrapper nhw = ensenso::ros::NodeHandleWrapper(std::move(nh)); \
83
\
84
camera_node::initNxLib(nhw.getPrivateNodeHandle()); \
85
\
86
camera = camera_node::initCamera<ClassName>(nhw, cameraType); \
87
} \
88
\
89
ClassName##Node::~ClassName##Node() \
90
{ \
91
camera->close(); \
92
}
93
94
#define NODE_PUBLIC_INTERFACE(ClassName) \
95
ENSENSO_CAMERA_PUBLIC \
96
explicit ClassName##Node(rclcpp::NodeOptions const& options = rclcpp::NodeOptions()); \
97
~ClassName##Node(); \
98
void onInit()
99
100
#define NODE_CTOR_IMPL_HEADER(ClassName) \
101
ClassName##Node::ClassName##Node(rclcpp::NodeOptions const& options) : Node(#ClassName "Node", options),
102
103
#define NODE_DTOR_IMPL_HEADER(ClassName) ClassName##Node::~ClassName##Node()
104
105
#define NODE_ON_INIT_IMPL_HEADER(ClassName) void ClassName##Node::onInit()
106
107
#define SINGLE_NODE_CLASS(ClassName) class ClassName : public rclcpp::Node
108
#define SINGLE_NODE_CTOR(ClassName, NodeName) ClassName() : Node(NodeName)
109
110
#define REGISTER_NODE(ClassName) RCLCPP_COMPONENTS_REGISTER_NODE(ClassName##Node)
111
112
#define DECLARE_NODE_PARAMETERS(node) \
113
node->declare_parameter<std::string>("serial", ""); \
114
node->declare_parameter<std::string>("settings", ""); \
115
node->declare_parameter<std::string>("file_camera_path", ""); \
116
node->declare_parameter<bool>("fixed", false); \
117
node->declare_parameter<int>("threads", -1); \
118
node->declare_parameter<std::string>("camera_frame", ""); \
119
node->declare_parameter<std::string>("target_frame", ""); \
120
node->declare_parameter<std::string>("link_frame", ""); \
121
node->declare_parameter<std::string>("robot_frame", ""); \
122
node->declare_parameter<std::string>("wrist_frame", ""); \
123
node->declare_parameter<int>("tcp_port", -1); \
124
node->declare_parameter<bool>("wait_for_camera", false); \
125
node->declare_parameter<int>("capture_timeout", 0); \
126
node->declare_parameter<std::string>("objects_file", ""); \
127
node->declare_parameter<std::string>("objects_frame", ""); \
128
node->declare_parameter<std::string>("visualization_marker_topic", ""); \
129
node->declare_parameter<double>("visualization_marker_rate", 1.0);
130
131
namespace
ensenso
132
{
133
namespace
ros
134
{
135
struct
NodeHandleWrapper
136
{
137
NodeHandle
nh
;
138
139
NodeHandleWrapper
(
NodeHandle
nh
) :
nh
(::
std
::
move
(
nh
))
140
{
141
}
142
143
NodeHandle
&
getNodeHandle
()
144
{
145
return
nh
;
146
}
147
148
NodeHandle
&
getPrivateNodeHandle
()
149
{
150
return
nh
;
151
}
152
};
153
}
// namespace ros
154
}
// namespace ensenso
155
156
#define CREATE_NODE_HANDLE_WRAPPER(name) \
157
rclcpp::Node::SharedPtr name##_ = shared_from_this(); \
158
ensenso::ros::NodeHandleWrapper name = ensenso::ros::NodeHandleWrapper(std::move(name##_));
159
160
#else
/***ROS1*********************************************************************************************************/
161
#include <
nodelet/nodelet.h
>
162
#include <
pluginlib/class_list_macros.h
>
163
164
#define GENERATE_NODE_CLASS(ClassName) \
165
class ClassName##Nodelet : public nodelet::Nodelet \
166
{ \
167
public: \
168
ClassName##Nodelet(); \
169
~ClassName##Nodelet(); \
170
void onInit() override; \
171
\
172
private: \
173
std::string cameraType; \
174
std::unique_ptr<ClassName> camera; \
175
};
176
177
#define GENERATE_NODE_CLASS_IMPL(ClassName, CameraType) \
178
ClassName##Nodelet::ClassName##Nodelet() : cameraType(CameraType) \
179
{ \
180
} \
181
\
182
ClassName##Nodelet::~ClassName##Nodelet() \
183
{ \
184
camera->close(); \
185
} \
186
\
187
void ClassName##Nodelet::onInit() \
188
{ \
189
CREATE_NODE_HANDLE_WRAPPER(nh) \
190
camera_node::initNxLib(nh.getPrivateNodeHandle()); \
191
camera = camera_node::initCamera<ClassName>(nh, cameraType); \
192
}
193
194
#define NODE_PUBLIC_INTERFACE(ClassName) \
195
public: \
196
ClassName##Nodelet(); \
197
~ClassName##Nodelet(); \
198
void onInit() override
199
200
#define NODE_CTOR_IMPL_HEADER(ClassName) ClassName##Nodelet::ClassName##Nodelet() :
201
202
#define NODE_DTOR_IMPL_HEADER(ClassName) ClassName##Nodelet::~ClassName##Nodelet()
203
204
#define NODE_ON_INIT_IMPL_HEADER(ClassName) void ClassName##Nodelet::onInit()
205
206
#define SINGLE_NODE_CLASS(ClassName) class ClassName
207
#define SINGLE_NODE_CTOR(ClassName, NodeName) ClassName()
208
209
#define REGISTER_NODE(ClassName) PLUGINLIB_EXPORT_CLASS(ClassName##Nodelet, nodelet::Nodelet)
210
211
namespace
ensenso
212
{
213
namespace
ros
214
{
215
using
NodeHandle
=
::ros::NodeHandle
;
216
217
struct
NodeHandleWrapper
218
{
219
NodeHandle
nh
;
220
NodeHandle
nhPrivate
;
221
222
NodeHandleWrapper
(
NodeHandle
&
nh
,
NodeHandle
&
nhPrivate
) :
nh
(
nh
),
nhPrivate
(
nhPrivate
)
223
{
224
}
225
NodeHandle
&
getNodeHandle
()
226
{
227
return
nh
;
228
}
229
NodeHandle
&
getPrivateNodeHandle
()
230
{
231
return
nhPrivate
;
232
}
233
};
234
}
// namespace ros
235
}
// namespace ensenso
236
237
#define CREATE_NODE_HANDLE_WRAPPER(name) \
238
ensenso::ros::NodeHandleWrapper name = ensenso::ros::NodeHandleWrapper(getNodeHandle(), getPrivateNodeHandle());
239
#endif
ros
ensenso::ros::NodeHandleWrapper::NodeHandleWrapper
NodeHandleWrapper(NodeHandle &nh, NodeHandle &nhPrivate)
Definition:
node.h:222
ensenso
Definition:
point_cloud_utilities.h:5
ensenso::ros::NodeHandleWrapper::nh
NodeHandle nh
Definition:
node.h:219
class_list_macros.h
ensenso::ros::NodeHandleWrapper::getPrivateNodeHandle
NodeHandle & getPrivateNodeHandle()
Definition:
node.h:229
ensenso::ros::NodeHandle
::ros::NodeHandle NodeHandle
Definition:
node.h:215
ensenso::ros::NodeHandleWrapper
Definition:
node.h:217
std
nodelet.h
ensenso::ros::NodeHandleWrapper::getNodeHandle
NodeHandle & getNodeHandle()
Definition:
node.h:225
ensenso::ros::NodeHandleWrapper::nhPrivate
NodeHandle nhPrivate
Definition:
node.h:220
node_handle.h
move
void move(std::vector< T > &a, std::vector< T > &b)
ensenso_camera
Author(s): Ensenso
autogenerated on Wed Apr 2 2025 02:37:46