Skip to content

Commit

Permalink
add get_domain_id method to rclcpp::Context.
Browse files Browse the repository at this point in the history
Signed-off-by: Tomoya.Fujita <Tomoya.Fujita@sony.com>
  • Loading branch information
fujitatomoya committed Aug 11, 2020
1 parent bbf2c4c commit 5aaf97f
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 0 deletions.
5 changes: 5 additions & 0 deletions rclcpp/include/rclcpp/context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,11 @@ class Context : public std::enable_shared_from_this<Context>
rclcpp::InitOptions
get_init_options();

/// Return actual domain id.
RCLCPP_PUBLIC
size_t
get_domain_id() const;

/// Return the shutdown reason, or empty string if not shutdown.
/**
* This function is thread-safe.
Expand Down
11 changes: 11 additions & 0 deletions rclcpp/src/rclcpp/context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -275,6 +275,17 @@ Context::get_init_options()
return init_options_;
}

size_t
Context::get_domain_id() const
{
size_t domain_id;
rcl_ret_t ret = rcl_context_get_domain_id(rcl_context_.get(), &domain_id);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to get domain id from context");
}
return domain_id;
}

std::string
Context::shutdown_reason()
{
Expand Down

0 comments on commit 5aaf97f

Please sign in to comment.