Skip to content

Commit

Permalink
reset rcl_context shared_ptr after calling rcl_init sucessfully
Browse files Browse the repository at this point in the history
Signed-off-by: Chen Lihui <Lihui.Chen@sony.com>
  • Loading branch information
Chen Lihui authored and Chen Lihui committed Sep 30, 2020
1 parent e73b613 commit dbf41b5
Showing 1 changed file with 8 additions and 4 deletions.
12 changes: 8 additions & 4 deletions rclcpp/src/rclcpp/context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -199,13 +199,17 @@ Context::init(
throw rclcpp::ContextAlreadyInitialized();
}
this->clean_up();
rcl_context_.reset(new rcl_context_t, __delete_context);
*rcl_context_.get() = rcl_get_zero_initialized_context();
rcl_ret_t ret = rcl_init(argc, argv, init_options.get_rcl_init_options(), rcl_context_.get());
rcl_context_t* context = new rcl_context_t;
if (!context) {
throw std::runtime_error("failed to allocate memory for rcl context");
}
*context = rcl_get_zero_initialized_context();
rcl_ret_t ret = rcl_init(argc, argv, init_options.get_rcl_init_options(), context);
if (RCL_RET_OK != ret) {
rcl_context_.reset();
delete context;
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to initialize rcl");
}
rcl_context_.reset(context, __delete_context);

if (init_options.auto_initialize_logging()) {
logging_mutex_ = get_global_logging_mutex();
Expand Down

0 comments on commit dbf41b5

Please sign in to comment.