From e494b3efada0258845e41ca866c5baadc8c9a83c Mon Sep 17 00:00:00 2001 From: Barry Xu <43591679+Barry-Xu-2018@users.noreply.github.com> Date: Tue, 3 Dec 2019 21:08:06 +0800 Subject: [PATCH] Add enable_rosout into NodeOptions. (#900) * Add disable_rosout into NodeOptions. Signed-off-by: Barry Xu * Update comments Signed-off-by: Barry Xu * keep implementation consistency by using enable_rosout name Signed-off-by: Barry Xu * fix error comment Signed-off-by: Barry Xu * add test case for node options Signed-off-by: Barry Xu * fix source about copy value and reset rcl_node_options, add more test cases Signed-off-by: Barry Xu --- rclcpp/include/rclcpp/node_options.hpp | 18 +++++++++++++++ rclcpp/src/rclcpp/node_options.cpp | 16 +++++++++++++ rclcpp/test/test_node_options.cpp | 32 ++++++++++++++++++++++++++ 3 files changed, 66 insertions(+) diff --git a/rclcpp/include/rclcpp/node_options.hpp b/rclcpp/include/rclcpp/node_options.hpp index 43141b6..57df850 100644 --- a/rclcpp/include/rclcpp/node_options.hpp +++ b/rclcpp/include/rclcpp/node_options.hpp @@ -152,6 +152,22 @@ public: NodeOptions & use_global_arguments(bool use_global_arguments); + /// Return the enable_rosout flag. + RCLCPP_PUBLIC + bool + enable_rosout() const; + + /// Set the enable_rosout flag, return this for parameter idiom. + /** + * If false this will cause the node not to use rosout logging. + * + * Defaults to true for now, as there are still some cases where it is + * desirable. + */ + RCLCPP_PUBLIC + NodeOptions & + enable_rosout(bool enable_rosout); + /// Return the use_intra_process_comms flag. RCLCPP_PUBLIC bool @@ -312,6 +328,8 @@ private: bool use_global_arguments_ {true}; + bool enable_rosout_ {true}; + bool use_intra_process_comms_ {false}; bool start_parameter_services_ {true}; diff --git a/rclcpp/src/rclcpp/node_options.cpp b/rclcpp/src/rclcpp/node_options.cpp index 65fe322..3d9e663 100644 --- a/rclcpp/src/rclcpp/node_options.cpp +++ b/rclcpp/src/rclcpp/node_options.cpp @@ -70,6 +70,7 @@ NodeOptions::operator=(const NodeOptions & other) this->arguments_ = other.arguments_; this->parameter_overrides_ = other.parameter_overrides_; this->use_global_arguments_ = other.use_global_arguments_; + this->enable_rosout_ = other.enable_rosout_; this->use_intra_process_comms_ = other.use_intra_process_comms_; this->start_parameter_services_ = other.start_parameter_services_; this->allocator_ = other.allocator_; @@ -90,6 +91,7 @@ NodeOptions::get_rcl_node_options() const node_options_->allocator = this->allocator_; node_options_->use_global_arguments = this->use_global_arguments_; node_options_->domain_id = this->get_domain_id_from_env(); + node_options_->enable_rosout = this->enable_rosout_; int c_argc = 0; std::unique_ptr c_argv; @@ -198,6 +200,20 @@ NodeOptions::use_global_arguments(bool use_global_arguments) return *this; } +bool +NodeOptions::enable_rosout() const +{ + return this->enable_rosout_; +} + +NodeOptions & +NodeOptions::enable_rosout(bool enable_rosout) +{ + this->node_options_.reset(); // reset node options to make it be recreated on next access. + this->enable_rosout_ = enable_rosout; + return *this; +} + bool NodeOptions::use_intra_process_comms() const { diff --git a/rclcpp/test/test_node_options.cpp b/rclcpp/test/test_node_options.cpp index c4eb969..7ffe070 100644 --- a/rclcpp/test/test_node_options.cpp +++ b/rclcpp/test/test_node_options.cpp @@ -98,3 +98,35 @@ TEST(TestNodeOptions, bad_ros_args) { options.get_rcl_node_options(), rclcpp::exceptions::UnknownROSArgsError); } + +TEST(TestNodeOptions, enable_rosout) { + { + auto options = rclcpp::NodeOptions(); + EXPECT_TRUE(options.enable_rosout()); + EXPECT_TRUE(options.get_rcl_node_options()->enable_rosout); + } + + { + auto options = rclcpp::NodeOptions().enable_rosout(false); + EXPECT_FALSE(options.enable_rosout()); + EXPECT_FALSE(options.get_rcl_node_options()->enable_rosout); + } + + { + auto options = rclcpp::NodeOptions().enable_rosout(true); + EXPECT_TRUE(options.enable_rosout()); + EXPECT_TRUE(options.get_rcl_node_options()->enable_rosout); + } + + { + auto options = rclcpp::NodeOptions(); + EXPECT_TRUE(options.enable_rosout()); + EXPECT_TRUE(options.get_rcl_node_options()->enable_rosout); + options.enable_rosout(false); + EXPECT_FALSE(options.enable_rosout()); + EXPECT_FALSE(options.get_rcl_node_options()->enable_rosout); + options.enable_rosout(true); + EXPECT_TRUE(options.enable_rosout()); + EXPECT_TRUE(options.get_rcl_node_options()->enable_rosout); + } +}