ROS 2 rclcpp + rcl - kilted  kilted
ROS 2 C++ Client Library with ROS Client Library
guard_condition.c
1 // Copyright 2015 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifdef __cplusplus
16 extern "C"
17 {
18 #endif
19 
20 #include "rcl/guard_condition.h"
21 
22 #include "rcl/error_handling.h"
23 #include "rcl/rcl.h"
24 #include "rmw/error_handling.h"
25 #include "rmw/rmw.h"
26 
27 #include "./context_impl.h"
28 
30 {
31  rmw_guard_condition_t * rmw_handle;
32  bool allocated_rmw_guard_condition;
34 };
35 
38 {
39  // All members are initialized to 0 or NULL by C99 6.7.8/10.
40  static rcl_guard_condition_t null_guard_condition;
41  return null_guard_condition;
42 }
43 
45 __rcl_guard_condition_init_from_rmw_impl(
46  rcl_guard_condition_t * guard_condition,
47  const rmw_guard_condition_t * rmw_guard_condition,
48  rcl_context_t * context,
49  const rcl_guard_condition_options_t options)
50 {
51  // This function will create an rmw_guard_condition if the parameter is null.
52 
53  // Perform argument validation.
54  const rcl_allocator_t * allocator = &options.allocator;
55  RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
56  RCL_CHECK_ARGUMENT_FOR_NULL(guard_condition, RCL_RET_INVALID_ARGUMENT);
57  // Ensure the guard_condition handle is zero initialized.
58  if (guard_condition->impl) {
59  RCL_SET_ERROR_MSG("guard_condition already initialized, or memory was unintialized");
60  return RCL_RET_ALREADY_INIT;
61  }
62  // Make sure rcl has been initialized.
63  RCL_CHECK_ARGUMENT_FOR_NULL(context, RCL_RET_INVALID_ARGUMENT);
64  if (!rcl_context_is_valid(context)) {
65  RCL_SET_ERROR_MSG(
66  "the given context is not valid, "
67  "either rcl_init() was not called or rcl_shutdown() was called.");
68  return RCL_RET_NOT_INIT;
69  }
70  // Allocate space for the guard condition impl.
71  guard_condition->impl = (rcl_guard_condition_impl_t *)allocator->allocate(
72  sizeof(rcl_guard_condition_impl_t), allocator->state);
73  if (!guard_condition->impl) {
74  RCL_SET_ERROR_MSG("allocating memory failed");
75  return RCL_RET_BAD_ALLOC;
76  }
77  // Create the rmw guard condition.
78  if (rmw_guard_condition) {
79  // If given, just assign (cast away const).
80  guard_condition->impl->rmw_handle = (rmw_guard_condition_t *)rmw_guard_condition;
81  guard_condition->impl->allocated_rmw_guard_condition = false;
82  } else {
83  // Otherwise create one.
84  guard_condition->impl->rmw_handle = rmw_create_guard_condition(&(context->impl->rmw_context));
85  if (!guard_condition->impl->rmw_handle) {
86  // Deallocate impl and exit.
87  allocator->deallocate(guard_condition->impl, allocator->state);
88  guard_condition->impl = NULL;
89  RCL_SET_ERROR_MSG(rmw_get_error_string().str);
90  return RCL_RET_ERROR;
91  }
92  guard_condition->impl->allocated_rmw_guard_condition = true;
93  }
94  // Copy options into impl.
95  guard_condition->impl->options = options;
96  return RCL_RET_OK;
97 }
98 
101  rcl_guard_condition_t * guard_condition,
102  rcl_context_t * context,
103  const rcl_guard_condition_options_t options)
104 {
105  // NULL indicates "create a new rmw guard condition".
106  return __rcl_guard_condition_init_from_rmw_impl(guard_condition, NULL, context, options);
107 }
108 
109 rcl_ret_t
111  rcl_guard_condition_t * guard_condition,
112  const rmw_guard_condition_t * rmw_guard_condition,
113  rcl_context_t * context,
114  const rcl_guard_condition_options_t options)
115 {
116  return __rcl_guard_condition_init_from_rmw_impl(
117  guard_condition, rmw_guard_condition, context, options);
118 }
119 
120 rcl_ret_t
122 {
123  // Perform argument validation.
124  RCL_CHECK_ARGUMENT_FOR_NULL(guard_condition, RCL_RET_INVALID_ARGUMENT);
125  rcl_ret_t result = RCL_RET_OK;
126  if (guard_condition->impl) {
127  // assuming the allocator is valid because it is checked in rcl_guard_condition_init()
128  rcl_allocator_t allocator = guard_condition->impl->options.allocator;
129  if (guard_condition->impl->rmw_handle && guard_condition->impl->allocated_rmw_guard_condition) {
130  if (rmw_destroy_guard_condition(guard_condition->impl->rmw_handle) != RMW_RET_OK) {
131  RCL_SET_ERROR_MSG(rmw_get_error_string().str);
132  result = RCL_RET_ERROR;
133  }
134  }
135  allocator.deallocate(guard_condition->impl, allocator.state);
136  guard_condition->impl = NULL;
137  }
138  return result;
139 }
140 
143 {
144  // !!! MAKE SURE THAT CHANGES TO THESE DEFAULTS ARE REFLECTED IN THE HEADER DOC STRING
145  rcl_guard_condition_options_t default_options;
146  default_options.allocator = rcl_get_default_allocator();
147  return default_options;
148 }
149 
150 rcl_ret_t
152 {
153  const rcl_guard_condition_options_t * options = rcl_guard_condition_get_options(guard_condition);
154  if (!options) {
155  return RCL_RET_INVALID_ARGUMENT; // error already set
156  }
157  // Trigger the guard condition.
158  if (rmw_trigger_guard_condition(guard_condition->impl->rmw_handle) != RMW_RET_OK) {
159  RCL_SET_ERROR_MSG(rmw_get_error_string().str);
160  return RCL_RET_ERROR;
161  }
162  return RCL_RET_OK;
163 }
164 
167 {
168  // Perform argument validation.
169  RCL_CHECK_ARGUMENT_FOR_NULL(guard_condition, NULL);
170  RCL_CHECK_FOR_NULL_WITH_MSG(
171  guard_condition->impl,
172  "guard condition implementation is invalid",
173  return NULL);
174  return &guard_condition->impl->options;
175 }
176 
177 rmw_guard_condition_t *
179 {
180  const rcl_guard_condition_options_t * options = rcl_guard_condition_get_options(guard_condition);
181  if (!options) {
182  return NULL; // error already set
183  }
184  return guard_condition->impl->rmw_handle;
185 }
186 
187 #ifdef __cplusplus
188 }
189 #endif
#define rcl_get_default_allocator
Return a properly initialized rcl_allocator_t with default values.
Definition: allocator.h:37
#define RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, msg, fail_statement)
Check that the given allocator is initialized, or fail with a message.
Definition: allocator.h:56
rcutils_allocator_t rcl_allocator_t
Encapsulation of an allocator.
Definition: allocator.h:31
RCL_PUBLIC RCL_WARN_UNUSED bool rcl_context_is_valid(const rcl_context_t *context)
Return true if the given context is currently valid, otherwise false.
Definition: context.c:94
RCL_PUBLIC RCL_WARN_UNUSED const rcl_guard_condition_options_t * rcl_guard_condition_get_options(const rcl_guard_condition_t *guard_condition)
Return the guard condition options.
RCL_PUBLIC RCL_WARN_UNUSED rcl_guard_condition_t rcl_get_zero_initialized_guard_condition(void)
Return a rcl_guard_condition_t struct with members set to NULL.
RCL_PUBLIC RCL_WARN_UNUSED rmw_guard_condition_t * rcl_guard_condition_get_rmw_handle(const rcl_guard_condition_t *guard_condition)
Return the rmw guard condition handle.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_trigger_guard_condition(rcl_guard_condition_t *guard_condition)
Trigger a rcl guard condition.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_guard_condition_init(rcl_guard_condition_t *guard_condition, rcl_context_t *context, const rcl_guard_condition_options_t options)
Initialize a rcl guard_condition.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_guard_condition_fini(rcl_guard_condition_t *guard_condition)
Finalize a rcl_guard_condition_t.
RCL_PUBLIC RCL_WARN_UNUSED rcl_guard_condition_options_t rcl_guard_condition_get_default_options(void)
Return the default options in a rcl_guard_condition_options_t struct.
rcl_ret_t rcl_guard_condition_init_from_rmw(rcl_guard_condition_t *guard_condition, const rmw_guard_condition_t *rmw_guard_condition, rcl_context_t *context, const rcl_guard_condition_options_t options)
Same as rcl_guard_condition_init(), but reusing an existing rmw handle.
rmw_context_t rmw_context
rmw context.
Definition: context_impl.h:40
Encapsulates the non-global state of an init/shutdown cycle.
Definition: context.h:114
rcl_context_impl_t * impl
Implementation specific pointer.
Definition: context.h:120
Options available for a rcl guard condition.
rcl_allocator_t allocator
Custom allocator for the guard condition, used for internal allocations.
Handle for a rcl guard condition.
rcl_guard_condition_impl_t * impl
Pointer to the guard condition implementation.
#define RCL_RET_NOT_INIT
rcl_init() not yet called return code.
Definition: types.h:43
#define RCL_RET_ALREADY_INIT
rcl_init() already called return code.
Definition: types.h:41
#define RCL_RET_OK
Success return code.
Definition: types.h:27
#define RCL_RET_BAD_ALLOC
Failed to allocate memory return code.
Definition: types.h:33
#define RCL_RET_INVALID_ARGUMENT
Invalid argument return code.
Definition: types.h:35
#define RCL_RET_ERROR
Unspecified error return code.
Definition: types.h:29
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:24