@@ -29,6 +29,8 @@ extern "C"
29
29
30
30
#include "rclc/executor_handle.h"
31
31
#include "rclc/types.h"
32
+ #include "rclc/sleep.h"
33
+ #include "rclc/visibility_control.h"
32
34
33
35
/*! \file executor.h
34
36
\brief The RCLC-Executor provides an Executor based on RCL in which all callbacks are
@@ -84,6 +86,7 @@ typedef struct
84
86
* Return a rclc_executor_t struct with pointer members initialized to `NULL`
85
87
* and member variables to 0.
86
88
*/
89
+ RCLC_PUBLIC
87
90
rclc_executor_t
88
91
rclc_executor_get_zero_initialized_executor (void );
89
92
@@ -110,6 +113,7 @@ rclc_executor_get_zero_initialized_executor(void);
110
113
* \return `RCL_RET_INVALID_ARGUMENT` if any null pointer as argument
111
114
* \return `RCL_RET_ERROR` in case of failure
112
115
*/
116
+ RCLC_PUBLIC
113
117
rcl_ret_t
114
118
rclc_executor_init (
115
119
rclc_executor_t * executor ,
@@ -134,6 +138,7 @@ rclc_executor_init(
134
138
* \return `RCL_RET_INVALID_ARGUMENT` if \p executor is a null pointer
135
139
* \return `RCL_RET_ERROR` in an error occured
136
140
*/
141
+ RCLC_PUBLIC
137
142
rcl_ret_t
138
143
rclc_executor_set_timeout (
139
144
rclc_executor_t * executor ,
@@ -155,6 +160,7 @@ rclc_executor_set_timeout(
155
160
* \return `RCL_RET_OK` if semantics was set successfully
156
161
* \return `RCL_RET_INVALID_ARGUMENT` if \p executor is a null pointer
157
162
*/
163
+ RCLC_PUBLIC
158
164
rcl_ret_t
159
165
rclc_executor_set_semantics (
160
166
rclc_executor_t * executor ,
@@ -179,6 +185,7 @@ rclc_executor_set_semantics(
179
185
* \return `RCL_RET_INVALID_ARGUMENT` if \p executor.handles is a null pointer
180
186
* \return `RCL_RET_ERROR` in an error occured (aka executor was not initialized)
181
187
*/
188
+ RCLC_PUBLIC
182
189
rcl_ret_t
183
190
rclc_executor_fini (rclc_executor_t * executor );
184
191
@@ -205,6 +212,7 @@ rclc_executor_fini(rclc_executor_t * executor);
205
212
* \return `RCL_RET_INVALID_ARGUMENT` if any parameter is a null pointer
206
213
* \return `RCL_RET_ERROR` if any other error occured
207
214
*/
215
+ RCLC_PUBLIC
208
216
rcl_ret_t
209
217
rclc_executor_add_subscription (
210
218
rclc_executor_t * executor ,
@@ -233,6 +241,7 @@ rclc_executor_add_subscription(
233
241
* \return `RCL_RET_INVALID_ARGUMENT` if any parameter is a null pointer
234
242
* \return `RCL_RET_ERROR` if any other error occured
235
243
*/
244
+ RCLC_PUBLIC
236
245
rcl_ret_t
237
246
rclc_executor_add_timer (
238
247
rclc_executor_t * executor ,
@@ -261,6 +270,7 @@ rclc_executor_add_timer(
261
270
* \return `RCL_RET_INVALID_ARGUMENT` if any parameter is a null pointer
262
271
* \return `RCL_RET_ERROR` if any other error occured
263
272
*/
273
+ RCLC_PUBLIC
264
274
rcl_ret_t
265
275
rclc_executor_add_client (
266
276
rclc_executor_t * executor ,
@@ -290,6 +300,7 @@ rclc_executor_add_client(
290
300
* \return `RCL_RET_INVALID_ARGUMENT` if any parameter is a null pointer
291
301
* \return `RCL_RET_ERROR` if any other error occured
292
302
*/
303
+ RCLC_PUBLIC
293
304
rcl_ret_t
294
305
rclc_executor_add_client_with_request_id (
295
306
rclc_executor_t * executor ,
@@ -320,6 +331,7 @@ rclc_executor_add_client_with_request_id(
320
331
* \return `RCL_RET_INVALID_ARGUMENT` if any parameter is a null pointer
321
332
* \return `RCL_RET_ERROR` if any other error occured
322
333
*/
334
+ RCLC_PUBLIC
323
335
rcl_ret_t
324
336
rclc_executor_add_service (
325
337
rclc_executor_t * executor ,
@@ -351,6 +363,7 @@ rclc_executor_add_service(
351
363
* \return `RCL_RET_INVALID_ARGUMENT` if any parameter is a null pointer
352
364
* \return `RCL_RET_ERROR` if any other error occured
353
365
*/
366
+ RCLC_PUBLIC
354
367
rcl_ret_t
355
368
rclc_executor_add_service_with_request_id (
356
369
rclc_executor_t * executor ,
@@ -383,6 +396,7 @@ rclc_executor_add_service_with_request_id(
383
396
* \return `RCL_RET_INVALID_ARGUMENT` if any parameter is a null pointer
384
397
* \return `RCL_RET_ERROR` if any other error occured
385
398
*/
399
+ RCLC_PUBLIC
386
400
rcl_ret_t
387
401
rclc_executor_add_service_with_context (
388
402
rclc_executor_t * executor ,
@@ -413,6 +427,7 @@ rclc_executor_add_service_with_context(
413
427
* \return `RCL_RET_INVALID_ARGUMENT` if any parameter is a null pointer
414
428
* \return `RCL_RET_ERROR` if any other error occured
415
429
*/
430
+ RCLC_PUBLIC
416
431
rcl_ret_t
417
432
rclc_executor_add_guard_condition (
418
433
rclc_executor_t * executor ,
@@ -449,6 +464,7 @@ rclc_executor_add_guard_condition(
449
464
* \return `RCL_RET_TIMEOUT` if rcl_wait() returned timeout (aka no data is avaiable during until the timeout)
450
465
* \return `RCL_RET_ERROR` if any other error occured
451
466
*/
467
+ RCLC_PUBLIC
452
468
rcl_ret_t
453
469
rclc_executor_spin_some (
454
470
rclc_executor_t * executor ,
@@ -475,6 +491,7 @@ rclc_executor_spin_some(
475
491
* \return `RCL_RET_INVALID_ARGUMENT` if executor is a null pointer
476
492
* \return `RCL_RET_ERROR` if any other error occured
477
493
*/
494
+ RCLC_PUBLIC
478
495
rcl_ret_t
479
496
rclc_executor_spin (rclc_executor_t * executor );
480
497
@@ -500,6 +517,7 @@ rclc_executor_spin(rclc_executor_t * executor);
500
517
* \return `RCL_RET_INVALID_ARGUMENT` if executor is a null pointer
501
518
* \return `RCL_RET_ERROR` if any other error occured
502
519
*/
520
+ RCLC_PUBLIC
503
521
rcl_ret_t
504
522
rclc_executor_spin_period (
505
523
rclc_executor_t * executor ,
@@ -528,6 +546,7 @@ rclc_executor_spin_period(
528
546
* \return `RCL_RET_INVALID_ARGUMENT` if executor is a null pointer
529
547
* \return `RCL_RET_ERROR` if any other error occured
530
548
*/
549
+ RCLC_PUBLIC
531
550
rcl_ret_t
532
551
rclc_executor_spin_one_period (
533
552
rclc_executor_t * executor ,
@@ -552,6 +571,7 @@ rclc_executor_spin_one_period(
552
571
* \return `RCL_RET_INVALID_ARGUMENT` if executor is a null pointer
553
572
* \return `RCL_RET_ERROR` if any other error occured
554
573
*/
574
+ RCLC_PUBLIC
555
575
rcl_ret_t
556
576
rclc_executor_set_trigger (
557
577
rclc_executor_t * executor ,
@@ -576,6 +596,7 @@ rclc_executor_set_trigger(
576
596
* \return true - if all handles are ready (subscriptions have new data, timers are ready)
577
597
* \return false - otherwise
578
598
*/
599
+ RCLC_PUBLIC
579
600
bool
580
601
rclc_executor_trigger_all (
581
602
rclc_executor_handle_t * handles ,
@@ -600,6 +621,7 @@ rclc_executor_trigger_all(
600
621
* \return true - if at least one handles is ready (subscriptions have new data, timers are ready)
601
622
* \return false - otherwise
602
623
*/
624
+ RCLC_PUBLIC
603
625
bool
604
626
rclc_executor_trigger_any (
605
627
rclc_executor_handle_t * handles ,
@@ -623,6 +645,7 @@ rclc_executor_trigger_any(
623
645
* \param [in] obj trigger_object set by rclc_executor_set_trigger (not used)
624
646
* \return true always
625
647
*/
648
+ RCLC_PUBLIC
626
649
bool
627
650
rclc_executor_trigger_always (
628
651
rclc_executor_handle_t * handles ,
@@ -648,6 +671,7 @@ rclc_executor_trigger_always(
648
671
* \return true if rcl-handle obj is ready
649
672
* \return false otherwise
650
673
*/
674
+ RCLC_PUBLIC
651
675
bool
652
676
rclc_executor_trigger_one (
653
677
rclc_executor_handle_t * handles ,
0 commit comments