-
Notifications
You must be signed in to change notification settings - Fork 163
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
refactor rcl into a functional library #5
Changes from all commits
75fafe9
9631cba
d9e493a
bac3b21
2f029b5
4b55f8e
c24a214
0cb3bf3
29b50e2
483ddfd
ad21736
3e5298b
821bbf7
77406de
1097b54
22761b6
7ab361a
4655139
fb9f660
bd3e4e8
902172d
9c0208e
6985fc0
f528b7a
3e516c8
879f0a1
d281ab3
02f926c
34ae477
2037346
654ded8
43c1824
5c07b9e
4ccaefb
536b80c
c4d3022
a022299
0ae4ca7
ff64d07
abc1f87
aa83632
52da897
88c503e
e2cbace
7b36a60
b205c36
cf450f5
8ea6b75
68facdb
2398e98
898f389
09a2aad
a44c14c
6ccbb35
7bceed4
b92148d
f35c06e
64dc7ac
c6a903f
5372c52
c816e64
8da408a
41d123b
1af1507
655577b
fe37e82
1adcc05
a14caef
1030d18
5054744
b358e98
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,82 @@ | ||
// Copyright 2015 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 RCL__ALLOCATOR_H_ | ||
#define RCL__ALLOCATOR_H_ | ||
|
||
#if __cplusplus | ||
extern "C" | ||
{ | ||
#endif | ||
|
||
#include "rcl/macros.h" | ||
#include "rcl/types.h" | ||
#include "rcl/visibility_control.h" | ||
|
||
/// Encapsulation of an allocator. | ||
/* To use malloc, free, and realloc use rcl_get_default_allocator(). | ||
* | ||
* The allocator should be trivially copyable. | ||
* Meaning that the struct should continue to work after being assignment | ||
* copied into a new struct. | ||
* Specifically the object pointed to by the state pointer should remain valid | ||
* until all uses of the allocator have been made. | ||
* Particular care should be taken when giving an allocator to rcl_init_* where | ||
* it is stored within another object and used later. | ||
*/ | ||
typedef struct rcl_allocator_t | ||
{ | ||
/// Allocate memory, given a size and state structure. | ||
/* An error should be indicated by returning NULL. */ | ||
void * (*allocate)(size_t size, void * state); | ||
/// Deallocate previously allocated memory, mimicking free(). | ||
void (* deallocate)(void * pointer, void * state); | ||
/// Reallocate if possible, otherwise it deallocates and allocates. | ||
/* If unsupported then do deallocate and then allocate. | ||
* This should behave as realloc is described, as opposed to reallocf, i.e. | ||
* the memory given by pointer will not be free'd automatically if realloc | ||
* fails. | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I would agree to mimic There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Well the void * mem = malloc(...);
mem = realloc(mem, ...);
if (!mem) {
// The memory allocated by malloc is now leaked,
// since it was not free'd and the only pointer to it was overwritten with NULL.
} Which leads to something correct being like this: void * mem = malloc(...);
void * new_mem = realloc(mem, ...);
if (!new_mem) {
free(mem);
}
mem = new_mem; And void * mem = malloc(...);
mem = reallocf(mem, ...);
if (!mem) {
// No memory has been leaked.
} The only downside to only having I think I'll instead make a wrapper function which does something similar to this: void *
rcl_reallocf(
void * (*realloc_func)(void *, size_t, void *),
void (*free_func)(void *, void *),
void * original_mem, size_t new_size, void * state)
{
void * new_mem = realloc_func(original_mem, new_size, state);
if (!new_mem) {
free_func(original_mem, state);
}
return new_mem;
} There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I changed it in 898f389 |
||
* For reallocf behavior use rcl_reallocf(). | ||
* This function must be able to take an input pointer of NULL and succeed. | ||
*/ | ||
void * (*reallocate)(void * pointer, size_t size, void * state); | ||
/// Implementation defined state storage. | ||
/* This is passed as the second parameter to other allocator functions. */ | ||
void * state; | ||
} rcl_allocator_t; | ||
|
||
/// Return a properly initialized rcl_allocator_t with default values. | ||
/* This function does not allocate heap memory. | ||
* This function is thread-safe. | ||
* This function is lock-free. | ||
*/ | ||
RCL_PUBLIC | ||
RCL_WARN_UNUSED | ||
rcl_allocator_t | ||
rcl_get_default_allocator(); | ||
|
||
/// Emulate the behavior of reallocf. | ||
/* This function will return NULL if the allocator is NULL or has NULL for | ||
* function pointer fields. | ||
*/ | ||
RCL_PUBLIC | ||
RCL_WARN_UNUSED | ||
void * | ||
rcl_reallocf(void * pointer, size_t size, rcl_allocator_t * allocator); | ||
|
||
#if __cplusplus | ||
} | ||
#endif | ||
|
||
#endif // RCL__ALLOCATOR_H_ |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,38 @@ | ||
// Copyright 2015 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 RCL__ERROR_HANDLING_H_ | ||
#define RCL__ERROR_HANDLING_H_ | ||
|
||
#include "rmw/error_handling.h" | ||
|
||
/* The error handling in RCL is just an alias to the error handling in RMW. */ | ||
|
||
typedef rmw_error_state_t rcl_error_state_t; | ||
|
||
#define rcl_set_error_state rmw_set_error_state | ||
|
||
#define RCL_SET_ERROR_MSG(msg) RMW_SET_ERROR_MSG(msg) | ||
|
||
#define rcl_error_is_set rmw_error_is_set | ||
|
||
#define rcl_get_error_state rmw_get_error_state | ||
|
||
#define rcl_get_error_string rmw_get_error_string | ||
|
||
#define rcl_get_error_string_safe rmw_get_error_string_safe | ||
|
||
#define rcl_reset_error rmw_reset_error | ||
|
||
#endif // RCL__ERROR_HANDLING_H_ |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,174 @@ | ||
// Copyright 2015 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 RCL__GUARD_CONDITION_H_ | ||
#define RCL__GUARD_CONDITION_H_ | ||
|
||
#if __cplusplus | ||
extern "C" | ||
{ | ||
#endif | ||
|
||
#include "rcl/macros.h" | ||
#include "rcl/node.h" | ||
#include "rcl/visibility_control.h" | ||
|
||
/// Internal rcl guard condition implementation struct. | ||
struct rcl_guard_condition_impl_t; | ||
|
||
/// Handle for a rcl guard condition. | ||
typedef struct rcl_guard_condition_t | ||
{ | ||
struct rcl_guard_condition_impl_t * impl; | ||
} rcl_guard_condition_t; | ||
|
||
/// Options available for a rcl guard condition. | ||
typedef struct rcl_guard_condition_options_t | ||
{ | ||
/// Custom allocator for the guard condition, used for internal allocations. | ||
rcl_allocator_t allocator; | ||
} rcl_guard_condition_options_t; | ||
|
||
/// Return a rcl_guard_condition_t struct with members set to NULL. | ||
RCL_PUBLIC | ||
RCL_WARN_UNUSED | ||
rcl_guard_condition_t | ||
rcl_get_zero_initialized_guard_condition(); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Does the function name need to include Same question for similar API below. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I think There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I see, it currently doesn't perform any complex initialization. Do you expect it to do that in the future? If not I would rather not add a function like this to our core API - simply because the caller code can do exactly the same using a few characters ( There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I generally agree, and I was about to remove these functions, but in testing I noticed that you can do this: rcl_node_t node = rcl_get_zero_initialized_node();
rcl_node_init(&node, ...);
// ... use the node
rcl_node_fini(&node);
node = rcl_get_zero_initialized_node(); But not this (at least not in C): rcl_node_t node = {0};
rcl_node_init(&node, ...);
// ... use the node
rcl_node_fini(&node);
node = {0}; // This is a compiler error. The error looks like this:
So I left them in, but I can still remove them, even with this caveat. |
||
|
||
/// Initialize a rcl guard_condition. | ||
/* After calling this function on a rcl_guard_condition_t, it can be passed to | ||
* rcl_wait() and then concurrently it can be triggered to wake-up rcl_wait(). | ||
* | ||
* The given rcl_node_t must be valid and the resulting rcl_guard_condition_t | ||
* is only valid as long as the given rcl_node_t remains valid. | ||
* | ||
* Expected usage: | ||
* | ||
* #include <rcl/rcl.h> | ||
* | ||
* rcl_node_t node = rcl_get_zero_initialized_node(); | ||
* rcl_node_options_t node_ops = rcl_node_get_default_options(); | ||
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops); | ||
* // ... error handling | ||
* rcl_guard_condition_t guard_condition = rcl_get_zero_initialized_guard_condition(); | ||
* ret = rcl_guard_condition_init( | ||
* &guard_condition, &node, rcl_guard_condition_get_default_options()); | ||
* // ... error handling, and on shutdown do deinitialization: | ||
* ret = rcl_guard_condition_fini(&guard_condition, &node); | ||
* // ... error handling for rcl_guard_condition_fini() | ||
* ret = rcl_node_fini(&node); | ||
* // ... error handling for rcl_deinitialize_node() | ||
* | ||
* This function does allocate heap memory. | ||
* This function is not thread-safe. | ||
* This function is lock-free. | ||
* | ||
* \TODO(wjwwood): does this function need a node to be passed to it? (same for fini) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Currently There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I agree that some context may be needed, but I'm not sure that node is the right context. Should guard conditions become invalid when a node is destroyed? Should you be able to create guard conditions with out nodes (I think you should be abled to)? I also have the There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I think it comes down to what some rmw impl. might require. I can imagine that some implementation will need to create a context in There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I think we should wait until we refactor When we do that I think the right approach will be to have There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Sounds good to me. |
||
* | ||
* \param[inout] guard_condition preallocated guard_condition structure | ||
* \param[in] node valid rcl node handle | ||
* \param[in] options the guard_condition's options | ||
* \return RCL_RET_OK if guard_condition was initialized successfully, or | ||
* RCL_RET_ALREADY_INIT if the guard condition is already initialized, or | ||
* RCL_RET_INVALID_ARGUMENT if any arugments are invalid, or | ||
* RCL_RET_BAD_ALLOC if allocating memory failed, or | ||
* RCL_RET_ERROR if an unspecified error occurs. | ||
*/ | ||
RCL_PUBLIC | ||
RCL_WARN_UNUSED | ||
rcl_ret_t | ||
rcl_guard_condition_init( | ||
rcl_guard_condition_t * guard_condition, | ||
const rcl_node_t * node, | ||
const rcl_guard_condition_options_t options); | ||
|
||
/// Finalize a rcl_guard_condition_t. | ||
/* After calling, calls to rcl_guard_condition_trigger() will fail when using | ||
* this guard condition. | ||
* However, the given node handle is still valid. | ||
* | ||
* This function does free heap memory and can allocate memory on errors. | ||
* This function is not thread-safe with rcl_guard_condition_trigger(). | ||
* This function is lock-free. | ||
* | ||
* \param[inout] guard_condition handle to the guard_condition to be finalized | ||
* \param[in] node handle to the node used to create the guard_condition | ||
* \return RCL_RET_OK if guard_condition was finalized successfully, or | ||
* RCL_RET_INVALID_ARGUMENT if any arugments are invalid, or | ||
* RCL_RET_ERROR if an unspecified error occurs. | ||
*/ | ||
RCL_PUBLIC | ||
RCL_WARN_UNUSED | ||
rcl_ret_t | ||
rcl_guard_condition_fini(rcl_guard_condition_t * guard_condition, rcl_node_t * node); | ||
|
||
/// Return the default options in a rcl_guard_condition_options_t struct. | ||
/* This function does not allocate heap memory. | ||
* This function is thread-safe. | ||
* This function is lock-free. | ||
*/ | ||
RCL_PUBLIC | ||
RCL_WARN_UNUSED | ||
rcl_guard_condition_options_t | ||
rcl_guard_condition_get_default_options(); | ||
|
||
/// Trigger a rcl guard condition. | ||
/* This function can fail, and therefore return NULL, if the: | ||
* - guard condition is NULL | ||
* - guard condition is invalid (never called init or called fini) | ||
* | ||
* A guard condition can be triggered from any thread. | ||
* | ||
* This function does not allocate heap memory, but can on errors. | ||
* This function is thread-safe with itself, but cannot be called concurrently | ||
* with rcl_guard_condition_fini() on the same guard condition. | ||
* This function is lock-free, but the underlying system calls may not be. | ||
* | ||
* \param[in] guard_condition handle to the guard_condition to be triggered | ||
* \return RCL_RET_OK if the guard condition was triggered, or | ||
* RCL_RET_INVALID_ARGUMENT if any arugments are invalid, or | ||
* RCL_RET_ERROR if an unspecified error occurs. | ||
*/ | ||
RCL_PUBLIC | ||
RCL_WARN_UNUSED | ||
rcl_ret_t | ||
rcl_guard_condition_trigger(const rcl_guard_condition_t * guard_condition); | ||
|
||
/// Return the rmw guard condition handle. | ||
/* The handle returned is a pointer to the internally held rmw handle. | ||
* This function can fail, and therefore return NULL, if the: | ||
* - guard_condition is NULL | ||
* - guard_condition is invalid (never called init, called fini, or invalid node) | ||
* | ||
* The returned handle is made invalid if the guard condition is finalized or | ||
* if rcl_shutdown() is called. | ||
* The returned handle is not guaranteed to be valid for the life time of the | ||
* guard condition as it may be finalized and recreated itself. | ||
* Therefore it is recommended to get the handle from the guard condition using | ||
* this function each time it is needed and avoid use of the handle | ||
* concurrently with functions that might change it. | ||
* | ||
* \param[in] guard_condition pointer to the rcl guard_condition | ||
* \return rmw guard_condition handle if successful, otherwise NULL | ||
*/ | ||
RCL_PUBLIC | ||
RCL_WARN_UNUSED | ||
rmw_guard_condition_t * | ||
rcl_guard_condition_get_rmw_handle(const rcl_guard_condition_t * guard_condition); | ||
|
||
#if __cplusplus | ||
} | ||
#endif | ||
|
||
#endif // RCL__GUARD_CONDITION_H_ |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,33 @@ | ||
// Copyright 2015 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 RCL__MACROS_H_ | ||
#define RCL__MACROS_H_ | ||
|
||
#if __cplusplus | ||
extern "C" | ||
{ | ||
#endif | ||
|
||
#ifndef _WIN32 | ||
# define RCL_WARN_UNUSED __attribute__((warn_unused_result)) | ||
#else | ||
# define RCL_WARN_UNUSED _Check_return_ | ||
#endif | ||
|
||
#if __cplusplus | ||
} | ||
#endif | ||
|
||
#endif // RCL__MACROS_H_ |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Should we use C11 here?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
No, it causes issues on GCC 4.7 and it is not necessary to define that in order to use
stdatomic.h
, which is the only thing from "C11" that I use. Also Windows doesn't support it and it doesn't appear that it will.There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
We already use
-std=c11
throughout rosidl. Which platform has only gcc 4.7 and what are the problems?Since the line is in a condition it doesn't affect Windows.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I had trouble with the line
#include <time.h>
when I enabled-std=c11
, but I never tracked it down to a bug report or tried with a newer version of gcc.Windows doesn't support C11 and I can't find any indication that they plan to improve on that: http://herbsutter.com/2012/05/03/reader-qa-what-about-vc-and-c99/
I can tell you that they would need some extra features or compiler support to implement the C11 atomic api as described using their atomics primitives.
I haven't run into any C11 feature that I need yet and I had strange compiler behavior on Linux with gcc when using
-std=c11
(but it works fine on OS X), so I don't pass the flag.