fixup guard_condition and other docs, start on time_win32.c

This commit is contained in:
William Woodall 2015-12-11 13:38:31 -08:00
parent 6985fc04df
commit f528b7a925
5 changed files with 40 additions and 49 deletions

View file

@ -23,16 +23,17 @@ extern "C"
#include "rcl/types.h"
/// Encapsulation of an allocator.
/* To use malloc, free, and realloc use rcl_get_default_allocator */
/* To use malloc, free, and realloc use rcl_get_default_allocator(). */
typedef struct rcl_allocator_t
{
/// Allocate memory, given a size and state structure.
/* An error should be indicated by returning null. */
/* 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);
/// Reallocates if possible, otherwise it deallocates and allocates.
/* If unsupported then do deallocate and then allocate.
* \TODO(wjwwood): should this behave as reallocf?
* 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.
@ -40,12 +41,12 @@ typedef struct rcl_allocator_t
*/
void * (*reallocate)(void * pointer, size_t size, void * state);
/// Implementation defined state storage.
/* This is passed as the second parameter to the (de)allocate functions. */
/* 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 memory.
/* This function does not allocate heap memory.
* This function is thread-safe.
* This function is lock-free.
*/

View file

@ -34,23 +34,17 @@ typedef struct 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 incidental allocations.
/* For default behavior (malloc/free), use: rcl_get_default_allocator() */
/// 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.
/* Should be called to get a null rcl_guard_condition_t before passing to
* rcl_initalize_guard_condition().
* It's also possible to use calloc() instead of this if the rcl guard condition is
* being allocated on the heap.
*/
rcl_guard_condition_t
rcl_get_zero_initialized_guard_condition();
/// Initialize a rcl guard_condition.
/* After calling this function on a rcl_guard_condition_t, it can be passed to
* rcl_wait and can be triggered to wake rcl_wait up.
* 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.
@ -64,15 +58,17 @@ rcl_get_zero_initialized_guard_condition();
* 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();
* rcl_guard_condition_options_t guard_condition_ops = rcl_guard_condition_get_default_options();
* ret = rcl_guard_condition_init(&guard_condition, &node, ts, "chatter", &guard_condition_ops);
* 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)
*
@ -89,14 +85,16 @@ 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);
const rcl_guard_condition_options_t options);
/// Finalize a rcl_guard_condition_t.
/* After calling, calls to rcl_trigger_guard_condition will fail when using
/* 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 is not thread-safe.
* 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
@ -107,7 +105,11 @@ rcl_guard_condition_init(
rcl_ret_t
rcl_guard_condition_fini(rcl_guard_condition_t * guard_condition, rcl_node_t * node);
/// Return the default guard_condition options in a rcl_guard_condition_options_t.
/// 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_guard_condition_options_t
rcl_guard_condition_get_default_options();
@ -118,8 +120,10 @@ rcl_guard_condition_get_default_options();
*
* 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
@ -127,7 +131,7 @@ rcl_guard_condition_get_default_options();
* RCL_RET_ERROR if an unspecified error occurs.
*/
rcl_ret_t
rcl_trigger_guard_condition(const rcl_guard_condition_t * guard_condition);
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.
@ -137,8 +141,6 @@ rcl_trigger_guard_condition(const rcl_guard_condition_t * guard_condition);
*
* The returned handle is only valid as long as the given guard_condition is valid.
*
* \TODO(wjwwood) should the return value of this be const?
*
* \param[in] guard_condition pointer to the rcl guard_condition
* \return rmw guard_condition handle if successful, otherwise NULL
*/

View file

@ -20,11 +20,12 @@ extern "C"
{
#endif
#include <stdint.h>
#include "rcl/allocator.h"
#include "rcl/types.h"
// Intentional underflow to get max size_t.
#define RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID (size_t)-1
#define RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID SIZE_MAX
struct rcl_node_impl_t;
@ -51,15 +52,11 @@ typedef struct rcl_node_options_t
* RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID? (currently max size_t)
*/
size_t domain_id;
/// Custom allocator used for incidental allocations, e.g. node name string.
/// Custom allocator used for internal allocations.
rcl_allocator_t allocator;
} rcl_node_options_t;
/// Return a rcl_node_t struct with members initialized to NULL.
/* Should be called to get rcl_node_t before passing to rcl_node_init().
* It's also possible to use calloc() instead of this if the rcl_node is being
* allocated on the heap.
*/
rcl_node_t
rcl_get_zero_initialized_node();

View file

@ -40,13 +40,12 @@ 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)
const rcl_guard_condition_options_t options)
{
// Perform argument validation.
RCL_CHECK_ARGUMENT_FOR_NULL(guard_condition, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
const rcl_allocator_t * allocator = &options->allocator;
const rcl_allocator_t * allocator = &options.allocator;
RCL_CHECK_FOR_NULL_WITH_MSG(
allocator->allocate, "allocate not set", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_FOR_NULL_WITH_MSG(
@ -77,7 +76,7 @@ rcl_guard_condition_init(
return RCL_RET_ERROR;
}
// Copy options into impl.
guard_condition->impl->options = *options;
guard_condition->impl->options = options;
return RCL_RET_OK;
}

View file

@ -12,6 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifdef WIN32
#ifndef WIN32
#error time_win32.c is only intended to be used with win32 based systems
#endif
@ -33,6 +34,10 @@ extern "C"
rcl_ret_t
rcl_system_time_point_now(rcl_system_time_point_t * now)
{
}
#if 0
{
RCL_CHECK_ARGUMENT_FOR_NULL(now, RCL_RET_INVALID_ARGUMENT);
/* Windows implementation adapted from roscpp_core (3-clause BSD), see:
@ -111,31 +116,18 @@ rcl_system_time_point_now(rcl_system_time_point_t * now)
}
return RCL_RET_OK;
}
#endif
rcl_ret_t
rcl_steady_time_point_now(rcl_steady_time_point_t * now)
{
RCL_CHECK_ARGUMENT_FOR_NULL(now, RCL_RET_INVALID_ARGUMENT);
#ifndef WIN32
// Unix implementations
#if HAS_CLOCK_GETTIME || defined(__MACH__)
// If clock_gettime is available or on OS X, use a timespec.
struct timespec timespec_now;
__timespec_get_now_monotonic(&timespec_now);
if (__WOULD_BE_NEGATIVE(timespec_now.tv_sec, timespec_now.tv_nsec)) {
RCL_SET_ERROR_MSG("unexpected negative time");
return RCL_RET_ERROR;
}
now->nanoseconds = RCL_S_TO_NS(timespec_now.tv_sec) + timespec_now.tv_nsec;
#else // if HAS_CLOCK_GETTIME || defined(__MACH__)
// Cannot fallback to gettimeofday because it is not monotonic.
#error No monotonic clock detected.
#endif // if HAS_CLOCK_GETTIME || defined(__MACH__)
#else
#endif
WINAPI ret = QueryPerformanceFrequency();
return RCL_RET_OK;
}
#if __cplusplus
}
#endif
#endif