From 9d80e95f557da8a50a80567fd7864e589ab980f6 Mon Sep 17 00:00:00 2001 From: dhood Date: Tue, 5 Dec 2017 11:25:27 -0800 Subject: [PATCH] Remove utilities:: namespace --- rclcpp/include/rclcpp/executor.hpp | 2 +- rclcpp/include/rclcpp/rate.hpp | 2 +- rclcpp/include/rclcpp/rclcpp.hpp | 12 ------------ rclcpp/include/rclcpp/utilities.hpp | 3 --- rclcpp/src/rclcpp/client.cpp | 2 +- rclcpp/src/rclcpp/executor.cpp | 6 +++--- .../executors/multi_threaded_executor.cpp | 4 ++-- .../executors/single_threaded_executor.cpp | 2 +- rclcpp/src/rclcpp/graph_listener.cpp | 6 +++--- .../src/rclcpp/node_interfaces/node_graph.cpp | 2 +- rclcpp/src/rclcpp/utilities.cpp | 18 +++++++++--------- rclcpp/test/test_rate.cpp | 12 ++++++------ 12 files changed, 28 insertions(+), 43 deletions(-) diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index e753130488..3059a549e8 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -233,7 +233,7 @@ class Executor } std::chrono::nanoseconds timeout_left = timeout_ns; - while (rclcpp::utilities::ok()) { + while (rclcpp::ok()) { // Do one item of work. spin_once(timeout_left); // Check if the future is set, return SUCCESS if it is. diff --git a/rclcpp/include/rclcpp/rate.hpp b/rclcpp/include/rclcpp/rate.hpp index 7e7fe71664..296cce14a1 100644 --- a/rclcpp/include/rclcpp/rate.hpp +++ b/rclcpp/include/rclcpp/rate.hpp @@ -82,7 +82,7 @@ class GenericRate : public RateBase return false; } // Sleep (will get interrupted by ctrl-c, may not sleep full time) - rclcpp::utilities::sleep_for(time_to_sleep); + rclcpp::sleep_for(time_to_sleep); return true; } diff --git a/rclcpp/include/rclcpp/rclcpp.hpp b/rclcpp/include/rclcpp/rclcpp.hpp index 3f57d9b5cd..518ecac05f 100644 --- a/rclcpp/include/rclcpp/rclcpp.hpp +++ b/rclcpp/include/rclcpp/rclcpp.hpp @@ -150,16 +150,4 @@ #include "rclcpp/utilities.hpp" #include "rclcpp/visibility_control.hpp" -namespace rclcpp -{ - -// Namespace escalations. -using rclcpp::utilities::ok; -using rclcpp::utilities::ok; -using rclcpp::utilities::shutdown; -using rclcpp::utilities::init; -using rclcpp::utilities::sleep_for; - -} // namespace rclcpp - #endif // RCLCPP__RCLCPP_HPP_ diff --git a/rclcpp/include/rclcpp/utilities.hpp b/rclcpp/include/rclcpp/utilities.hpp index 36879a2d4b..a17a631257 100644 --- a/rclcpp/include/rclcpp/utilities.hpp +++ b/rclcpp/include/rclcpp/utilities.hpp @@ -44,8 +44,6 @@ std::string to_string(T value) namespace rclcpp { -namespace utilities -{ /// Initialize communications via the rmw implementation and set up a global signal handler. /** @@ -111,7 +109,6 @@ RCLCPP_PUBLIC bool sleep_for(const std::chrono::nanoseconds & nanoseconds); -} // namespace utilities } // namespace rclcpp #endif // RCLCPP__UTILITIES_HPP_ diff --git a/rclcpp/src/rclcpp/client.cpp b/rclcpp/src/rclcpp/client.cpp index 7dd7f5a806..d646005b1f 100644 --- a/rclcpp/src/rclcpp/client.cpp +++ b/rclcpp/src/rclcpp/client.cpp @@ -100,7 +100,7 @@ ClientBase::wait_for_service_nanoseconds(std::chrono::nanoseconds timeout) } // continue forever if timeout is negative, otherwise continue until out of time_to_wait do { - if (!rclcpp::utilities::ok()) { + if (!rclcpp::ok()) { return false; } node_ptr->wait_for_graph_change(event, time_to_wait); diff --git a/rclcpp/src/rclcpp/executor.cpp b/rclcpp/src/rclcpp/executor.cpp index 8744b0bf05..c03a9f2f98 100644 --- a/rclcpp/src/rclcpp/executor.cpp +++ b/rclcpp/src/rclcpp/executor.cpp @@ -50,7 +50,7 @@ Executor::Executor(const ExecutorArgs & args) // and one for the executor's guard cond (interrupt_guard_condition_) // Put the global ctrl-c guard condition in - memory_strategy_->add_guard_condition(rclcpp::utilities::get_sigint_guard_condition(&wait_set_)); + memory_strategy_->add_guard_condition(rclcpp::get_sigint_guard_condition(&wait_set_)); // Put the executor's guard condition in memory_strategy_->add_guard_condition(&interrupt_guard_condition_); @@ -97,8 +97,8 @@ Executor::~Executor() } // Remove and release the sigint guard condition memory_strategy_->remove_guard_condition( - rclcpp::utilities::get_sigint_guard_condition(&wait_set_)); - rclcpp::utilities::release_sigint_guard_condition(&wait_set_); + rclcpp::get_sigint_guard_condition(&wait_set_)); + rclcpp::release_sigint_guard_condition(&wait_set_); } void diff --git a/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp b/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp index e333d64a3f..b31fbe7e0c 100644 --- a/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp +++ b/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp @@ -66,11 +66,11 @@ MultiThreadedExecutor::get_number_of_threads() void MultiThreadedExecutor::run(size_t) { - while (rclcpp::utilities::ok() && spinning.load()) { + while (rclcpp::ok() && spinning.load()) { executor::AnyExecutable::SharedPtr any_exec; { std::lock_guard wait_lock(wait_mutex_); - if (!rclcpp::utilities::ok() || !spinning.load()) { + if (!rclcpp::ok() || !spinning.load()) { return; } any_exec = get_next_executable(); diff --git a/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp b/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp index 4ced407950..291560d13c 100644 --- a/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp +++ b/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp @@ -29,7 +29,7 @@ SingleThreadedExecutor::spin() throw std::runtime_error("spin() called while already spinning"); } RCLCPP_SCOPE_EXIT(this->spinning.store(false); ); - while (rclcpp::utilities::ok() && spinning.load()) { + while (rclcpp::ok() && spinning.load()) { auto any_exec = get_next_executable(); execute_any_executable(any_exec); } diff --git a/rclcpp/src/rclcpp/graph_listener.cpp b/rclcpp/src/rclcpp/graph_listener.cpp index 843f4bb120..26c9c58ef0 100644 --- a/rclcpp/src/rclcpp/graph_listener.cpp +++ b/rclcpp/src/rclcpp/graph_listener.cpp @@ -43,7 +43,7 @@ GraphListener::GraphListener() throw_from_rcl_error(ret, "failed to create interrupt guard condition"); } - shutdown_guard_condition_ = rclcpp::utilities::get_sigint_guard_condition(&wait_set_); + shutdown_guard_condition_ = rclcpp::get_sigint_guard_condition(&wait_set_); } GraphListener::~GraphListener() @@ -75,7 +75,7 @@ GraphListener::start_if_not_started() // This is important to ensure that the wait set is finalized before // destruction of static objects occurs. std::weak_ptr weak_this = shared_from_this(); - rclcpp::utilities::on_shutdown( + rclcpp::on_shutdown( [weak_this]() { auto shared_this = weak_this.lock(); if (shared_this) { @@ -335,7 +335,7 @@ GraphListener::shutdown() throw_from_rcl_error(ret, "failed to finalize interrupt guard condition"); } if (shutdown_guard_condition_) { - rclcpp::utilities::release_sigint_guard_condition(&wait_set_); + rclcpp::release_sigint_guard_condition(&wait_set_); shutdown_guard_condition_ = nullptr; } if (is_started_) { diff --git a/rclcpp/src/rclcpp/node_interfaces/node_graph.cpp b/rclcpp/src/rclcpp/node_interfaces/node_graph.cpp index a287437290..fc2bfbae41 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_graph.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_graph.cpp @@ -297,7 +297,7 @@ NodeGraph::wait_for_graph_change( } } auto pred = [&event]() { - return event->check() || !rclcpp::utilities::ok(); + return event->check() || !rclcpp::ok(); }; std::unique_lock graph_lock(graph_mutex_); if (!pred()) { diff --git a/rclcpp/src/rclcpp/utilities.cpp b/rclcpp/src/rclcpp/utilities.cpp index 8f07a96a1e..e387f6f92c 100644 --- a/rclcpp/src/rclcpp/utilities.cpp +++ b/rclcpp/src/rclcpp/utilities.cpp @@ -157,7 +157,7 @@ signal_handler(int signal_value) } void -rclcpp::utilities::init(int argc, char * argv[]) +rclcpp::init(int argc, char * argv[]) { g_is_interrupted.store(false); if (rcl_init(argc, argv, rcl_get_default_allocator()) != RCL_RET_OK) { @@ -174,14 +174,14 @@ rclcpp::utilities::init(int argc, char * argv[]) action.sa_flags = SA_SIGINFO; ::old_action = set_sigaction(SIGINT, action); // Register an on_shutdown hook to restore the old action. - rclcpp::utilities::on_shutdown( + rclcpp::on_shutdown( []() { set_sigaction(SIGINT, ::old_action); }); #else ::old_signal_handler = set_signal_handler(SIGINT, ::signal_handler); // Register an on_shutdown hook to restore the old signal handler. - rclcpp::utilities::on_shutdown( + rclcpp::on_shutdown( []() { set_signal_handler(SIGINT, ::old_signal_handler); }); @@ -189,7 +189,7 @@ rclcpp::utilities::init(int argc, char * argv[]) } bool -rclcpp::utilities::ok() +rclcpp::ok() { return ::g_signal_status == 0; } @@ -198,7 +198,7 @@ static std::mutex on_shutdown_mutex_; static std::vector> on_shutdown_callbacks_; void -rclcpp::utilities::shutdown() +rclcpp::shutdown() { trigger_interrupt_guard_condition(SIGINT); @@ -211,14 +211,14 @@ rclcpp::utilities::shutdown() } void -rclcpp::utilities::on_shutdown(std::function callback) +rclcpp::on_shutdown(std::function callback) { std::lock_guard lock(on_shutdown_mutex_); on_shutdown_callbacks_.push_back(callback); } rcl_guard_condition_t * -rclcpp::utilities::get_sigint_guard_condition(rcl_wait_set_t * wait_set) +rclcpp::get_sigint_guard_condition(rcl_wait_set_t * wait_set) { std::lock_guard lock(g_sigint_guard_cond_handles_mutex); auto kv = g_sigint_guard_cond_handles.find(wait_set); @@ -240,7 +240,7 @@ rclcpp::utilities::get_sigint_guard_condition(rcl_wait_set_t * wait_set) } void -rclcpp::utilities::release_sigint_guard_condition(rcl_wait_set_t * wait_set) +rclcpp::release_sigint_guard_condition(rcl_wait_set_t * wait_set) { std::lock_guard lock(g_sigint_guard_cond_handles_mutex); auto kv = g_sigint_guard_cond_handles.find(wait_set); @@ -262,7 +262,7 @@ rclcpp::utilities::release_sigint_guard_condition(rcl_wait_set_t * wait_set) } bool -rclcpp::utilities::sleep_for(const std::chrono::nanoseconds & nanoseconds) +rclcpp::sleep_for(const std::chrono::nanoseconds & nanoseconds) { std::chrono::nanoseconds time_left = nanoseconds; { diff --git a/rclcpp/test/test_rate.cpp b/rclcpp/test/test_rate.cpp index 7a5b4c0591..a4c1c4386a 100644 --- a/rclcpp/test/test_rate.cpp +++ b/rclcpp/test/test_rate.cpp @@ -36,14 +36,14 @@ TEST(TestRate, rate_basics) { ASSERT_TRUE(period < delta); ASSERT_TRUE(period * overrun_ratio > delta); - rclcpp::utilities::sleep_for(offset); + rclcpp::sleep_for(offset); ASSERT_TRUE(r.sleep()); auto two = std::chrono::system_clock::now(); delta = two - start; ASSERT_TRUE(2 * period < delta); ASSERT_TRUE(2 * period * overrun_ratio > delta); - rclcpp::utilities::sleep_for(offset); + rclcpp::sleep_for(offset); auto two_offset = std::chrono::system_clock::now(); r.reset(); ASSERT_TRUE(r.sleep()); @@ -52,7 +52,7 @@ TEST(TestRate, rate_basics) { ASSERT_TRUE(period < delta); ASSERT_TRUE(period * overrun_ratio > delta); - rclcpp::utilities::sleep_for(offset + period); + rclcpp::sleep_for(offset + period); auto four = std::chrono::system_clock::now(); ASSERT_FALSE(r.sleep()); auto five = std::chrono::system_clock::now(); @@ -75,14 +75,14 @@ TEST(TestRate, wall_rate_basics) { ASSERT_TRUE(period < delta); ASSERT_TRUE(period * overrun_ratio > delta); - rclcpp::utilities::sleep_for(offset); + rclcpp::sleep_for(offset); ASSERT_TRUE(r.sleep()); auto two = std::chrono::steady_clock::now(); delta = two - start; ASSERT_TRUE(2 * period < delta + epsilon); ASSERT_TRUE(2 * period * overrun_ratio > delta); - rclcpp::utilities::sleep_for(offset); + rclcpp::sleep_for(offset); auto two_offset = std::chrono::steady_clock::now(); r.reset(); ASSERT_TRUE(r.sleep()); @@ -91,7 +91,7 @@ TEST(TestRate, wall_rate_basics) { ASSERT_TRUE(period < delta); ASSERT_TRUE(period * overrun_ratio > delta); - rclcpp::utilities::sleep_for(offset + period); + rclcpp::sleep_for(offset + period); auto four = std::chrono::steady_clock::now(); ASSERT_FALSE(r.sleep()); auto five = std::chrono::steady_clock::now();