Skip to content

Commit

Permalink
Finalize context iff shutdown. (#396)
Browse files Browse the repository at this point in the history
Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
  • Loading branch information
hidmic authored Jun 23, 2020
1 parent d855c90 commit 4ade4a1
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 4 deletions.
9 changes: 7 additions & 2 deletions rmw_fastrtps_cpp/src/rmw_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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;
}

Expand All @@ -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;
Expand Down
8 changes: 6 additions & 2 deletions rmw_fastrtps_dynamic_cpp/src/rmw_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

Expand All @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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_

0 comments on commit 4ade4a1

Please sign in to comment.