Skip to content

Commit

Permalink
refactor init to allow options to be passed and to not be global
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood committed Nov 6, 2018
1 parent dd2c47d commit f8adb10
Show file tree
Hide file tree
Showing 5 changed files with 259 additions and 8 deletions.
1 change: 1 addition & 0 deletions rmw/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ include_directories(include)
set(rmw_sources
"src/allocators.c"
"src/convert_rcutils_ret_to_rmw_ret.c"
"src/init.c"
"src/names_and_types.c"
"src/sanity_checks.c"
"src/node_security_options.c"
Expand Down
134 changes: 134 additions & 0 deletions rmw/include/rmw/init.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,134 @@
// Copyright 2014-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 RMW__RMW_H_
#define RMW__RMW_H_

#ifdef __cplusplus
extern "C"
{
#endif

#include <stdint.h>

#include "rmw/macros.h"
#include "rmw/types.h"
#include "rmw/visibility_control.h"

/// Implementation defined options structure used during rmw_init().
/**
* This should be defined by the rmw implementation.
*/
typedef struct rmw_init_options_impl_t rmw_init_options_impl_t;

/// Options structure used during rmw_init().
typedef struct RMW_PUBLIC_TYPE rmw_init_options_t {
/// Locally (process local) unique ID that represents this init/shutdown cycle.
/**
* This should be set by the caller of `rmw_init()` to a number that is
* unique within this process.
* It is designed to be used with `rcl_init()` and `rcl_get_instance_id()`.
*/
uint64_t instance_id;
/// Implementation defined init options.
rmw_init_options_impl_t * impl;
} rmw_init_options_t;

/// Return the default init options.
/**
* This should be defined by the rmw implementation.
*/
RMW_PUBLIC
RMW_WARN_UNUSED
rmw_init_options_t
rmw_get_default_init_options(void);

/// Implementation defined context structure returned by rmw_init().
/**
* This should be defined by the rmw implementation.
*/
typedef struct rmw_init_context_impl_t rmw_init_context_impl_t;

/// Initialization context structure which is used to store init specific information.
typedef struct RMW_PUBLIC_TYPE rmw_init_context_t {
/// Locally (process local) unique ID that represents this init/shutdown cycle.
uint64_t instance_id;
/// Implementation defined init context information.
rmw_init_context_impl_t * impl;
} rmw_init_context_t;

/// Return a zero initialized init context structure.
RMW_PUBLIC
RMW_WARN_UNUSED
rmw_init_context_t
rmw_get_zero_initialized_init_context(void);

/// Initialize the middleware with the given options, and yielding an init context.
/**
* The given init context must be zero initialized, and is filled with
* middleware specific data upon success of this function.
* The init context is used when initializing some entities like nodes and
* guard conditions, and is also required to properly call rmw_shutdown().
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | Yes
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | Yes
*
* This should be defined by the rmw implementation.
*
* \param[in] options initialization options to be used during initialization
* \param[out] context resulting context struct
* \return `RMW_RET_OK` if successful, or
* \return `RMW_RET_INVALID_ARGUMENT` if any arguments are null or invalid, or
* \return `RMW_RET_ERROR` if an unexpected error occurs.
*/
RMW_PUBLIC
RMW_WARN_UNUSED
rmw_ret_t
rmw_init(const rmw_init_options_t * options, rmw_init_context_t * context);

/// Shutdown the middleware for a given init context.
/**
* The given init context must be a valid context which has been initialized
* with rmw_init().
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | Yes
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | Yes
*
* This should be defined by the rmw implementation.
*
* \param[in] context resulting context struct
* \return `RMW_RET_OK` if successful, or
* \return `RMW_RET_INVALID_ARGUMENT` if the argument is null or invalid, or
* \return `RMW_RET_ERROR` if an unexpected error occurs.
*/
RMW_PUBLIC
RMW_WARN_UNUSED
rmw_ret_t
rmw_shutdown(rmw_init_context_t * context);

#ifdef __cplusplus
}
#endif

#endif // RMW__RMW_H_
92 changes: 85 additions & 7 deletions rmw/include/rmw/rmw.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@
* `rmw` defines an interface of middleware primitives that are used by the higher level ROS API's.
* It consists of these main components:
*
* - Initialization and Shutdown:
* - rmw/init.h
* - Nodes
* - rmw/rmw.h
* - Publisher
Expand Down Expand Up @@ -117,20 +119,63 @@ RMW_WARN_UNUSED
const char *
rmw_get_serialization_format(void);

RMW_PUBLIC
RMW_WARN_UNUSED
rmw_ret_t
rmw_init(void);

// TODO(wjwwood): refactor this API to return a return code when updated to use an allocator
/// Create a node and return a handle to that node.
/**
* This function can fail, and therefore return `NULL`, if:
* - init_context, name, namespace_, or security_options is `NULL`
* - init_context, security_options is invalid
* - memory allocation fails during node creation
* - an unspecified error occurs
*
* The init_context must be non-null and valid, i.e. it has been initialized
* by `rmw_init()` and has not been finalized by `rmw_shutdown()`.
*
* The name and namespace_ should be valid node name and namespace,
* and this should be asserted by the caller (e.g. `rcl`).
*
* The domain ID should be used to physically separate nodes at the
* communication graph level by the middleware.
* For RTPS/DDS this maps naturally to their concept of domain id.
*
* The security options should always be non-null and encapsulate the
* essential security configurations for the node and its entities.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | Yes
* Thread-Safe | No
* Uses Atomics | No [1]
* Lock-Free | No [1]
* <i>[1] rmw implementation defined, check the implementation documentation</i>
*
* This should be defined by the rmw implementation.
*
* \param[in] init_context init context that this node should be associated with
* \param[in] name the node name
* \param[in] namespace_ the node namespace
* \param[in] domain_id the id of the domain that the node should join
* \param[in] security_options the security configurations for the node
* \return rmw node handle or `NULL` if there was an error
*/
RMW_PUBLIC
RMW_WARN_UNUSED
rmw_node_t *
rmw_create_node(
rmw_init_context_t * init_context,
const char * name,
const char * namespace_,
size_t domain_id,
const rmw_node_security_options_t * security_options);

/// Finalize a given node handle, reclaim the resources, and deallocate the node handle.
/**
* \param node the node handle to be destroyed
* \return `RMW_RET_OK` if successful, or
* \return `RMW_RET_INVALID_ARGUMENT` if node is null, or
* \return `RMW_RET_ERROR` if an unexpected error occurs.
*/
RMW_PUBLIC
RMW_WARN_UNUSED
rmw_ret_t
Expand Down Expand Up @@ -162,7 +207,6 @@ rmw_destroy_node(rmw_node_t * node);
*
* \param[in] node pointer to the rmw node
* \return rmw guard condition handle if successful, otherwise `NULL`
*
*/
RMW_PUBLIC
RMW_WARN_UNUSED
Expand Down Expand Up @@ -389,11 +433,45 @@ rmw_send_response(
rmw_request_id_t * request_header,
void * ros_response);

// TODO(wjwwood): refactor this API to return a return code when updated to use an allocator
/// Create a guard condition and return a handle to that guard condition.
/**
* This function can fail, and therefore return `NULL`, if:
* - init_context is `NULL`
* - init_context is invalid
* - memory allocation fails during guard condition creation
* - an unspecified error occurs
*
* The init_context must be non-null and valid, i.e. it has been initialized
* by `rmw_init()` and has not been finalized by `rmw_shutdown()`.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | Yes
* Thread-Safe | No
* Uses Atomics | No [1]
* Lock-Free | No [1]
* <i>[1] rmw implementation defined, check the implementation documentation</i>
*
* This should be defined by the rmw implementation.
*
* \param[in] init_context init context that this node should be associated with
* \return rmw guard condition handle or `NULL` if there was an error
*/
RMW_PUBLIC
RMW_WARN_UNUSED
rmw_guard_condition_t *
rmw_create_guard_condition(void);
rmw_create_guard_condition(rmw_init_context_t * init_context);


/// Finalize a given guard condition handle, reclaim the resources, and deallocate the handle.
/**
* \param guard_condition the guard condition handle to be destroyed
* \return `RMW_RET_OK` if successful, or
* \return `RMW_RET_INVALID_ARGUMENT` if guard_condition is null, or
* \return `RMW_RET_ERROR` if an unexpected error occurs.
*/
RMW_PUBLIC
RMW_WARN_UNUSED
rmw_ret_t
Expand Down
7 changes: 6 additions & 1 deletion rmw/include/rmw/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,12 +44,16 @@ typedef int rmw_ret_t;
// implementation. It may need to be increased in the future.
#define RMW_GID_STORAGE_SIZE 24

// forward declaration to avoid circular dependency
typedef struct rmw_init_context_t rmw_init_context_t;

typedef struct RMW_PUBLIC_TYPE rmw_node_t
{
const char * implementation_identifier;
void * data;
const char * name;
const char * namespace_;
rmw_init_context_t * init_context;
} rmw_node_t;

typedef struct RMW_PUBLIC_TYPE rmw_publisher_t
Expand Down Expand Up @@ -84,9 +88,10 @@ typedef struct RMW_PUBLIC_TYPE rmw_guard_condition_t
{
const char * implementation_identifier;
void * data;
rmw_init_context_t * init_context;
} rmw_guard_condition_t;

/// Array of subsciber handles.
/// Array of subscriber handles.
/**
* An array of void * pointers representing type-erased middleware-specific subscriptions.
* The number of non-null entries may be smaller than the allocated size of the array.
Expand Down
33 changes: 33 additions & 0 deletions rmw/src/init.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
// 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.

#include "rmw/init.h"

#ifdef __cplusplus
extern "C"
{
#endif

rmw_init_context_t
rmw_get_zero_initialized_init_context(void)
{
return (const rmw_init_context_t) {
.instance_id = 0,
.impl = NULL
};
}

#ifdef __cplusplus
}
#endif

0 comments on commit f8adb10

Please sign in to comment.