diff --git a/rmw_fastrtps_cpp/src/rmw_init.cpp b/rmw_fastrtps_cpp/src/rmw_init.cpp index e8d9e5948..4334babea 100644 --- a/rmw_fastrtps_cpp/src/rmw_init.cpp +++ b/rmw_fastrtps_cpp/src/rmw_init.cpp @@ -85,6 +85,20 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context) 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); + // Nothing to do here for now. + // This is just the middleware's notification that shutdown was called. + return RMW_RET_OK; +} + +rmw_ret_t +rmw_context_fini(rmw_context_t * context) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT); RMW_CHECK_TYPE_IDENTIFIERS_MATCH( diff --git a/rmw_fastrtps_cpp/src/rmw_wait_set.cpp b/rmw_fastrtps_cpp/src/rmw_wait_set.cpp index f18a04864..ef442fb81 100644 --- a/rmw_fastrtps_cpp/src/rmw_wait_set.cpp +++ b/rmw_fastrtps_cpp/src/rmw_wait_set.cpp @@ -23,10 +23,10 @@ extern "C" { rmw_wait_set_t * -rmw_create_wait_set(size_t max_conditions) +rmw_create_wait_set(rmw_context_t * context, size_t max_conditions) { return rmw_fastrtps_shared_cpp::__rmw_create_wait_set( - eprosima_fastrtps_identifier, max_conditions); + eprosima_fastrtps_identifier, context, max_conditions); } rmw_ret_t diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_init.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_init.cpp index f5ccc3f1f..3e57dfbb8 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_init.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_init.cpp @@ -85,6 +85,20 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context) 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); + // Nothing to do here for now. + // This is just the middleware's notification that shutdown was called. + return RMW_RET_OK; +} + +rmw_ret_t +rmw_context_fini(rmw_context_t * context) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT); RMW_CHECK_TYPE_IDENTIFIERS_MATCH( diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_wait_set.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_wait_set.cpp index 7af1f2398..f86f58512 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_wait_set.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_wait_set.cpp @@ -23,10 +23,10 @@ extern "C" { rmw_wait_set_t * -rmw_create_wait_set(size_t max_conditions) +rmw_create_wait_set(rmw_context_t * context, size_t max_conditions) { return rmw_fastrtps_shared_cpp::__rmw_create_wait_set( - eprosima_fastrtps_identifier, max_conditions); + eprosima_fastrtps_identifier, context, max_conditions); } rmw_ret_t diff --git a/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/rmw_common.hpp b/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/rmw_common.hpp index 22a45d2a0..39678d3ec 100644 --- a/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/rmw_common.hpp +++ b/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/rmw_common.hpp @@ -292,7 +292,7 @@ __rmw_wait( RMW_FASTRTPS_SHARED_CPP_PUBLIC rmw_wait_set_t * -__rmw_create_wait_set(const char * identifier, size_t max_conditions); +__rmw_create_wait_set(const char * identifier, rmw_context_t * context, size_t max_conditions); RMW_FASTRTPS_SHARED_CPP_PUBLIC rmw_ret_t diff --git a/rmw_fastrtps_shared_cpp/src/rmw_wait_set.cpp b/rmw_fastrtps_shared_cpp/src/rmw_wait_set.cpp index 26ab3b9c5..4c85a7748 100644 --- a/rmw_fastrtps_shared_cpp/src/rmw_wait_set.cpp +++ b/rmw_fastrtps_shared_cpp/src/rmw_wait_set.cpp @@ -24,8 +24,16 @@ namespace rmw_fastrtps_shared_cpp { rmw_wait_set_t * -__rmw_create_wait_set(const char * identifier, size_t max_conditions) +__rmw_create_wait_set(const char * identifier, rmw_context_t * context, size_t max_conditions) { + RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, NULL); + RMW_CHECK_TYPE_IDENTIFIERS_MATCH( + init context, + context->implementation_identifier, + identifier, + // TODO(wjwwood): replace this with RMW_RET_INCORRECT_RMW_IMPLEMENTATION when refactored + return nullptr); + (void)max_conditions; rmw_wait_set_t * wait_set = rmw_wait_set_allocate(); CustomWaitsetInfo * wait_set_info = nullptr;