Skip to content

Commit

Permalink
Remove utilities:: namespace
Browse files Browse the repository at this point in the history
  • Loading branch information
dhood committed Dec 5, 2017
1 parent 71b5f39 commit 9d80e95
Show file tree
Hide file tree
Showing 12 changed files with 28 additions and 43 deletions.
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/rate.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

Expand Down
12 changes: 0 additions & 12 deletions rclcpp/include/rclcpp/rclcpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_
3 changes: 0 additions & 3 deletions rclcpp/include/rclcpp/utilities.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
/**
Expand Down Expand Up @@ -111,7 +109,6 @@ RCLCPP_PUBLIC
bool
sleep_for(const std::chrono::nanoseconds & nanoseconds);

} // namespace utilities
} // namespace rclcpp

#endif // RCLCPP__UTILITIES_HPP_
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_);
Expand Down Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::mutex> wait_lock(wait_mutex_);
if (!rclcpp::utilities::ok() || !spinning.load()) {
if (!rclcpp::ok() || !spinning.load()) {
return;
}
any_exec = get_next_executable();
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/executors/single_threaded_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/src/rclcpp/graph_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down Expand Up @@ -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<GraphListener> weak_this = shared_from_this();
rclcpp::utilities::on_shutdown(
rclcpp::on_shutdown(
[weak_this]() {
auto shared_this = weak_this.lock();
if (shared_this) {
Expand Down Expand Up @@ -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_) {
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/node_interfaces/node_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::mutex> graph_lock(graph_mutex_);
if (!pred()) {
Expand Down
18 changes: 9 additions & 9 deletions rclcpp/src/rclcpp/utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand All @@ -174,22 +174,22 @@ 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);
});
#endif
}

bool
rclcpp::utilities::ok()
rclcpp::ok()
{
return ::g_signal_status == 0;
}
Expand All @@ -198,7 +198,7 @@ static std::mutex on_shutdown_mutex_;
static std::vector<std::function<void(void)>> on_shutdown_callbacks_;

void
rclcpp::utilities::shutdown()
rclcpp::shutdown()
{
trigger_interrupt_guard_condition(SIGINT);

Expand All @@ -211,14 +211,14 @@ rclcpp::utilities::shutdown()
}

void
rclcpp::utilities::on_shutdown(std::function<void(void)> callback)
rclcpp::on_shutdown(std::function<void(void)> callback)
{
std::lock_guard<std::mutex> 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<std::mutex> lock(g_sigint_guard_cond_handles_mutex);
auto kv = g_sigint_guard_cond_handles.find(wait_set);
Expand All @@ -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<std::mutex> lock(g_sigint_guard_cond_handles_mutex);
auto kv = g_sigint_guard_cond_handles.find(wait_set);
Expand All @@ -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;
{
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/test/test_rate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand All @@ -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();
Expand All @@ -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());
Expand All @@ -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();
Expand Down

0 comments on commit 9d80e95

Please sign in to comment.