rmw  master
C API providing a middleware abstraction layer which is used to implement the rest of ROS.
Classes | Typedefs | Functions
init.h File Reference
#include <stdint.h>
#include "rmw/init_options.h"
#include "rmw/macros.h"
#include "rmw/ret_types.h"
#include "rmw/visibility_control.h"
Include dependency graph for init.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  rmw_context_t
 Initialization context structure which is used to store init specific information. More...
 

Typedefs

typedef struct rmw_context_impl_t rmw_context_impl_t
 Implementation defined context structure returned by rmw_init(). More...
 
typedef struct RMW_PUBLIC_TYPE rmw_context_t rmw_context_t
 Initialization context structure which is used to store init specific information. More...
 

Functions

rmw_context_t rmw_get_zero_initialized_context (void)
 Return a zero initialized context structure. More...
 
rmw_ret_t rmw_init (const rmw_init_options_t *options, rmw_context_t *context)
 Initialize the middleware with the given options, and yielding an context. More...
 
rmw_ret_t rmw_shutdown (rmw_context_t *context)
 Shutdown the middleware for a given context. More...
 
rmw_ret_t rmw_context_fini (rmw_context_t *context)
 Finalize a context. More...
 

Typedef Documentation

◆ rmw_context_impl_t

Implementation defined context structure returned by rmw_init().

This should be defined by the rmw implementation.

◆ rmw_context_t

Initialization context structure which is used to store init specific information.

Function Documentation

◆ rmw_get_zero_initialized_context()

rmw_context_t rmw_get_zero_initialized_context ( void  )

Return a zero initialized context structure.

◆ rmw_init()

rmw_ret_t rmw_init ( const rmw_init_options_t options,
rmw_context_t context 
)

Initialize the middleware with the given options, and yielding an context.

Context is filled with middleware specific data upon success of this function. The context is used when initializing some entities like nodes and guard conditions, and is also required to properly call rmw_shutdown().

Precondition
The given options must have been initialized i.e. rmw_init_options_init() called on it and an enclave set.
The given context must be zero initialized.
Postcondition
If initialization fails, context will remain zero initialized.
context->actual_domain_id will be set with the domain id the rmw implementation is using. This matches options->domain_id if it is not RMW_DEFAULT_DOMAIN_ID. In other case, the value is rmw implementation dependent.
Remarks
If options are zero-initialized, then RMW_RET_INVALID_ARGUMENT is returned. If options are initialized but no enclave is provided, then RMW_RET_INVALID_ARGUMENT is returned. If context has been already initialized (rmw_init() was called on it), then RMW_RET_INVALID_ARGUMENT is returned.

Attribute Adherence
Allocates Memory Yes
Thread-Safe No
Uses Atomics No
Lock-Free Yes

This should be defined by the rmw implementation.

Parameters
[in]optionsinitialization options to be used during initialization
[out]contextresulting context struct
Returns
RMW_RET_OK if successful, or
RMW_RET_INVALID_ARGUMENT if any arguments are invalid, or
RMW_RET_INCORRECT_RMW_IMPLEMENTATION if the implementation identifier does not match, or
RMW_RET_ERROR if an unexpected error occurs.

◆ rmw_shutdown()

rmw_ret_t rmw_shutdown ( rmw_context_t context)

Shutdown the middleware for a given context.

Precondition
The given context must be a valid context which has been initialized with rmw_init().
Remarks
If context is zero initialized, then RMW_RET_INVALID_ARGUMENT is returned. If context has been already invalidated (rmw_shutdown() was called on it), then this function is a no-op and RMW_RET_OK is returned.

Attribute Adherence
Allocates Memory Yes
Thread-Safe No
Uses Atomics No
Lock-Free Yes

This should be defined by the rmw implementation.

Parameters
[in]contextresulting context struct
Returns
RMW_RET_OK if successful, or
RMW_RET_INVALID_ARGUMENT if any argument are invalid, or
RMW_RET_INCORRECT_RMW_IMPLEMENTATION if the implementation identifier does not match, or
RMW_RET_ERROR if an unexpected error occurs.

◆ rmw_context_fini()

rmw_ret_t rmw_context_fini ( rmw_context_t context)

Finalize a context.

This function will return early if a logical error, such as RMW_RET_INVALID_ARGUMENT or RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ensues, leaving the given context unchanged. Otherwise, it will proceed despite errors, freeing as much resources as it can and zero initializing the given context.

Precondition
The context to be finalized must have been previously initialized with rmw_init(), and then later invalidated with rmw_shutdown().
Remarks
If context is zero initialized, then RMW_RET_INVALID_ARGUMENT is returned. If context is initialized and valid (rmw_shutdown() was not called on it), then RMW_RET_INVALID_ARGUMENT is returned.

Attribute Adherence
Allocates Memory Yes
Thread-Safe No
Uses Atomics Yes
Lock-Free Yes [1]

[1] if atomic_is_lock_free() returns true for atomic_uint_least64_t

This should be defined by the rmw implementation.

Returns
RMW_RET_OK if successful, or
RMW_RET_INVALID_ARGUMENT if any arguments are invalid, or
RMW_RET_INCORRECT_RMW_IMPLEMENTATION if the implementation identifier does not match, or
RMW_RET_ERROR if an unspecified error occur.