diff --git a/rmw_fastrtps_cpp/CMakeLists.txt b/rmw_fastrtps_cpp/CMakeLists.txt
index 963b199a4..0c5efb02c 100644
--- a/rmw_fastrtps_cpp/CMakeLists.txt
+++ b/rmw_fastrtps_cpp/CMakeLists.txt
@@ -31,6 +31,7 @@ endif()
find_package(ament_cmake_ros REQUIRED)
+find_package(rcpputils REQUIRED)
find_package(rcutils REQUIRED)
find_package(rmw_dds_common REQUIRED)
find_package(rmw_fastrtps_shared_cpp REQUIRED)
@@ -93,6 +94,7 @@ target_link_libraries(rmw_fastrtps_cpp
# specific order: dependents before dependencies
ament_target_dependencies(rmw_fastrtps_cpp
+ "rcpputils"
"rcutils"
"rosidl_typesupport_fastrtps_c"
"rosidl_typesupport_fastrtps_cpp"
diff --git a/rmw_fastrtps_cpp/package.xml b/rmw_fastrtps_cpp/package.xml
index 776e4afe6..b216426f4 100644
--- a/rmw_fastrtps_cpp/package.xml
+++ b/rmw_fastrtps_cpp/package.xml
@@ -18,6 +18,7 @@
fastcdr
fastrtps
fastrtps_cmake_module
+ rcpputils
rcutils
rmw
rmw_dds_common
@@ -39,6 +40,7 @@
rosidl_typesupport_fastrtps_c
rosidl_typesupport_fastrtps_cpp
+ rcpputils
rcutils
rmw
rmw_fastrtps_shared_cpp
diff --git a/rmw_fastrtps_cpp/src/rmw_init.cpp b/rmw_fastrtps_cpp/src/rmw_init.cpp
index 9fda70589..e621b5b6e 100644
--- a/rmw_fastrtps_cpp/src/rmw_init.cpp
+++ b/rmw_fastrtps_cpp/src/rmw_init.cpp
@@ -13,17 +13,22 @@
// See the License for the specific language governing permissions and
// limitations under the License.
+#include
+#include
#include
#include "rcutils/strdup.h"
#include "rcutils/types.h"
+#include "rmw/error_handling.h"
#include "rmw/init.h"
#include "rmw/impl/cpp/macros.hpp"
#include "rmw/init_options.h"
#include "rmw/publisher_options.h"
#include "rmw/rmw.h"
+#include "rcpputils/scope_exit.hpp"
+
#include "rmw_dds_common/context.hpp"
#include "rmw_dds_common/msg/participant_entities_info.hpp"
@@ -68,55 +73,63 @@ using rmw_dds_common::msg::ParticipantEntitiesInfo;
rmw_ret_t
rmw_init(const rmw_init_options_t * options, rmw_context_t * context)
{
- std::unique_ptr clean_when_fail(
- context,
- [](rmw_context_t * context)
- {
- *context = rmw_get_zero_initialized_context();
- });
- rmw_ret_t ret = RMW_RET_OK;
-
- RCUTILS_CHECK_ARGUMENT_FOR_NULL(options, RMW_RET_INVALID_ARGUMENT);
- RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
+ RMW_CHECK_ARGUMENT_FOR_NULL(options, RMW_RET_INVALID_ARGUMENT);
+ RMW_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
+ RMW_CHECK_FOR_NULL_WITH_MSG(
+ options->implementation_identifier,
+ "expected initialized init options",
+ return RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
options,
options->implementation_identifier,
eprosima_fastrtps_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
+ if (NULL != context->implementation_identifier) {
+ RMW_SET_ERROR_MSG("expected a zero-initialized context");
+ return RMW_RET_INVALID_ARGUMENT;
+ }
+
+ const rmw_context_t zero_context = rmw_get_zero_initialized_context();
+ assert(0 == std::memcmp(context, &zero_context, sizeof(rmw_context_t)));
+ auto restore_context = rcpputils::make_scope_exit(
+ [context, &zero_context]() {*context = zero_context;});
+
context->instance_id = options->instance_id;
context->implementation_identifier = eprosima_fastrtps_identifier;
- std::unique_ptr context_impl(new (std::nothrow) rmw_context_impl_t());
- if (!context_impl) {
+ context->impl = new (std::nothrow) rmw_context_impl_t();
+ if (nullptr == context->impl) {
RMW_SET_ERROR_MSG("failed to allocate context impl");
return RMW_RET_BAD_ALLOC;
}
+ auto cleanup_impl = rcpputils::make_scope_exit(
+ [context]() {delete context->impl;});
+
+ context->impl->is_shutdown = false;
context->options = rmw_get_zero_initialized_init_options();
- ret = rmw_init_options_copy(options, &context->options);
+ rmw_ret_t ret = rmw_init_options_copy(options, &context->options);
if (RMW_RET_OK != ret) {
- if (RMW_RET_OK != rmw_init_options_fini(&context->options)) {
- RMW_SAFE_FWRITE_TO_STDERR(
- "'rmw_init_options_fini' failed while being executed due to '"
- RCUTILS_STRINGIFY(__function__) "' failing.\n");
- }
return ret;
}
- context_impl->is_shutdown = false;
- context->impl = context_impl.release();
- clean_when_fail.release();
+
+ cleanup_impl.cancel();
+ restore_context.cancel();
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_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
+ RMW_CHECK_FOR_NULL_WITH_MSG(
+ context->impl,
+ "expected initialized context",
+ return RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
context,
context->implementation_identifier,
eprosima_fastrtps_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
- RCUTILS_CHECK_ARGUMENT_FOR_NULL(context->impl, RMW_RET_INVALID_ARGUMENT);
context->impl->is_shutdown = true;
return RMW_RET_OK;
}
@@ -124,7 +137,11 @@ rmw_shutdown(rmw_context_t * context)
rmw_ret_t
rmw_context_fini(rmw_context_t * context)
{
- RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
+ RMW_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
+ RMW_CHECK_FOR_NULL_WITH_MSG(
+ context->impl,
+ "expected initialized context",
+ return RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
context,
context->implementation_identifier,
@@ -134,8 +151,9 @@ rmw_context_fini(rmw_context_t * context)
RCUTILS_SET_ERROR_MSG("context has not been shutdown");
return RMW_RET_INVALID_ARGUMENT;
}
+ rmw_ret_t ret = rmw_init_options_fini(&context->options);
delete context->impl;
*context = rmw_get_zero_initialized_context();
- return RMW_RET_OK;
+ return ret;
}
} // extern "C"
diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_init.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_init.cpp
index aedf8974d..a5a35143d 100644
--- a/rmw_fastrtps_dynamic_cpp/src/rmw_init.cpp
+++ b/rmw_fastrtps_dynamic_cpp/src/rmw_init.cpp
@@ -13,17 +13,22 @@
// See the License for the specific language governing permissions and
// limitations under the License.
+#include
+#include
#include
#include "rcutils/strdup.h"
#include "rcutils/types.h"
+#include "rmw/error_handling.h"
#include "rmw/impl/cpp/macros.hpp"
#include "rmw/init.h"
#include "rmw/init_options.h"
#include "rmw/publisher_options.h"
#include "rmw/rmw.h"
+#include "rcpputils/scope_exit.hpp"
+
#include "rmw_dds_common/context.hpp"
#include "rmw_dds_common/msg/participant_entities_info.hpp"
@@ -68,54 +73,63 @@ using rmw_dds_common::msg::ParticipantEntitiesInfo;
rmw_ret_t
rmw_init(const rmw_init_options_t * options, rmw_context_t * context)
{
- std::unique_ptr clean_when_fail(
- context,
- [](rmw_context_t * context)
- {
- *context = rmw_get_zero_initialized_context();
- });
- rmw_ret_t ret = RMW_RET_OK;
-
- RCUTILS_CHECK_ARGUMENT_FOR_NULL(options, RMW_RET_INVALID_ARGUMENT);
- RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
+ RMW_CHECK_ARGUMENT_FOR_NULL(options, RMW_RET_INVALID_ARGUMENT);
+ RMW_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
+ RMW_CHECK_FOR_NULL_WITH_MSG(
+ options->implementation_identifier,
+ "expected initialized init options",
+ return RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
options,
options->implementation_identifier,
eprosima_fastrtps_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
+ if (NULL != context->implementation_identifier) {
+ RMW_SET_ERROR_MSG("expected a zero-initialized context");
+ return RMW_RET_INVALID_ARGUMENT;
+ }
+
+ const rmw_context_t zero_context = rmw_get_zero_initialized_context();
+ assert(0 == std::memcmp(context, &zero_context, sizeof(rmw_context_t)));
+ auto restore_context = rcpputils::make_scope_exit(
+ [context, &zero_context]() {*context = zero_context;});
+
context->instance_id = options->instance_id;
context->implementation_identifier = eprosima_fastrtps_identifier;
- std::unique_ptr context_impl(new (std::nothrow) rmw_context_impl_t());
- if (!context_impl) {
+ context->impl = new (std::nothrow) rmw_context_impl_t();
+ if (nullptr == context->impl) {
RMW_SET_ERROR_MSG("failed to allocate context impl");
return RMW_RET_BAD_ALLOC;
}
+ auto cleanup_impl = rcpputils::make_scope_exit(
+ [context]() {delete context->impl;});
+
+ context->impl->is_shutdown = false;
context->options = rmw_get_zero_initialized_init_options();
- ret = rmw_init_options_copy(options, &context->options);
+ rmw_ret_t ret = rmw_init_options_copy(options, &context->options);
if (RMW_RET_OK != ret) {
- if (RMW_RET_OK != rmw_init_options_fini(&context->options)) {
- RMW_SAFE_FWRITE_TO_STDERR(
- "'rmw_init_options_fini' failed while being executed due to '"
- RCUTILS_STRINGIFY(__function__) "' failing.\n");
- }
return ret;
}
- context->impl = context_impl.release();
- clean_when_fail.release();
+
+ cleanup_impl.cancel();
+ restore_context.cancel();
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_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
+ RMW_CHECK_FOR_NULL_WITH_MSG(
+ context->impl,
+ "expected initialized context",
+ return RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
context,
context->implementation_identifier,
eprosima_fastrtps_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
- RCUTILS_CHECK_ARGUMENT_FOR_NULL(context->impl, RMW_RET_INVALID_ARGUMENT);
context->impl->is_shutdown = true;
return RMW_RET_OK;
}
@@ -123,7 +137,11 @@ rmw_shutdown(rmw_context_t * context)
rmw_ret_t
rmw_context_fini(rmw_context_t * context)
{
- RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
+ RMW_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
+ RMW_CHECK_FOR_NULL_WITH_MSG(
+ context->impl,
+ "expected initialized context",
+ return RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
context,
context->implementation_identifier,
@@ -133,8 +151,9 @@ rmw_context_fini(rmw_context_t * context)
RCUTILS_SET_ERROR_MSG("context has not been shutdown");
return RMW_RET_INVALID_ARGUMENT;
}
+ rmw_ret_t ret = rmw_init_options_fini(&context->options);
delete context->impl;
*context = rmw_get_zero_initialized_context();
- return RMW_RET_OK;
+ return ret;
}
} // extern "C"