Skip to content

Commit

Permalink
Merge pull request #5 from ros2/rcl_refactor
Browse files Browse the repository at this point in the history
refactor rcl into a functional library
  • Loading branch information
wjwwood committed Dec 18, 2015
2 parents d0083b7 + b358e98 commit 083f6ec
Show file tree
Hide file tree
Showing 43 changed files with 6,653 additions and 172 deletions.
54 changes: 54 additions & 0 deletions rcl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,14 +3,68 @@ cmake_minimum_required(VERSION 2.8.3)
project(rcl)

find_package(ament_cmake REQUIRED)
find_package(rcl_interfaces REQUIRED)
find_package(rmw REQUIRED)
find_package(rmw_implementation REQUIRED)
find_package(rmw_implementation_cmake REQUIRED)
find_package(rosidl_generator_c REQUIRED)

include_directories(include)

if(NOT WIN32)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -Wextra")
endif()

set(${PROJECT_NAME}_sources
src/rcl/allocator.c
src/rcl/common.c
src/rcl/guard_condition.c
src/rcl/node.c
src/rcl/publisher.c
src/rcl/rcl.c
src/rcl/subscription.c
src/rcl/wait.c
src/rcl/time.c
src/rcl/timer.c
)

macro(target)
add_library(${PROJECT_NAME}${target_suffix} SHARED ${${PROJECT_NAME}_sources})
ament_target_dependencies(${PROJECT_NAME}${target_suffix}
"rcl_interfaces"
"rmw"
"rosidl_generator_c"
"${rmw_implementation}"
)

# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(${PROJECT_NAME}${target_suffix} PRIVATE "RCL_BUILDING_DLL")

install(
TARGETS ${PROJECT_NAME}${target_suffix}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)
endmacro()

call_for_each_rmw_implementation(target GENERATE_DEFAULT)

ament_export_dependencies(rcl_interfaces)
ament_export_dependencies(rmw)
ament_export_dependencies(rmw_implementation)
ament_export_dependencies(rosidl_generator_c)

ament_export_include_directories(include)

ament_export_libraries(${PROJECT_NAME})

if(AMENT_ENABLE_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()

add_subdirectory(test)
endif()

ament_package()
Expand Down
82 changes: 82 additions & 0 deletions rcl/include/rcl/allocator.h
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.
* 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_
38 changes: 38 additions & 0 deletions rcl/include/rcl/error_handling.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_
174 changes: 174 additions & 0 deletions rcl/include/rcl/guard_condition.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();

/// 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)
*
* \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_
33 changes: 33 additions & 0 deletions rcl/include/rcl/macros.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_
Loading

0 comments on commit 083f6ec

Please sign in to comment.