From 3f73bbe1e898ce666f1d0c5580a8cb3c5ab61829 Mon Sep 17 00:00:00 2001 From: "Tomoya.Fujita" Date: Tue, 30 Jun 2020 11:36:48 +0900 Subject: [PATCH] get rid of unnecessary headers and fix comments. Signed-off-by: Tomoya.Fujita --- rclcpp/include/rclcpp/init_options.hpp | 8 +++----- rclcpp/src/rclcpp/init_options.cpp | 2 +- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/rclcpp/include/rclcpp/init_options.hpp b/rclcpp/include/rclcpp/init_options.hpp index 8160a7d868..093e12ee58 100644 --- a/rclcpp/include/rclcpp/init_options.hpp +++ b/rclcpp/include/rclcpp/init_options.hpp @@ -16,11 +16,9 @@ #define RCLCPP__INIT_OPTIONS_HPP_ #include -#include #include "rcl/init_options.h" #include "rclcpp/visibility_control.hpp" -#include "rcutils/get_env.h" namespace rclcpp { @@ -82,17 +80,17 @@ class InitOptions const rcl_init_options_t * get_rcl_init_options() const; - /// Retrieve the ROS_DOMAIN_ID environment variable. + /// Retrieve default domain id and set. RCLCPP_PUBLIC void use_default_domain_id(); - /// Set domain id. + /// Set the domain id. RCLCPP_PUBLIC void set_domain_id(size_t domain_id); - /// Return the domain id. + /// Return domain id. RCLCPP_PUBLIC size_t get_domain_id() const; diff --git a/rclcpp/src/rclcpp/init_options.cpp b/rclcpp/src/rclcpp/init_options.cpp index a05a24d6be..4134c5edad 100644 --- a/rclcpp/src/rclcpp/init_options.cpp +++ b/rclcpp/src/rclcpp/init_options.cpp @@ -125,7 +125,7 @@ InitOptions::get_domain_id() const size_t domain_id; rcl_ret_t ret = rcl_init_options_get_domain_id(init_options_.get(), &domain_id); if (RCL_RET_OK != ret) { - rclcpp::exceptions::throw_from_rcl_error(ret, "failed to get domain id to rcl init options"); + rclcpp::exceptions::throw_from_rcl_error(ret, "failed to get domain id from rcl init options"); } return domain_id;