Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove e.g. node:: namespaces and namespace escalation #416

Merged
merged 19 commits into from
Dec 5, 2017
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 5 additions & 5 deletions rclcpp/include/rclcpp/any_executable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,11 +42,11 @@ struct AnyExecutable
virtual ~AnyExecutable();

// Only one of the following pointers will be set.
rclcpp::subscription::SubscriptionBase::SharedPtr subscription;
rclcpp::subscription::SubscriptionBase::SharedPtr subscription_intra_process;
rclcpp::timer::TimerBase::SharedPtr timer;
rclcpp::service::ServiceBase::SharedPtr service;
rclcpp::client::ClientBase::SharedPtr client;
rclcpp::SubscriptionBase::SharedPtr subscription;
rclcpp::SubscriptionBase::SharedPtr subscription_intra_process;
rclcpp::TimerBase::SharedPtr timer;
rclcpp::ServiceBase::SharedPtr service;
rclcpp::ClientBase::SharedPtr client;
// These are used to keep the scope on the containing items
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group;
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base;
Expand Down
4 changes: 0 additions & 4 deletions rclcpp/include/rclcpp/any_service_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,6 @@
namespace rclcpp
{

namespace any_service_callback
{

template<typename ServiceT>
class AnyServiceCallback
{
Expand Down Expand Up @@ -100,7 +97,6 @@ class AnyServiceCallback
}
};

} // namespace any_service_callback
} // namespace rclcpp

#endif // RCLCPP__ANY_SERVICE_CALLBACK_HPP_
4 changes: 0 additions & 4 deletions rclcpp/include/rclcpp/any_subscription_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,6 @@
namespace rclcpp
{

namespace any_subscription_callback
{

template<typename MessageT, typename Alloc>
class AnySubscriptionCallback
{
Expand Down Expand Up @@ -209,7 +206,6 @@ class AnySubscriptionCallback
MessageDeleter message_deleter_;
};

} // namespace any_subscription_callback
} // namespace rclcpp

#endif // RCLCPP__ANY_SUBSCRIPTION_CALLBACK_HPP_
24 changes: 12 additions & 12 deletions rclcpp/include/rclcpp/callback_group.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,19 +59,19 @@ class CallbackGroup
explicit CallbackGroup(CallbackGroupType group_type);

RCLCPP_PUBLIC
const std::vector<rclcpp::subscription::SubscriptionBase::WeakPtr> &
const std::vector<rclcpp::SubscriptionBase::WeakPtr> &
get_subscription_ptrs() const;

RCLCPP_PUBLIC
const std::vector<rclcpp::timer::TimerBase::WeakPtr> &
const std::vector<rclcpp::TimerBase::WeakPtr> &
get_timer_ptrs() const;

RCLCPP_PUBLIC
const std::vector<rclcpp::service::ServiceBase::WeakPtr> &
const std::vector<rclcpp::ServiceBase::WeakPtr> &
get_service_ptrs() const;

RCLCPP_PUBLIC
const std::vector<rclcpp::client::ClientBase::WeakPtr> &
const std::vector<rclcpp::ClientBase::WeakPtr> &
get_client_ptrs() const;

RCLCPP_PUBLIC
Expand All @@ -87,27 +87,27 @@ class CallbackGroup

RCLCPP_PUBLIC
void
add_subscription(const rclcpp::subscription::SubscriptionBase::SharedPtr subscription_ptr);
add_subscription(const rclcpp::SubscriptionBase::SharedPtr subscription_ptr);

RCLCPP_PUBLIC
void
add_timer(const rclcpp::timer::TimerBase::SharedPtr timer_ptr);
add_timer(const rclcpp::TimerBase::SharedPtr timer_ptr);

RCLCPP_PUBLIC
void
add_service(const rclcpp::service::ServiceBase::SharedPtr service_ptr);
add_service(const rclcpp::ServiceBase::SharedPtr service_ptr);

RCLCPP_PUBLIC
void
add_client(const rclcpp::client::ClientBase::SharedPtr client_ptr);
add_client(const rclcpp::ClientBase::SharedPtr client_ptr);

CallbackGroupType type_;
// Mutex to protect the subsequent vectors of pointers.
mutable std::mutex mutex_;
std::vector<rclcpp::subscription::SubscriptionBase::WeakPtr> subscription_ptrs_;
std::vector<rclcpp::timer::TimerBase::WeakPtr> timer_ptrs_;
std::vector<rclcpp::service::ServiceBase::WeakPtr> service_ptrs_;
std::vector<rclcpp::client::ClientBase::WeakPtr> client_ptrs_;
std::vector<rclcpp::SubscriptionBase::WeakPtr> subscription_ptrs_;
std::vector<rclcpp::TimerBase::WeakPtr> timer_ptrs_;
std::vector<rclcpp::ServiceBase::WeakPtr> service_ptrs_;
std::vector<rclcpp::ClientBase::WeakPtr> client_ptrs_;
std::atomic_bool can_be_taken_from_;
};

Expand Down
4 changes: 0 additions & 4 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,9 +47,6 @@ namespace node_interfaces
class NodeBaseInterface;
} // namespace node_interfaces

namespace client
{

class ClientBase
{
public:
Expand Down Expand Up @@ -282,7 +279,6 @@ class Client : public ClientBase
std::mutex pending_requests_mutex_;
};

} // namespace client
} // namespace rclcpp

#endif // RCLCPP__CLIENT_HPP_
4 changes: 0 additions & 4 deletions rclcpp/include/rclcpp/context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,6 @@
namespace rclcpp
{

namespace context
{

class Context
{
public:
Expand Down Expand Up @@ -72,7 +69,6 @@ class Context
std::mutex mutex_;
};

} // namespace context
} // namespace rclcpp

#endif // RCLCPP__CONTEXT_HPP_
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/contexts/default_context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ namespace contexts
namespace default_context
{

class DefaultContext : public rclcpp::context::Context
class DefaultContext : public rclcpp::Context
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(DefaultContext)
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace rclcpp
{

template<typename MessageT, typename CallbackT, typename AllocatorT, typename SubscriptionT>
typename rclcpp::subscription::Subscription<MessageT, AllocatorT>::SharedPtr
typename rclcpp::Subscription<MessageT, AllocatorT>::SharedPtr
create_subscription(
rclcpp::node_interfaces::NodeTopicsInterface * node_topics,
const std::string & topic_name,
Expand Down
3 changes: 0 additions & 3 deletions rclcpp/include/rclcpp/event.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,6 @@

namespace rclcpp
{
namespace event
{

class Event
{
Expand Down Expand Up @@ -52,7 +50,6 @@ class Event
std::atomic_bool state_;
};

} // namespace event
} // namespace rclcpp

#endif // RCLCPP__EVENT_HPP_
25 changes: 11 additions & 14 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,7 @@ namespace rclcpp
{

// Forward declaration is used in convenience method signature.
namespace node
{
class Node;
} // namespace node

namespace executor
{
Expand Down Expand Up @@ -124,7 +121,7 @@ class Executor
/// Convenience function which takes Node and forwards NodeBaseInterface.
RCLCPP_PUBLIC
virtual void
add_node(std::shared_ptr<rclcpp::node::Node> node_ptr, bool notify = true);
add_node(std::shared_ptr<rclcpp::Node> node_ptr, bool notify = true);

/// Remove a node from the executor.
/**
Expand All @@ -140,7 +137,7 @@ class Executor
/// Convenience function which takes Node and forwards NodeBaseInterface.
RCLCPP_PUBLIC
virtual void
remove_node(std::shared_ptr<rclcpp::node::Node> node_ptr, bool notify = true);
remove_node(std::shared_ptr<rclcpp::Node> node_ptr, bool notify = true);

/// Add a node to executor, execute the next available unit of work, and remove the node.
/**
Expand All @@ -162,7 +159,7 @@ class Executor
}

/// Convenience function which takes Node and forwards NodeBaseInterface.
template<typename NodeT = rclcpp::node::Node, typename T = std::milli>
template<typename NodeT = rclcpp::Node, typename T = std::milli>
void
spin_node_once(
std::shared_ptr<NodeT> node,
Expand All @@ -185,7 +182,7 @@ class Executor
/// Convenience function which takes Node and forwards NodeBaseInterface.
RCLCPP_PUBLIC
void
spin_node_some(std::shared_ptr<rclcpp::node::Node> node);
spin_node_some(std::shared_ptr<rclcpp::Node> node);

/// Complete all available queued work without blocking.
/**
Expand Down Expand Up @@ -236,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 Expand Up @@ -295,24 +292,24 @@ class Executor
RCLCPP_PUBLIC
static void
execute_subscription(
rclcpp::subscription::SubscriptionBase::SharedPtr subscription);
rclcpp::SubscriptionBase::SharedPtr subscription);

RCLCPP_PUBLIC
static void
execute_intra_process_subscription(
rclcpp::subscription::SubscriptionBase::SharedPtr subscription);
rclcpp::SubscriptionBase::SharedPtr subscription);

RCLCPP_PUBLIC
static void
execute_timer(rclcpp::timer::TimerBase::SharedPtr timer);
execute_timer(rclcpp::TimerBase::SharedPtr timer);

RCLCPP_PUBLIC
static void
execute_service(rclcpp::service::ServiceBase::SharedPtr service);
execute_service(rclcpp::ServiceBase::SharedPtr service);

RCLCPP_PUBLIC
static void
execute_client(rclcpp::client::ClientBase::SharedPtr client);
execute_client(rclcpp::ClientBase::SharedPtr client);

RCLCPP_PUBLIC
void
Expand All @@ -324,7 +321,7 @@ class Executor

RCLCPP_PUBLIC
rclcpp::callback_group::CallbackGroup::SharedPtr
get_group_by_timer(rclcpp::timer::TimerBase::SharedPtr timer);
get_group_by_timer(rclcpp::TimerBase::SharedPtr timer);

RCLCPP_PUBLIC
void
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/executors.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr);

RCLCPP_PUBLIC
void
spin_some(rclcpp::node::Node::SharedPtr node_ptr);
spin_some(rclcpp::Node::SharedPtr node_ptr);

/// Create a default single-threaded executor and spin the specified node.
/** \param[in] node_ptr Shared pointer to the node to spin. */
Expand All @@ -45,13 +45,13 @@ spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr);

RCLCPP_PUBLIC
void
spin(rclcpp::node::Node::SharedPtr node_ptr);
spin(rclcpp::Node::SharedPtr node_ptr);

namespace executors
{

using rclcpp::executors::multi_threaded_executor::MultiThreadedExecutor;
using rclcpp::executors::single_threaded_executor::SingleThreadedExecutor;
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 Expand Up @@ -81,7 +81,7 @@ spin_node_until_future_complete(
return retcode;
}

template<typename NodeT = rclcpp::node::Node, typename ResponseT, typename TimeT = std::milli>
template<typename NodeT = rclcpp::Node, typename ResponseT, typename TimeT = std::milli>
rclcpp::executor::FutureReturnCode
spin_node_until_future_complete(
rclcpp::executor::Executor & executor,
Expand Down Expand Up @@ -109,7 +109,7 @@ spin_until_future_complete(
return executors::spin_node_until_future_complete<FutureT>(executor, node_ptr, future, timeout);
}

template<typename NodeT = rclcpp::node::Node, typename FutureT, typename TimeT = std::milli>
template<typename NodeT = rclcpp::Node, typename FutureT, typename TimeT = std::milli>
rclcpp::executor::FutureReturnCode
spin_until_future_complete(
std::shared_ptr<NodeT> node_ptr,
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
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/intra_process_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,7 @@ class IntraProcessManager
*/
RCLCPP_PUBLIC
uint64_t
add_subscription(subscription::SubscriptionBase::SharedPtr subscription);
add_subscription(SubscriptionBase::SharedPtr subscription);

/// Unregister a subscription using the subscription's unique id.
/**
Expand Down Expand Up @@ -187,14 +187,14 @@ class IntraProcessManager
template<typename MessageT, typename Alloc>
uint64_t
add_publisher(
typename publisher::Publisher<MessageT, Alloc>::SharedPtr publisher,
typename Publisher<MessageT, Alloc>::SharedPtr publisher,
size_t buffer_size = 0)
{
auto id = IntraProcessManager::get_next_unique_id();
size_t size = buffer_size > 0 ? buffer_size : publisher->get_queue_size();
auto mrb = mapped_ring_buffer::MappedRingBuffer<
MessageT,
typename publisher::Publisher<MessageT, Alloc>::MessageAlloc
typename Publisher<MessageT, Alloc>::MessageAlloc
>::make_shared(size, publisher->get_allocator());
impl_->add_publisher(id, publisher, mrb, size);
return id;
Expand Down
Loading