Skip to content

Commit

Permalink
Remove single_threaded_executor:: namespace
Browse files Browse the repository at this point in the history
  • Loading branch information
dhood committed Dec 5, 2017
1 parent e68fe02 commit 0b13f04
Show file tree
Hide file tree
Showing 4 changed files with 5 additions and 8 deletions.
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/executors.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ namespace executors
{

using rclcpp::executors::multi_threaded_executor::MultiThreadedExecutor;
using rclcpp::executors::single_threaded_executor::SingleThreadedExecutor;
using rclcpp::executors::SingleThreadedExecutor;

/// Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
/**
Expand Down
3 changes: 0 additions & 3 deletions rclcpp/include/rclcpp/executors/single_threaded_executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,6 @@ namespace rclcpp
{
namespace executors
{
namespace single_threaded_executor
{

/// Single-threaded executor implementation
// This is the default executor created by rclcpp::spin.
Expand Down Expand Up @@ -64,7 +62,6 @@ class SingleThreadedExecutor : public executor::Executor
RCLCPP_DISABLE_COPY(SingleThreadedExecutor)
};

} // namespace single_threaded_executor
} // namespace executors
} // namespace rclcpp

Expand Down
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/rclcpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,9 +66,9 @@
* - rclcpp::spin()
* - rclcpp::spin_some()
* - rclcpp::spin_until_future_complete()
* - rclcpp::executors::single_threaded_executor::SingleThreadedExecutor
* - rclcpp::executors::single_threaded_executor::SingleThreadedExecutor::add_node()
* - rclcpp::executors::single_threaded_executor::SingleThreadedExecutor::spin()
* - rclcpp::executors::SingleThreadedExecutor
* - rclcpp::executors::SingleThreadedExecutor::add_node()
* - rclcpp::executors::SingleThreadedExecutor::spin()
* - rclcpp::executors::multi_threaded_executor::MultiThreadedExecutor
* - rclcpp::executors::multi_threaded_executor::MultiThreadedExecutor::add_node()
* - rclcpp::executors::multi_threaded_executor::MultiThreadedExecutor::spin()
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 @@ -15,7 +15,7 @@
#include "rclcpp/executors/single_threaded_executor.hpp"
#include "rclcpp/scope_exit.hpp"

using rclcpp::executors::single_threaded_executor::SingleThreadedExecutor;
using rclcpp::executors::SingleThreadedExecutor;

SingleThreadedExecutor::SingleThreadedExecutor(const rclcpp::executor::ExecutorArgs & args)
: executor::Executor(args) {}
Expand Down

0 comments on commit 0b13f04

Please sign in to comment.