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

Ensure compliant init/shutdown API implementation. #401

Merged
merged 4 commits into from
Jun 29, 2020
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions rmw_fastrtps_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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"
Expand Down
2 changes: 2 additions & 0 deletions rmw_fastrtps_cpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
<build_depend>fastcdr</build_depend>
<build_depend>fastrtps</build_depend>
<build_depend>fastrtps_cmake_module</build_depend>
<build_depend>rcpputils</build_depend>
<build_depend>rcutils</build_depend>
<build_depend>rmw</build_depend>
<build_depend>rmw_dds_common</build_depend>
Expand All @@ -39,6 +40,7 @@
<build_export_depend>rosidl_typesupport_fastrtps_c</build_export_depend>
<build_export_depend>rosidl_typesupport_fastrtps_cpp</build_export_depend>

<exec_depend>rcpputils</exec_depend>
<exec_depend>rcutils</exec_depend>
<exec_depend>rmw</exec_depend>
<exec_depend>rmw_fastrtps_shared_cpp</exec_depend>
Expand Down
63 changes: 37 additions & 26 deletions rmw_fastrtps_cpp/src/rmw_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,15 @@
#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"

Expand Down Expand Up @@ -68,63 +71,70 @@ using rmw_dds_common::msg::ParticipantEntitiesInfo;
rmw_ret_t
rmw_init(const rmw_init_options_t * options, rmw_context_t * context)
{
std::unique_ptr<rmw_context_t, void (*)(rmw_context_t *)> 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;
}

auto cleanup = rcpputils::make_scope_exit(
[context]() {
delete context->impl;
*context = rmw_get_zero_initialized_context();
});

context->instance_id = options->instance_id;
context->implementation_identifier = eprosima_fastrtps_identifier;

std::unique_ptr<rmw_context_impl_t> 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;
}
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.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;
}

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,
Expand All @@ -134,8 +144,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"
62 changes: 37 additions & 25 deletions rmw_fastrtps_dynamic_cpp/src/rmw_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,15 @@
#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"

Expand Down Expand Up @@ -68,62 +71,70 @@ using rmw_dds_common::msg::ParticipantEntitiesInfo;
rmw_ret_t
rmw_init(const rmw_init_options_t * options, rmw_context_t * context)
{
std::unique_ptr<rmw_context_t, void (*)(rmw_context_t *)> 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;
}

auto cleanup = rcpputils::make_scope_exit(
[context]() {
delete context->impl;
*context = rmw_get_zero_initialized_context();
});

context->instance_id = options->instance_id;
context->implementation_identifier = eprosima_fastrtps_identifier;

std::unique_ptr<rmw_context_impl_t> 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;
}
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.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;
}

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,
Expand All @@ -133,8 +144,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"