forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathwaitable.hpp
More file actions
212 lines (191 loc) · 6.19 KB
/
waitable.hpp
File metadata and controls
212 lines (191 loc) · 6.19 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
// Copyright 2018 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP__WAITABLE_HPP_
#define RCLCPP__WAITABLE_HPP_
#include <atomic>
#include <memory>
#include "rclcpp/macros.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rcl/wait.h"
namespace rclcpp
{
class Waitable
{
public:
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(Waitable)
RCLCPP_PUBLIC
virtual ~Waitable() = default;
/// Get the number of ready subscriptions
/**
* Returns a value of 0 by default.
* This should be overridden if the Waitable contains one or more subscriptions.
* \return The number of subscriptions associated with the Waitable.
*/
RCLCPP_PUBLIC
virtual
size_t
get_number_of_ready_subscriptions();
/// Get the number of ready timers
/**
* Returns a value of 0 by default.
* This should be overridden if the Waitable contains one or more timers.
* \return The number of timers associated with the Waitable.
*/
RCLCPP_PUBLIC
virtual
size_t
get_number_of_ready_timers();
/// Get the number of ready clients
/**
* Returns a value of 0 by default.
* This should be overridden if the Waitable contains one or more clients.
* \return The number of clients associated with the Waitable.
*/
RCLCPP_PUBLIC
virtual
size_t
get_number_of_ready_clients();
/// Get the number of ready events
/**
* Returns a value of 0 by default.
* This should be overridden if the Waitable contains one or more events.
* \return The number of events associated with the Waitable.
*/
RCLCPP_PUBLIC
virtual
size_t
get_number_of_ready_events();
/// Get the number of ready services
/**
* Returns a value of 0 by default.
* This should be overridden if the Waitable contains one or more services.
* \return The number of services associated with the Waitable.
*/
RCLCPP_PUBLIC
virtual
size_t
get_number_of_ready_services();
/// Get the number of ready guard_conditions
/**
* Returns a value of 0 by default.
* This should be overridden if the Waitable contains one or more guard_conditions.
* \return The number of guard_conditions associated with the Waitable.
*/
RCLCPP_PUBLIC
virtual
size_t
get_number_of_ready_guard_conditions();
/// Add the Waitable to a wait set.
/**
* \param[in] wait_set A handle to the wait set to add the Waitable to.
* \return `true` if the Waitable is added successfully, `false` otherwise.
* \throws rclcpp::execptions::RCLError from rcl_wait_set_add_*()
*/
RCLCPP_PUBLIC
virtual
bool
add_to_wait_set(rcl_wait_set_t * wait_set) = 0;
/// Check if the Waitable is ready.
/**
* The input wait set should be the same that was used in a previously call to
* `add_to_wait_set()`.
* The wait set should also have been previously waited on with `rcl_wait()`.
*
* \param[in] wait_set A handle to the wait set the Waitable was previously added to
* and that has been waited on.
* \return `true` if the Waitable is ready, `false` otherwise.
*/
RCLCPP_PUBLIC
virtual
bool
is_ready(rcl_wait_set_t * wait_set) = 0;
/// Take the data so that it can be consumed with `execute`.
/**
* NOTE: take_data is a partial fix to a larger design issue with the
* multithreaded executor. This method is likely to be removed when
* a more permanent fix is implemented. A longterm fix is currently
* being discussed here: https://github.com/ros2/rclcpp/pull/1276
*
* This method takes the data from the underlying data structure and
* writes it to the void shared pointer `data` that is passed into the
* method. The `data` can then be executed with the `execute` method.
*
* Before calling this method, the Waitable should be added to a wait set,
* waited on, and then updated.
*
* Example usage:
*
* ```cpp
* // ... create a wait set and a Waitable
* // Add the Waitable to the wait set
* bool add_ret = waitable.add_to_wait_set(wait_set);
* // ... error handling
* // Wait
* rcl_ret_t wait_ret = rcl_wait(wait_set);
* // ... error handling
* // Update the Waitable
* waitable.update(wait_set);
* // Execute any entities of the Waitable that may be ready
* std::shared_ptr<void> data = waitable.take_data();
* ```
*/
RCLCPP_PUBLIC
virtual
std::shared_ptr<void>
take_data() = 0;
/// Execute data that is passed in.
/**
* Before calling this method, the Waitable should be added to a wait set,
* waited on, and then updated - and the `take_data` method should be
* called.
*
* Example usage:
*
* ```cpp
* // ... create a wait set and a Waitable
* // Add the Waitable to the wait set
* bool add_ret = waitable.add_to_wait_set(wait_set);
* // ... error handling
* // Wait
* rcl_ret_t wait_ret = rcl_wait(wait_set);
* // ... error handling
* // Update the Waitable
* waitable.update(wait_set);
* // Execute any entities of the Waitable that may be ready
* std::shared_ptr<void> data = waitable.take_data();
* waitable.execute(data);
* ```
*/
RCLCPP_PUBLIC
virtual
void
execute(std::shared_ptr<void> & data) = 0;
/// Exchange the "in use by wait set" state for this timer.
/**
* This is used to ensure this timer is not used by multiple
* wait sets at the same time.
*
* \param[in] in_use_state the new state to exchange into the state, true
* indicates it is now in use by a wait set, and false is that it is no
* longer in use by a wait set.
* \returns the previous state.
*/
RCLCPP_PUBLIC
bool
exchange_in_use_by_wait_set_state(bool in_use_state);
private:
std::atomic<bool> in_use_by_wait_set_{false};
}; // class Waitable
} // namespace rclcpp
#endif // RCLCPP__WAITABLE_HPP_