Skip to content
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 to support init options and context #237

Merged
merged 3 commits into from Nov 30, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
10 changes: 9 additions & 1 deletion rmw_fastrtps_cpp/src/rmw_guard_condition.cpp
Expand Up @@ -13,6 +13,7 @@
// limitations under the License.

#include "rmw/error_handling.h"
#include "rmw/impl/cpp/macros.hpp"
#include "rmw/rmw.h"

#include "rmw_fastrtps_shared_cpp/rmw_common.hpp"
Expand All @@ -22,8 +23,15 @@
extern "C"
{
rmw_guard_condition_t *
rmw_create_guard_condition()
rmw_create_guard_condition(rmw_context_t * context)
{
RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, NULL);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
init context,
context->implementation_identifier,
eprosima_fastrtps_identifier,
// TODO(wjwwood): replace this with RMW_RET_INCORRECT_RMW_IMPLEMENTATION when refactored
return NULL);
return rmw_fastrtps_shared_cpp::__rmw_create_guard_condition(
eprosima_fastrtps_identifier);
}
Expand Down
78 changes: 77 additions & 1 deletion rmw_fastrtps_cpp/src/rmw_init.cpp
Expand Up @@ -12,13 +12,89 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "rmw/impl/cpp/macros.hpp"
#include "rmw/rmw.h"

#include "rmw_fastrtps_cpp/identifier.hpp"

extern "C"
{
rmw_ret_t
rmw_init()
rmw_init_options_init(rmw_init_options_t * init_options, rcutils_allocator_t allocator)
{
RMW_CHECK_ARGUMENT_FOR_NULL(init_options, RMW_RET_INVALID_ARGUMENT);
RCUTILS_CHECK_ALLOCATOR(&allocator, return RMW_RET_INVALID_ARGUMENT);
if (NULL != init_options->implementation_identifier) {
RMW_SET_ERROR_MSG("expected zero-initialized init_options");
return RMW_RET_INVALID_ARGUMENT;
}
init_options->instance_id = 0;
init_options->implementation_identifier = eprosima_fastrtps_identifier;
init_options->allocator = allocator;
init_options->impl = nullptr;
return RMW_RET_OK;
}

rmw_ret_t
rmw_init_options_copy(const rmw_init_options_t * src, rmw_init_options_t * dst)
{
RMW_CHECK_ARGUMENT_FOR_NULL(src, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_ARGUMENT_FOR_NULL(dst, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
src,
src->implementation_identifier,
eprosima_fastrtps_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
if (NULL != dst->implementation_identifier) {
RMW_SET_ERROR_MSG("expected zero-initialized dst");
return RMW_RET_INVALID_ARGUMENT;
}
*dst = *src;
return RMW_RET_OK;
}

rmw_ret_t
rmw_init_options_fini(rmw_init_options_t * init_options)
{
RMW_CHECK_ARGUMENT_FOR_NULL(init_options, RMW_RET_INVALID_ARGUMENT);
RCUTILS_CHECK_ALLOCATOR(&(init_options->allocator), return RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
init_options,
init_options->implementation_identifier,
eprosima_fastrtps_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
*init_options = rmw_get_zero_initialized_init_options();
return RMW_RET_OK;
}

rmw_ret_t
rmw_init(const rmw_init_options_t * options, rmw_context_t * context)
{
RCUTILS_CHECK_ARGUMENT_FOR_NULL(options, RMW_RET_INVALID_ARGUMENT);
RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
options,
options->implementation_identifier,
eprosima_fastrtps_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
context->instance_id = options->instance_id;
context->implementation_identifier = eprosima_fastrtps_identifier;
context->impl = nullptr;
return RMW_RET_OK;
}

rmw_ret_t
rmw_shutdown(rmw_context_t * context)
{
RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
context,
context->implementation_identifier,
eprosima_fastrtps_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
// context impl is explicitly supposed to be nullptr for now, see rmw_init's code
// RCUTILS_CHECK_ARGUMENT_FOR_NULL(context->impl, RMW_RET_INVALID_ARGUMENT);
*context = rmw_get_zero_initialized_context();
return RMW_RET_OK;
}
} // extern "C"
9 changes: 9 additions & 0 deletions rmw_fastrtps_cpp/src/rmw_node.cpp
Expand Up @@ -22,6 +22,7 @@

#include "rmw/allocators.h"
#include "rmw/error_handling.h"
#include "rmw/impl/cpp/macros.hpp"
#include "rmw/rmw.h"

#include "rmw_fastrtps_shared_cpp/rmw_common.hpp"
Expand All @@ -32,11 +33,19 @@ extern "C"
{
rmw_node_t *
rmw_create_node(
rmw_context_t * context,
const char * name,
const char * namespace_,
size_t domain_id,
const rmw_node_security_options_t * security_options)
{
RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, NULL);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
init context,
context->implementation_identifier,
eprosima_fastrtps_identifier,
// TODO(wjwwood): replace this with RMW_RET_INCORRECT_RMW_IMPLEMENTATION when refactored
return NULL);
return rmw_fastrtps_shared_cpp::__rmw_create_node(
eprosima_fastrtps_identifier, name, namespace_, domain_id, security_options);
}
Expand Down
10 changes: 9 additions & 1 deletion rmw_fastrtps_dynamic_cpp/src/rmw_guard_condition.cpp
Expand Up @@ -13,6 +13,7 @@
// limitations under the License.

#include "rmw/error_handling.h"
#include "rmw/impl/cpp/macros.hpp"
#include "rmw/rmw.h"

#include "rmw_fastrtps_shared_cpp/rmw_common.hpp"
Expand All @@ -22,8 +23,15 @@
extern "C"
{
rmw_guard_condition_t *
rmw_create_guard_condition()
rmw_create_guard_condition(rmw_context_t * context)
{
RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, NULL);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
init context,
context->implementation_identifier,
eprosima_fastrtps_identifier,
// TODO(wjwwood): replace this with RMW_RET_INCORRECT_RMW_IMPLEMENTATION when refactored
return NULL);
return rmw_fastrtps_shared_cpp::__rmw_create_guard_condition(
eprosima_fastrtps_identifier);
}
Expand Down
78 changes: 77 additions & 1 deletion rmw_fastrtps_dynamic_cpp/src/rmw_init.cpp
Expand Up @@ -12,13 +12,89 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "rmw/impl/cpp/macros.hpp"
#include "rmw/rmw.h"

#include "rmw_fastrtps_dynamic_cpp/identifier.hpp"

extern "C"
{
rmw_ret_t
rmw_init()
rmw_init_options_init(rmw_init_options_t * init_options, rcutils_allocator_t allocator)
{
RMW_CHECK_ARGUMENT_FOR_NULL(init_options, RMW_RET_INVALID_ARGUMENT);
RCUTILS_CHECK_ALLOCATOR(&allocator, return RMW_RET_INVALID_ARGUMENT);
if (NULL != init_options->implementation_identifier) {
RMW_SET_ERROR_MSG("expected zero-initialized init_options");
return RMW_RET_INVALID_ARGUMENT;
}
init_options->instance_id = 0;
init_options->implementation_identifier = eprosima_fastrtps_identifier;
wjwwood marked this conversation as resolved.
Show resolved Hide resolved
init_options->allocator = allocator;
init_options->impl = nullptr;
return RMW_RET_OK;
}

rmw_ret_t
rmw_init_options_copy(const rmw_init_options_t * src, rmw_init_options_t * dst)
{
RMW_CHECK_ARGUMENT_FOR_NULL(src, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_ARGUMENT_FOR_NULL(dst, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
src,
src->implementation_identifier,
eprosima_fastrtps_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
if (NULL != dst->implementation_identifier) {
RMW_SET_ERROR_MSG("expected zero-initialized dst");
return RMW_RET_INVALID_ARGUMENT;
}
*dst = *src;
return RMW_RET_OK;
}

rmw_ret_t
rmw_init_options_fini(rmw_init_options_t * init_options)
{
RMW_CHECK_ARGUMENT_FOR_NULL(init_options, RMW_RET_INVALID_ARGUMENT);
RCUTILS_CHECK_ALLOCATOR(&(init_options->allocator), return RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
init_options,
init_options->implementation_identifier,
eprosima_fastrtps_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
*init_options = rmw_get_zero_initialized_init_options();
return RMW_RET_OK;
}

rmw_ret_t
rmw_init(const rmw_init_options_t * options, rmw_context_t * context)
{
RCUTILS_CHECK_ARGUMENT_FOR_NULL(options, RMW_RET_INVALID_ARGUMENT);
RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
options,
options->implementation_identifier,
eprosima_fastrtps_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
context->instance_id = options->instance_id;
context->implementation_identifier = eprosima_fastrtps_identifier;
context->impl = nullptr;
return RMW_RET_OK;
}

rmw_ret_t
rmw_shutdown(rmw_context_t * context)
{
RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
context,
context->implementation_identifier,
eprosima_fastrtps_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
// context impl is explicitly supposed to be nullptr for now, see rmw_init's code
// RCUTILS_CHECK_ARGUMENT_FOR_NULL(context->impl, RMW_RET_INVALID_ARGUMENT);
*context = rmw_get_zero_initialized_context();
return RMW_RET_OK;
}
} // extern "C"
9 changes: 9 additions & 0 deletions rmw_fastrtps_dynamic_cpp/src/rmw_node.cpp
Expand Up @@ -22,6 +22,7 @@

#include "rmw/allocators.h"
#include "rmw/error_handling.h"
#include "rmw/impl/cpp/macros.hpp"
#include "rmw/rmw.h"

#include "rmw_fastrtps_shared_cpp/rmw_common.hpp"
Expand All @@ -32,11 +33,19 @@ extern "C"
{
rmw_node_t *
rmw_create_node(
rmw_context_t * context,
const char * name,
const char * namespace_,
size_t domain_id,
const rmw_node_security_options_t * security_options)
{
RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, NULL);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
init context,
context->implementation_identifier,
eprosima_fastrtps_identifier,
// TODO(wjwwood): replace this with RMW_RET_INCORRECT_RMW_IMPLEMENTATION when refactored
return NULL);
return rmw_fastrtps_shared_cpp::__rmw_create_node(
eprosima_fastrtps_identifier, name, namespace_, domain_id, security_options);
}
Expand Down