Skip to content

Commit

Permalink
Remove multi_threaded_executor:: namespace
Browse files Browse the repository at this point in the history
  • Loading branch information
dhood committed Dec 5, 2017
1 parent 0b13f04 commit 03f9121
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 @@ -50,7 +50,7 @@ spin(rclcpp::Node::SharedPtr node_ptr);
namespace executors
{

using rclcpp::executors::multi_threaded_executor::MultiThreadedExecutor;
using rclcpp::executors::MultiThreadedExecutor;
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/multi_threaded_executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,6 @@ namespace rclcpp
{
namespace executors
{
namespace multi_threaded_executor
{

class MultiThreadedExecutor : public executor::Executor
{
Expand Down Expand Up @@ -63,7 +61,6 @@ class MultiThreadedExecutor : public executor::Executor
size_t number_of_threads_;
};

} // namespace multi_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 @@ -69,9 +69,9 @@
* - 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()
* - rclcpp::executors::MultiThreadedExecutor
* - rclcpp::executors::MultiThreadedExecutor::add_node()
* - rclcpp::executors::MultiThreadedExecutor::spin()
* - rclcpp/executor.hpp
* - rclcpp/executors.hpp
* - rclcpp/executors/single_threaded_executor.hpp
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#include "rclcpp/utilities.hpp"
#include "rclcpp/scope_exit.hpp"

using rclcpp::executors::multi_threaded_executor::MultiThreadedExecutor;
using rclcpp::executors::MultiThreadedExecutor;

MultiThreadedExecutor::MultiThreadedExecutor(const rclcpp::executor::ExecutorArgs & args)
: executor::Executor(args)
Expand Down

0 comments on commit 03f9121

Please sign in to comment.