diff --git a/rmw_fastrtps_cpp/src/rmw_init.cpp b/rmw_fastrtps_cpp/src/rmw_init.cpp index 5cd5927f3..9fda70589 100644 --- a/rmw_fastrtps_cpp/src/rmw_init.cpp +++ b/rmw_fastrtps_cpp/src/rmw_init.cpp @@ -101,6 +101,7 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context) } return ret; } + context_impl->is_shutdown = false; context->impl = context_impl.release(); clean_when_fail.release(); return RMW_RET_OK; @@ -115,8 +116,8 @@ rmw_shutdown(rmw_context_t * 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. + RCUTILS_CHECK_ARGUMENT_FOR_NULL(context->impl, RMW_RET_INVALID_ARGUMENT); + context->impl->is_shutdown = true; return RMW_RET_OK; } @@ -129,6 +130,10 @@ rmw_context_fini(rmw_context_t * context) context->implementation_identifier, eprosima_fastrtps_identifier, return RMW_RET_INCORRECT_RMW_IMPLEMENTATION); + if (!context->impl->is_shutdown) { + RCUTILS_SET_ERROR_MSG("context has not been shutdown"); + return RMW_RET_INVALID_ARGUMENT; + } delete context->impl; *context = rmw_get_zero_initialized_context(); return RMW_RET_OK; diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_init.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_init.cpp index 9d320cfc1..aedf8974d 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_init.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_init.cpp @@ -115,8 +115,8 @@ rmw_shutdown(rmw_context_t * 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. + RCUTILS_CHECK_ARGUMENT_FOR_NULL(context->impl, RMW_RET_INVALID_ARGUMENT); + context->impl->is_shutdown = true; return RMW_RET_OK; } @@ -129,6 +129,10 @@ rmw_context_fini(rmw_context_t * context) context->implementation_identifier, eprosima_fastrtps_identifier, return RMW_RET_INCORRECT_RMW_IMPLEMENTATION); + if (!context->impl->is_shutdown) { + RCUTILS_SET_ERROR_MSG("context has not been shutdown"); + return RMW_RET_INVALID_ARGUMENT; + } delete context->impl; *context = rmw_get_zero_initialized_context(); return RMW_RET_OK; diff --git a/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/rmw_context_impl.hpp b/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/rmw_context_impl.hpp index 9132363b7..c9e206ec2 100644 --- a/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/rmw_context_impl.hpp +++ b/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/rmw_context_impl.hpp @@ -27,6 +27,8 @@ struct rmw_context_impl_t std::mutex mutex; /// Reference count. uint64_t count; + /// Shutdown flag. + bool is_shutdown; }; #endif // RMW_FASTRTPS_SHARED_CPP__RMW_CONTEXT_IMPL_HPP_