diff --git a/rclcpp/include/rclcpp/any_executable.hpp b/rclcpp/include/rclcpp/any_executable.hpp index a0ddc75f02..4820b4b8d4 100644 --- a/rclcpp/include/rclcpp/any_executable.hpp +++ b/rclcpp/include/rclcpp/any_executable.hpp @@ -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; diff --git a/rclcpp/include/rclcpp/any_service_callback.hpp b/rclcpp/include/rclcpp/any_service_callback.hpp index ae9072cb77..598e0ef8ab 100644 --- a/rclcpp/include/rclcpp/any_service_callback.hpp +++ b/rclcpp/include/rclcpp/any_service_callback.hpp @@ -27,9 +27,6 @@ namespace rclcpp { -namespace any_service_callback -{ - template class AnyServiceCallback { @@ -100,7 +97,6 @@ class AnyServiceCallback } }; -} // namespace any_service_callback } // namespace rclcpp #endif // RCLCPP__ANY_SERVICE_CALLBACK_HPP_ diff --git a/rclcpp/include/rclcpp/any_subscription_callback.hpp b/rclcpp/include/rclcpp/any_subscription_callback.hpp index 7a66a86b47..5850126548 100644 --- a/rclcpp/include/rclcpp/any_subscription_callback.hpp +++ b/rclcpp/include/rclcpp/any_subscription_callback.hpp @@ -30,9 +30,6 @@ namespace rclcpp { -namespace any_subscription_callback -{ - template class AnySubscriptionCallback { @@ -209,7 +206,6 @@ class AnySubscriptionCallback MessageDeleter message_deleter_; }; -} // namespace any_subscription_callback } // namespace rclcpp #endif // RCLCPP__ANY_SUBSCRIPTION_CALLBACK_HPP_ diff --git a/rclcpp/include/rclcpp/callback_group.hpp b/rclcpp/include/rclcpp/callback_group.hpp index 62a395aa2d..810bfc3a4e 100644 --- a/rclcpp/include/rclcpp/callback_group.hpp +++ b/rclcpp/include/rclcpp/callback_group.hpp @@ -59,19 +59,19 @@ class CallbackGroup explicit CallbackGroup(CallbackGroupType group_type); RCLCPP_PUBLIC - const std::vector & + const std::vector & get_subscription_ptrs() const; RCLCPP_PUBLIC - const std::vector & + const std::vector & get_timer_ptrs() const; RCLCPP_PUBLIC - const std::vector & + const std::vector & get_service_ptrs() const; RCLCPP_PUBLIC - const std::vector & + const std::vector & get_client_ptrs() const; RCLCPP_PUBLIC @@ -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 subscription_ptrs_; - std::vector timer_ptrs_; - std::vector service_ptrs_; - std::vector client_ptrs_; + std::vector subscription_ptrs_; + std::vector timer_ptrs_; + std::vector service_ptrs_; + std::vector client_ptrs_; std::atomic_bool can_be_taken_from_; }; diff --git a/rclcpp/include/rclcpp/client.hpp b/rclcpp/include/rclcpp/client.hpp index 1637b8320c..f6eb9d2509 100644 --- a/rclcpp/include/rclcpp/client.hpp +++ b/rclcpp/include/rclcpp/client.hpp @@ -47,9 +47,6 @@ namespace node_interfaces class NodeBaseInterface; } // namespace node_interfaces -namespace client -{ - class ClientBase { public: @@ -282,7 +279,6 @@ class Client : public ClientBase std::mutex pending_requests_mutex_; }; -} // namespace client } // namespace rclcpp #endif // RCLCPP__CLIENT_HPP_ diff --git a/rclcpp/include/rclcpp/context.hpp b/rclcpp/include/rclcpp/context.hpp index 2ec86b960c..79ea48383a 100644 --- a/rclcpp/include/rclcpp/context.hpp +++ b/rclcpp/include/rclcpp/context.hpp @@ -30,9 +30,6 @@ namespace rclcpp { -namespace context -{ - class Context { public: @@ -72,7 +69,6 @@ class Context std::mutex mutex_; }; -} // namespace context } // namespace rclcpp #endif // RCLCPP__CONTEXT_HPP_ diff --git a/rclcpp/include/rclcpp/contexts/default_context.hpp b/rclcpp/include/rclcpp/contexts/default_context.hpp index 2a31da9269..2ed9bcbbf1 100644 --- a/rclcpp/include/rclcpp/contexts/default_context.hpp +++ b/rclcpp/include/rclcpp/contexts/default_context.hpp @@ -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) diff --git a/rclcpp/include/rclcpp/create_subscription.hpp b/rclcpp/include/rclcpp/create_subscription.hpp index cab3baa647..5125d9b16f 100644 --- a/rclcpp/include/rclcpp/create_subscription.hpp +++ b/rclcpp/include/rclcpp/create_subscription.hpp @@ -27,7 +27,7 @@ namespace rclcpp { template -typename rclcpp::subscription::Subscription::SharedPtr +typename rclcpp::Subscription::SharedPtr create_subscription( rclcpp::node_interfaces::NodeTopicsInterface * node_topics, const std::string & topic_name, diff --git a/rclcpp/include/rclcpp/event.hpp b/rclcpp/include/rclcpp/event.hpp index 0ddb3f40f6..988dba29e2 100644 --- a/rclcpp/include/rclcpp/event.hpp +++ b/rclcpp/include/rclcpp/event.hpp @@ -23,8 +23,6 @@ namespace rclcpp { -namespace event -{ class Event { @@ -52,7 +50,6 @@ class Event std::atomic_bool state_; }; -} // namespace event } // namespace rclcpp #endif // RCLCPP__EVENT_HPP_ diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index 5353a378e4..3059a549e8 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -38,10 +38,7 @@ namespace rclcpp { // Forward declaration is used in convenience method signature. -namespace node -{ class Node; -} // namespace node namespace executor { @@ -124,7 +121,7 @@ class Executor /// Convenience function which takes Node and forwards NodeBaseInterface. RCLCPP_PUBLIC virtual void - add_node(std::shared_ptr node_ptr, bool notify = true); + add_node(std::shared_ptr node_ptr, bool notify = true); /// Remove a node from the executor. /** @@ -140,7 +137,7 @@ class Executor /// Convenience function which takes Node and forwards NodeBaseInterface. RCLCPP_PUBLIC virtual void - remove_node(std::shared_ptr node_ptr, bool notify = true); + remove_node(std::shared_ptr node_ptr, bool notify = true); /// Add a node to executor, execute the next available unit of work, and remove the node. /** @@ -162,7 +159,7 @@ class Executor } /// Convenience function which takes Node and forwards NodeBaseInterface. - template + template void spin_node_once( std::shared_ptr node, @@ -185,7 +182,7 @@ class Executor /// Convenience function which takes Node and forwards NodeBaseInterface. RCLCPP_PUBLIC void - spin_node_some(std::shared_ptr node); + spin_node_some(std::shared_ptr node); /// Complete all available queued work without blocking. /** @@ -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. @@ -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 @@ -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 diff --git a/rclcpp/include/rclcpp/executors.hpp b/rclcpp/include/rclcpp/executors.hpp index a99253eecd..af0bdedc00 100644 --- a/rclcpp/include/rclcpp/executors.hpp +++ b/rclcpp/include/rclcpp/executors.hpp @@ -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. */ @@ -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. /** @@ -81,7 +81,7 @@ spin_node_until_future_complete( return retcode; } -template +template rclcpp::executor::FutureReturnCode spin_node_until_future_complete( rclcpp::executor::Executor & executor, @@ -109,7 +109,7 @@ spin_until_future_complete( return executors::spin_node_until_future_complete(executor, node_ptr, future, timeout); } -template +template rclcpp::executor::FutureReturnCode spin_until_future_complete( std::shared_ptr node_ptr, diff --git a/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp b/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp index d175d6f6ee..40abbc0041 100644 --- a/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp +++ b/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp @@ -28,8 +28,6 @@ namespace rclcpp { namespace executors { -namespace multi_threaded_executor -{ class MultiThreadedExecutor : public executor::Executor { @@ -63,7 +61,6 @@ class MultiThreadedExecutor : public executor::Executor size_t number_of_threads_; }; -} // namespace multi_threaded_executor } // namespace executors } // namespace rclcpp diff --git a/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp b/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp index f70e18f26e..50e83469f4 100644 --- a/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp +++ b/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp @@ -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. @@ -64,7 +62,6 @@ class SingleThreadedExecutor : public executor::Executor RCLCPP_DISABLE_COPY(SingleThreadedExecutor) }; -} // namespace single_threaded_executor } // namespace executors } // namespace rclcpp diff --git a/rclcpp/include/rclcpp/intra_process_manager.hpp b/rclcpp/include/rclcpp/intra_process_manager.hpp index 69e5d5e121..4eed5c35fc 100644 --- a/rclcpp/include/rclcpp/intra_process_manager.hpp +++ b/rclcpp/include/rclcpp/intra_process_manager.hpp @@ -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. /** @@ -187,14 +187,14 @@ class IntraProcessManager template uint64_t add_publisher( - typename publisher::Publisher::SharedPtr publisher, + typename Publisher::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::MessageAlloc + typename Publisher::MessageAlloc >::make_shared(size, publisher->get_allocator()); impl_->add_publisher(id, publisher, mrb, size); return id; diff --git a/rclcpp/include/rclcpp/intra_process_manager_impl.hpp b/rclcpp/include/rclcpp/intra_process_manager_impl.hpp index 8ffba7444c..553c44ec1d 100644 --- a/rclcpp/include/rclcpp/intra_process_manager_impl.hpp +++ b/rclcpp/include/rclcpp/intra_process_manager_impl.hpp @@ -48,14 +48,14 @@ class IntraProcessManagerImplBase ~IntraProcessManagerImplBase() = default; virtual void - add_subscription(uint64_t id, subscription::SubscriptionBase::SharedPtr subscription) = 0; + add_subscription(uint64_t id, SubscriptionBase::SharedPtr subscription) = 0; virtual void remove_subscription(uint64_t intra_process_subscription_id) = 0; virtual void add_publisher( uint64_t id, - publisher::PublisherBase::WeakPtr publisher, + PublisherBase::WeakPtr publisher, mapped_ring_buffer::MappedRingBufferBase::SharedPtr mrb, size_t size) = 0; @@ -92,7 +92,7 @@ class IntraProcessManagerImpl : public IntraProcessManagerImplBase ~IntraProcessManagerImpl() = default; void - add_subscription(uint64_t id, subscription::SubscriptionBase::SharedPtr subscription) + add_subscription(uint64_t id, SubscriptionBase::SharedPtr subscription) { subscriptions_[id] = subscription; // subscription->get_topic_name() -> const char * can be used as the key, @@ -118,7 +118,7 @@ class IntraProcessManagerImpl : public IntraProcessManagerImplBase void add_publisher( uint64_t id, - publisher::PublisherBase::WeakPtr publisher, + PublisherBase::WeakPtr publisher, mapped_ring_buffer::MappedRingBufferBase::SharedPtr mrb, size_t size) { @@ -258,9 +258,9 @@ class IntraProcessManagerImpl : public IntraProcessManagerImplBase using AllocSet = std::set, RebindAlloc>; using SubscriptionMap = std::unordered_map< - uint64_t, subscription::SubscriptionBase::WeakPtr, + uint64_t, SubscriptionBase::WeakPtr, std::hash, std::equal_to, - RebindAlloc>>; + RebindAlloc>>; struct strcmp_wrapper : public std::binary_function { @@ -286,7 +286,7 @@ class IntraProcessManagerImpl : public IntraProcessManagerImplBase PublisherInfo() = default; - publisher::PublisherBase::WeakPtr publisher; + PublisherBase::WeakPtr publisher; std::atomic sequence_number; mapped_ring_buffer::MappedRingBufferBase::SharedPtr buffer; diff --git a/rclcpp/include/rclcpp/memory_strategy.hpp b/rclcpp/include/rclcpp/memory_strategy.hpp index 4e1523db41..0421555c6c 100644 --- a/rclcpp/include/rclcpp/memory_strategy.hpp +++ b/rclcpp/include/rclcpp/memory_strategy.hpp @@ -81,15 +81,15 @@ class RCLCPP_PUBLIC MemoryStrategy virtual rcl_allocator_t get_allocator() = 0; - static rclcpp::subscription::SubscriptionBase::SharedPtr + static rclcpp::SubscriptionBase::SharedPtr get_subscription_by_handle( const rcl_subscription_t * subscriber_handle, const WeakNodeVector & weak_nodes); - static rclcpp::service::ServiceBase::SharedPtr + static rclcpp::ServiceBase::SharedPtr get_service_by_handle(const rcl_service_t * service_handle, const WeakNodeVector & weak_nodes); - static rclcpp::client::ClientBase::SharedPtr + static rclcpp::ClientBase::SharedPtr get_client_by_handle(const rcl_client_t * client_handle, const WeakNodeVector & weak_nodes); static rclcpp::node_interfaces::NodeBaseInterface::SharedPtr @@ -99,17 +99,17 @@ class RCLCPP_PUBLIC MemoryStrategy static rclcpp::callback_group::CallbackGroup::SharedPtr get_group_by_subscription( - rclcpp::subscription::SubscriptionBase::SharedPtr subscription, + rclcpp::SubscriptionBase::SharedPtr subscription, const WeakNodeVector & weak_nodes); static rclcpp::callback_group::CallbackGroup::SharedPtr get_group_by_service( - rclcpp::service::ServiceBase::SharedPtr service, + rclcpp::ServiceBase::SharedPtr service, const WeakNodeVector & weak_nodes); static rclcpp::callback_group::CallbackGroup::SharedPtr get_group_by_client( - rclcpp::client::ClientBase::SharedPtr client, + rclcpp::ClientBase::SharedPtr client, const WeakNodeVector & weak_nodes); }; diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index b312b1ab0c..e90a04e0fd 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -60,9 +60,6 @@ namespace rclcpp { -namespace node -{ - /// Node is the single point of entry for creating publishers and subscribers. class Node : public std::enable_shared_from_this { @@ -82,7 +79,7 @@ class Node : public std::enable_shared_from_this const std::string & namespace_ = "", bool use_intra_process_comms = false); - /// Create a node based on the node name and a rclcpp::context::Context. + /// Create a node based on the node name and a rclcpp::Context. /** * \param[in] node_name Name of the node. * \param[in] namespace_ Namespace of the node. @@ -94,7 +91,7 @@ class Node : public std::enable_shared_from_this Node( const std::string & node_name, const std::string & namespace_, - rclcpp::context::Context::SharedPtr context, + rclcpp::Context::SharedPtr context, bool use_intra_process_comms = false); RCLCPP_PUBLIC @@ -137,7 +134,7 @@ class Node : public std::enable_shared_from_this */ template< typename MessageT, typename Alloc = std::allocator, - typename PublisherT = ::rclcpp::publisher::Publisher> + typename PublisherT = ::rclcpp::Publisher> std::shared_ptr create_publisher( const std::string & topic_name, size_t qos_history_depth, @@ -152,7 +149,7 @@ class Node : public std::enable_shared_from_this */ template< typename MessageT, typename Alloc = std::allocator, - typename PublisherT = ::rclcpp::publisher::Publisher> + typename PublisherT = ::rclcpp::Publisher> std::shared_ptr create_publisher( const std::string & topic_name, @@ -178,7 +175,7 @@ class Node : public std::enable_shared_from_this typename MessageT, typename CallbackT, typename Alloc = std::allocator, - typename SubscriptionT = rclcpp::subscription::Subscription> + typename SubscriptionT = rclcpp::Subscription> std::shared_ptr create_subscription( const std::string & topic_name, @@ -209,7 +206,7 @@ class Node : public std::enable_shared_from_this typename MessageT, typename CallbackT, typename Alloc = std::allocator, - typename SubscriptionT = rclcpp::subscription::Subscription> + typename SubscriptionT = rclcpp::Subscription> std::shared_ptr create_subscription( const std::string & topic_name, @@ -228,7 +225,7 @@ class Node : public std::enable_shared_from_this * \param[in] group Callback group to execute this timer's callback in. */ template - typename rclcpp::timer::WallTimer::SharedPtr + typename rclcpp::WallTimer::SharedPtr create_wall_timer( std::chrono::duration period, CallbackT callback, @@ -236,7 +233,7 @@ class Node : public std::enable_shared_from_this /* Create and return a Client. */ template - typename rclcpp::client::Client::SharedPtr + typename rclcpp::Client::SharedPtr create_client( const std::string & service_name, const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, @@ -244,7 +241,7 @@ class Node : public std::enable_shared_from_this /* Create and return a Service. */ template - typename rclcpp::service::Service::SharedPtr + typename rclcpp::Service::SharedPtr create_service( const std::string & service_name, CallbackT && callback, @@ -353,7 +350,7 @@ class Node : public std::enable_shared_from_this * out of scope. */ RCLCPP_PUBLIC - rclcpp::event::Event::SharedPtr + rclcpp::Event::SharedPtr get_graph_event(); /// Wait for a graph event to occur by waiting on an Event to become set. @@ -367,7 +364,7 @@ class Node : public std::enable_shared_from_this RCLCPP_PUBLIC void wait_for_graph_change( - rclcpp::event::Event::SharedPtr event, + rclcpp::Event::SharedPtr event, std::chrono::nanoseconds timeout); RCLCPP_PUBLIC @@ -432,7 +429,6 @@ class Node : public std::enable_shared_from_this bool use_intra_process_comms_; }; -} // namespace node } // namespace rclcpp #ifndef RCLCPP__NODE_IMPL_HPP_ diff --git a/rclcpp/include/rclcpp/node_impl.hpp b/rclcpp/include/rclcpp/node_impl.hpp index 5a2f01fa1a..3b355053ec 100644 --- a/rclcpp/include/rclcpp/node_impl.hpp +++ b/rclcpp/include/rclcpp/node_impl.hpp @@ -49,8 +49,6 @@ namespace rclcpp { -namespace node -{ template std::shared_ptr @@ -141,13 +139,13 @@ Node::create_subscription( } template -typename rclcpp::timer::WallTimer::SharedPtr +typename rclcpp::WallTimer::SharedPtr Node::create_wall_timer( std::chrono::duration period, CallbackT callback, rclcpp::callback_group::CallbackGroup::SharedPtr group) { - auto timer = rclcpp::timer::WallTimer::make_shared( + auto timer = rclcpp::WallTimer::make_shared( std::chrono::duration_cast(period), std::move(callback)); node_timers_->add_timer(timer, group); @@ -155,7 +153,7 @@ Node::create_wall_timer( } template -typename client::Client::SharedPtr +typename Client::SharedPtr Node::create_client( const std::string & service_name, const rmw_qos_profile_t & qos_profile, @@ -164,8 +162,8 @@ Node::create_client( rcl_client_options_t options = rcl_client_get_default_options(); options.qos = qos_profile; - using rclcpp::client::Client; - using rclcpp::client::ClientBase; + using rclcpp::Client; + using rclcpp::ClientBase; auto cli = Client::make_shared( node_base_.get(), @@ -179,23 +177,23 @@ Node::create_client( } template -typename rclcpp::service::Service::SharedPtr +typename rclcpp::Service::SharedPtr Node::create_service( const std::string & service_name, CallbackT && callback, const rmw_qos_profile_t & qos_profile, rclcpp::callback_group::CallbackGroup::SharedPtr group) { - rclcpp::service::AnyServiceCallback any_service_callback; + rclcpp::AnyServiceCallback any_service_callback; any_service_callback.set(std::forward(callback)); rcl_service_options_t service_options = rcl_service_get_default_options(); service_options.qos = qos_profile; - auto serv = service::Service::make_shared( + auto serv = Service::make_shared( node_base_->get_shared_rcl_node_handle(), service_name, any_service_callback, service_options); - auto serv_base_ptr = std::dynamic_pointer_cast(serv); + auto serv_base_ptr = std::dynamic_pointer_cast(serv); node_services_->add_service(serv_base_ptr, group); return serv; } @@ -216,8 +214,8 @@ Node::set_parameter_if_not_set( rclcpp::parameter::ParameterVariant parameter_variant; if (!this->get_parameter(name, parameter_variant)) { this->set_parameters({ - rclcpp::parameter::ParameterVariant(name, value), - }); + rclcpp::parameter::ParameterVariant(name, value), + }); } } @@ -248,7 +246,6 @@ Node::get_parameter_or( return got_parameter; } -} // namespace node } // namespace rclcpp #endif // RCLCPP__NODE_IMPL_HPP_ diff --git a/rclcpp/include/rclcpp/node_interfaces/node_base.hpp b/rclcpp/include/rclcpp/node_interfaces/node_base.hpp index d3d7834bf5..b0754cd69a 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_base.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_base.hpp @@ -39,7 +39,7 @@ class NodeBase : public NodeBaseInterface NodeBase( const std::string & node_name, const std::string & namespace_, - rclcpp::context::Context::SharedPtr context); + rclcpp::Context::SharedPtr context); RCLCPP_PUBLIC virtual @@ -57,7 +57,7 @@ class NodeBase : public NodeBaseInterface RCLCPP_PUBLIC virtual - rclcpp::context::Context::SharedPtr + rclcpp::Context::SharedPtr get_context(); RCLCPP_PUBLIC @@ -118,7 +118,7 @@ class NodeBase : public NodeBaseInterface private: RCLCPP_DISABLE_COPY(NodeBase) - rclcpp::context::Context::SharedPtr context_; + rclcpp::Context::SharedPtr context_; std::shared_ptr node_handle_; diff --git a/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp index 23e397c7b9..7869cde178 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp @@ -56,7 +56,7 @@ class NodeBaseInterface /** \return SharedPtr to the node's context. */ RCLCPP_PUBLIC virtual - rclcpp::context::Context::SharedPtr + rclcpp::Context::SharedPtr get_context() = 0; /// Return the rcl_node_t node handle (non-const version). diff --git a/rclcpp/include/rclcpp/node_interfaces/node_graph.hpp b/rclcpp/include/rclcpp/node_interfaces/node_graph.hpp index 09863b477f..5e747bc463 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_graph.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_graph.hpp @@ -96,14 +96,14 @@ class NodeGraph : public NodeGraphInterface RCLCPP_PUBLIC virtual - rclcpp::event::Event::SharedPtr + rclcpp::Event::SharedPtr get_graph_event(); RCLCPP_PUBLIC virtual void wait_for_graph_change( - rclcpp::event::Event::SharedPtr event, + rclcpp::Event::SharedPtr event, std::chrono::nanoseconds timeout); RCLCPP_PUBLIC @@ -127,7 +127,7 @@ class NodeGraph : public NodeGraphInterface /// For notifying waiting threads (wait_for_graph_change()) on changes (notify_graph_change()). std::condition_variable graph_cv_; /// Weak references to graph events out on loan. - std::vector graph_events_; + std::vector graph_events_; /// Number of graph events out on loan, used to determine if the graph should be monitored. /** graph_users_count_ is atomic so that it can be accessed without acquiring the graph_mutex_ */ std::atomic_size_t graph_users_count_; diff --git a/rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp index 18c978daf9..136ec9d7d1 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp @@ -113,7 +113,7 @@ class NodeGraphInterface */ RCLCPP_PUBLIC virtual - rclcpp::event::Event::SharedPtr + rclcpp::Event::SharedPtr get_graph_event() = 0; /// Wait for a graph event to occur by waiting on an Event to become set. @@ -128,7 +128,7 @@ class NodeGraphInterface virtual void wait_for_graph_change( - rclcpp::event::Event::SharedPtr event, + rclcpp::Event::SharedPtr event, std::chrono::nanoseconds timeout) = 0; /// Return the number of on loan graph events, see get_graph_event(). diff --git a/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp b/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp index 883187bfa8..0649e24635 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp @@ -113,7 +113,7 @@ class NodeParameters : public NodeParametersInterface std::map parameters_; - publisher::Publisher::SharedPtr events_publisher_; + Publisher::SharedPtr events_publisher_; }; } // namespace node_interfaces diff --git a/rclcpp/include/rclcpp/node_interfaces/node_services.hpp b/rclcpp/include/rclcpp/node_interfaces/node_services.hpp index e792525400..0b0d99dceb 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_services.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_services.hpp @@ -45,14 +45,14 @@ class NodeServices : public NodeServicesInterface virtual void add_client( - rclcpp::client::ClientBase::SharedPtr client_base_ptr, + rclcpp::ClientBase::SharedPtr client_base_ptr, rclcpp::callback_group::CallbackGroup::SharedPtr group); RCLCPP_PUBLIC virtual void add_service( - rclcpp::service::ServiceBase::SharedPtr service_base_ptr, + rclcpp::ServiceBase::SharedPtr service_base_ptr, rclcpp::callback_group::CallbackGroup::SharedPtr group); private: diff --git a/rclcpp/include/rclcpp/node_interfaces/node_services_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_services_interface.hpp index da32bb1727..7f591cecae 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_services_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_services_interface.hpp @@ -36,14 +36,14 @@ class NodeServicesInterface virtual void add_client( - rclcpp::client::ClientBase::SharedPtr client_base_ptr, + rclcpp::ClientBase::SharedPtr client_base_ptr, rclcpp::callback_group::CallbackGroup::SharedPtr group) = 0; RCLCPP_PUBLIC virtual void add_service( - rclcpp::service::ServiceBase::SharedPtr service_base_ptr, + rclcpp::ServiceBase::SharedPtr service_base_ptr, rclcpp::callback_group::CallbackGroup::SharedPtr group) = 0; }; diff --git a/rclcpp/include/rclcpp/node_interfaces/node_timers.hpp b/rclcpp/include/rclcpp/node_interfaces/node_timers.hpp index a93774b24a..955e39cbff 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_timers.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_timers.hpp @@ -45,7 +45,7 @@ class NodeTimers : public NodeTimersInterface virtual void add_timer( - rclcpp::timer::TimerBase::SharedPtr timer, + rclcpp::TimerBase::SharedPtr timer, rclcpp::callback_group::CallbackGroup::SharedPtr callback_group); private: diff --git a/rclcpp/include/rclcpp/node_interfaces/node_timers_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_timers_interface.hpp index b101186ae5..09edbadbc1 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_timers_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_timers_interface.hpp @@ -36,7 +36,7 @@ class NodeTimersInterface virtual void add_timer( - rclcpp::timer::TimerBase::SharedPtr timer, + rclcpp::TimerBase::SharedPtr timer, rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) = 0; }; diff --git a/rclcpp/include/rclcpp/node_interfaces/node_topics.hpp b/rclcpp/include/rclcpp/node_interfaces/node_topics.hpp index 9341738ef9..31cf62e54c 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_topics.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_topics.hpp @@ -47,7 +47,7 @@ class NodeTopics : public NodeTopicsInterface RCLCPP_PUBLIC virtual - rclcpp::publisher::PublisherBase::SharedPtr + rclcpp::PublisherBase::SharedPtr create_publisher( const std::string & topic_name, const rclcpp::PublisherFactory & publisher_factory, @@ -58,11 +58,11 @@ class NodeTopics : public NodeTopicsInterface virtual void add_publisher( - rclcpp::publisher::PublisherBase::SharedPtr publisher); + rclcpp::PublisherBase::SharedPtr publisher); RCLCPP_PUBLIC virtual - rclcpp::subscription::SubscriptionBase::SharedPtr + rclcpp::SubscriptionBase::SharedPtr create_subscription( const std::string & topic_name, const rclcpp::SubscriptionFactory & subscription_factory, @@ -73,7 +73,7 @@ class NodeTopics : public NodeTopicsInterface virtual void add_subscription( - rclcpp::subscription::SubscriptionBase::SharedPtr subscription, + rclcpp::SubscriptionBase::SharedPtr subscription, rclcpp::callback_group::CallbackGroup::SharedPtr callback_group); private: diff --git a/rclcpp/include/rclcpp/node_interfaces/node_topics_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_topics_interface.hpp index b515b2fdc2..2a2e628f62 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_topics_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_topics_interface.hpp @@ -42,7 +42,7 @@ class NodeTopicsInterface RCLCPP_PUBLIC virtual - rclcpp::publisher::PublisherBase::SharedPtr + rclcpp::PublisherBase::SharedPtr create_publisher( const std::string & topic_name, const rclcpp::PublisherFactory & publisher_factory, @@ -53,11 +53,11 @@ class NodeTopicsInterface virtual void add_publisher( - rclcpp::publisher::PublisherBase::SharedPtr publisher) = 0; + rclcpp::PublisherBase::SharedPtr publisher) = 0; RCLCPP_PUBLIC virtual - rclcpp::subscription::SubscriptionBase::SharedPtr + rclcpp::SubscriptionBase::SharedPtr create_subscription( const std::string & topic_name, const rclcpp::SubscriptionFactory & subscription_factory, @@ -68,7 +68,7 @@ class NodeTopicsInterface virtual void add_subscription( - rclcpp::subscription::SubscriptionBase::SharedPtr subscription, + rclcpp::SubscriptionBase::SharedPtr subscription, rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) = 0; }; diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 117e74ae53..2e36aba87d 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -40,8 +40,6 @@ namespace rclcpp { -namespace parameter_client -{ class AsyncParametersClient { @@ -59,13 +57,13 @@ class AsyncParametersClient RCLCPP_PUBLIC AsyncParametersClient( - const rclcpp::node::Node::SharedPtr node, + const rclcpp::Node::SharedPtr node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); RCLCPP_PUBLIC AsyncParametersClient( - rclcpp::node::Node * node, + rclcpp::Node * node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); @@ -114,8 +112,8 @@ class AsyncParametersClient typename CallbackT, typename Alloc = std::allocator, typename SubscriptionT = - rclcpp::subscription::Subscription> - typename rclcpp::subscription::Subscription::SharedPtr + rclcpp::Subscription> + typename rclcpp::Subscription::SharedPtr on_parameter_event(CallbackT && callback) { using rclcpp::message_memory_strategy::MessageMemoryStrategy; @@ -156,14 +154,14 @@ class AsyncParametersClient private: const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface_; - rclcpp::client::Client::SharedPtr get_parameters_client_; - rclcpp::client::Client::SharedPtr + rclcpp::Client::SharedPtr get_parameters_client_; + rclcpp::Client::SharedPtr get_parameter_types_client_; - rclcpp::client::Client::SharedPtr set_parameters_client_; - rclcpp::client::Client::SharedPtr + rclcpp::Client::SharedPtr set_parameters_client_; + rclcpp::Client::SharedPtr set_parameters_atomically_client_; - rclcpp::client::Client::SharedPtr list_parameters_client_; - rclcpp::client::Client::SharedPtr + rclcpp::Client::SharedPtr list_parameters_client_; + rclcpp::Client::SharedPtr describe_parameters_client_; std::string remote_node_name_; }; @@ -175,14 +173,14 @@ class SyncParametersClient RCLCPP_PUBLIC explicit SyncParametersClient( - rclcpp::node::Node::SharedPtr node, + rclcpp::Node::SharedPtr node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); RCLCPP_PUBLIC SyncParametersClient( rclcpp::executor::Executor::SharedPtr executor, - rclcpp::node::Node::SharedPtr node, + rclcpp::Node::SharedPtr node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); @@ -246,7 +244,7 @@ class SyncParametersClient uint64_t depth); template - typename rclcpp::subscription::Subscription::SharedPtr + typename rclcpp::Subscription::SharedPtr on_parameter_event(CallbackT && callback) { return async_parameters_client_->on_parameter_event(std::forward(callback)); @@ -269,11 +267,10 @@ class SyncParametersClient private: rclcpp::executor::Executor::SharedPtr executor_; - rclcpp::node::Node::SharedPtr node_; + rclcpp::Node::SharedPtr node_; AsyncParametersClient::SharedPtr async_parameters_client_; }; -} // namespace parameter_client } // namespace rclcpp #endif // RCLCPP__PARAMETER_CLIENT_HPP_ diff --git a/rclcpp/include/rclcpp/parameter_service.hpp b/rclcpp/include/rclcpp/parameter_service.hpp index e5dd58560e..6970cbc230 100644 --- a/rclcpp/include/rclcpp/parameter_service.hpp +++ b/rclcpp/include/rclcpp/parameter_service.hpp @@ -32,8 +32,6 @@ namespace rclcpp { -namespace parameter_service -{ class ParameterService { @@ -42,23 +40,22 @@ class ParameterService RCLCPP_PUBLIC explicit ParameterService( - const rclcpp::node::Node::SharedPtr node, + const rclcpp::Node::SharedPtr node, const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); private: - const rclcpp::node::Node::SharedPtr node_; - rclcpp::service::Service::SharedPtr get_parameters_service_; - rclcpp::service::Service::SharedPtr + const rclcpp::Node::SharedPtr node_; + rclcpp::Service::SharedPtr get_parameters_service_; + rclcpp::Service::SharedPtr get_parameter_types_service_; - rclcpp::service::Service::SharedPtr set_parameters_service_; - rclcpp::service::Service::SharedPtr + rclcpp::Service::SharedPtr set_parameters_service_; + rclcpp::Service::SharedPtr set_parameters_atomically_service_; - rclcpp::service::Service::SharedPtr + rclcpp::Service::SharedPtr describe_parameters_service_; - rclcpp::service::Service::SharedPtr list_parameters_service_; + rclcpp::Service::SharedPtr list_parameters_service_; }; -} // namespace parameter_service } // namespace rclcpp #endif // RCLCPP__PARAMETER_SERVICE_HPP_ diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index d6b46369d3..f505bef7a5 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -45,9 +45,6 @@ namespace node_interfaces class NodeTopicsInterface; } -namespace publisher -{ - class PublisherBase { friend ::rclcpp::node_interfaces::NodeTopicsInterface; @@ -305,8 +302,6 @@ class Publisher : public PublisherBase MessageDeleter message_deleter_; }; -} // namespace publisher - } // namespace rclcpp #endif // RCLCPP__PUBLISHER_HPP_ diff --git a/rclcpp/include/rclcpp/publisher_factory.hpp b/rclcpp/include/rclcpp/publisher_factory.hpp index 45bff70f6c..def1bc3e53 100644 --- a/rclcpp/include/rclcpp/publisher_factory.hpp +++ b/rclcpp/include/rclcpp/publisher_factory.hpp @@ -46,7 +46,7 @@ struct PublisherFactory { // Creates a PublisherT publisher object and returns it as a PublisherBase. using PublisherFactoryFunction = std::function< - rclcpp::publisher::PublisherBase::SharedPtr( + rclcpp::PublisherBase::SharedPtr( rclcpp::node_interfaces::NodeBaseInterface * node_base, const std::string & topic_name, rcl_publisher_options_t & publisher_options)>; @@ -58,7 +58,7 @@ struct PublisherFactory using AddPublisherToIntraProcessManagerFunction = std::function< uint64_t( rclcpp::intra_process_manager::IntraProcessManager * ipm, - rclcpp::publisher::PublisherBase::SharedPtr publisher)>; + rclcpp::PublisherBase::SharedPtr publisher)>; AddPublisherToIntraProcessManagerFunction add_publisher_to_intra_process_manager; @@ -66,7 +66,7 @@ struct PublisherFactory // PublisherT::publish() and which handles the intra process transmission of // the message being published. using SharedPublishCallbackFactoryFunction = std::function< - rclcpp::publisher::PublisherBase::StoreMessageCallbackT( + rclcpp::PublisherBase::StoreMessageCallbackT( rclcpp::intra_process_manager::IntraProcessManager::SharedPtr ipm)>; SharedPublishCallbackFactoryFunction create_shared_publish_callback; @@ -96,13 +96,13 @@ create_publisher_factory(std::shared_ptr allocator) factory.add_publisher_to_intra_process_manager = []( rclcpp::intra_process_manager::IntraProcessManager * ipm, - rclcpp::publisher::PublisherBase::SharedPtr publisher) -> uint64_t + rclcpp::PublisherBase::SharedPtr publisher) -> uint64_t { return ipm->add_publisher(std::dynamic_pointer_cast(publisher)); }; // function to create a shared publish callback std::function - using StoreMessageCallbackT = rclcpp::publisher::PublisherBase::StoreMessageCallbackT; + using StoreMessageCallbackT = rclcpp::PublisherBase::StoreMessageCallbackT; factory.create_shared_publish_callback = [](rclcpp::intra_process_manager::IntraProcessManager::SharedPtr ipm) -> StoreMessageCallbackT { @@ -129,7 +129,7 @@ create_publisher_factory(std::shared_ptr allocator) "' is incompatible from the publisher type '" + message_type_info.name() + "'"); } MessageT * typed_message_ptr = static_cast(msg); - using MessageDeleter = typename publisher::Publisher::MessageDeleter; + using MessageDeleter = typename Publisher::MessageDeleter; std::unique_ptr unique_msg(typed_message_ptr); uint64_t message_seq = ipm->store_intra_process_message(publisher_id, unique_msg); diff --git a/rclcpp/include/rclcpp/rate.hpp b/rclcpp/include/rclcpp/rate.hpp index 9587c91e1f..296cce14a1 100644 --- a/rclcpp/include/rclcpp/rate.hpp +++ b/rclcpp/include/rclcpp/rate.hpp @@ -25,8 +25,6 @@ namespace rclcpp { -namespace rate -{ class RateBase { @@ -84,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; } @@ -116,7 +114,6 @@ class GenericRate : public RateBase using Rate = GenericRate; using WallRate = GenericRate; -} // namespace rate } // namespace rclcpp #endif // RCLCPP__RATE_HPP_ diff --git a/rclcpp/include/rclcpp/rclcpp.hpp b/rclcpp/include/rclcpp/rclcpp.hpp index 3156d716af..518ecac05f 100644 --- a/rclcpp/include/rclcpp/rclcpp.hpp +++ b/rclcpp/include/rclcpp/rclcpp.hpp @@ -18,46 +18,46 @@ * It consists of these main components: * * - Node - * - rclcpp::node::Node + * - rclcpp::Node * - rclcpp/node.hpp * - Publisher - * - rclcpp::node::Node::create_publisher() - * - rclcpp::publisher::Publisher - * - rclcpp::publisher::Publisher::publish() + * - rclcpp::Node::create_publisher() + * - rclcpp::Publisher + * - rclcpp::Publisher::publish() * - rclcpp/publisher.hpp * - Subscription - * - rclcpp::node::Node::create_subscription() - * - rclcpp::subscription::Subscription + * - rclcpp::Node::create_subscription() + * - rclcpp::Subscription * - rclcpp/subscription.hpp * - Service Client - * - rclcpp::node::Node::create_client() - * - rclcpp::client::Client + * - rclcpp::Node::create_client() + * - rclcpp::Client * - rclcpp/client.hpp * - Service Server - * - rclcpp::node::Node::create_service() - * - rclcpp::service::Service + * - rclcpp::Node::create_service() + * - rclcpp::Service * - rclcpp/service.hpp * - Timer - * - rclcpp::node::Node::create_wall_timer() - * - rclcpp::timer::WallTimer - * - rclcpp::timer::TimerBase + * - rclcpp::Node::create_wall_timer() + * - rclcpp::WallTimer + * - rclcpp::TimerBase * - rclcpp/timer.hpp * - Parameters: - * - rclcpp::node::Node::set_parameters() - * - rclcpp::node::Node::get_parameters() - * - rclcpp::node::Node::get_parameter() - * - rclcpp::node::Node::describe_parameters() - * - rclcpp::node::Node::list_parameters() - * - rclcpp::node::Node::register_param_change_callback() + * - rclcpp::Node::set_parameters() + * - rclcpp::Node::get_parameters() + * - rclcpp::Node::get_parameter() + * - rclcpp::Node::describe_parameters() + * - rclcpp::Node::list_parameters() + * - rclcpp::Node::register_param_change_callback() * - rclcpp::parameter::ParameterVariant - * - rclcpp::parameter_client::AsyncParametersClient - * - rclcpp::parameter_client::SyncParametersClient + * - rclcpp::AsyncParametersClient + * - rclcpp::SyncParametersClient * - rclcpp/parameter.hpp * - rclcpp/parameter_client.hpp * - rclcpp/parameter_service.hpp * - Rate: - * - rclcpp::rate::Rate - * - rclcpp::rate::WallRate + * - rclcpp::Rate + * - rclcpp::WallRate * - rclcpp/rate.hpp * * There are also some components which help control the execution of callbacks: @@ -66,32 +66,32 @@ * - 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::multi_threaded_executor::MultiThreadedExecutor - * - rclcpp::executors::multi_threaded_executor::MultiThreadedExecutor::add_node() - * - rclcpp::executors::multi_threaded_executor::MultiThreadedExecutor::spin() + * - rclcpp::executors::SingleThreadedExecutor + * - rclcpp::executors::SingleThreadedExecutor::add_node() + * - rclcpp::executors::SingleThreadedExecutor::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 * - rclcpp/executors/multi_threaded_executor.hpp * - CallbackGroups (mechanism for enforcing concurrency rules for callbacks): - * - rclcpp::node::Node::create_callback_group() + * - rclcpp::Node::create_callback_group() * - rclcpp::callback_group::CallbackGroup * - rclcpp/callback_group.hpp * * Additionally, there are some methods for introspecting the ROS graph: * * - Graph Events (a waitable event object that wakes up when the graph changes): - * - rclcpp::node::Node::get_graph_event() - * - rclcpp::node::Node::wait_for_graph_change() - * - rclcpp::event::Event + * - rclcpp::Node::get_graph_event() + * - rclcpp::Node::wait_for_graph_change() + * - rclcpp::Event * - List topic names and types: - * - rclcpp::node::Node::get_topic_names_and_types() + * - rclcpp::Node::get_topic_names_and_types() * - Get the number of publishers or subscribers on a topic: - * - rclcpp::node::Node::count_publishers() - * - rclcpp::node::Node::count_subscribers() + * - rclcpp::Node::count_publishers() + * - rclcpp::Node::count_subscribers() * * And components related to logging: * @@ -105,7 +105,7 @@ * - Logger: * - rclcpp::Logger * - rclcpp/logger.hpp - * - rclcpp::node::Node::get_logger() + * - rclcpp::Node::get_logger() * * Finally, there are many internal API's and utilities: * @@ -121,7 +121,7 @@ * - rclcpp/strategies/allocator_memory_strategy.hpp * - rclcpp/strategies/message_pool_memory_strategy.hpp * - Context object which is shared amongst multiple Nodes: - * - rclcpp::context::Context + * - rclcpp::Context * - rclcpp/context.hpp * - rclcpp/contexts/default_context.hpp * - Various utilities: @@ -150,34 +150,4 @@ #include "rclcpp/utilities.hpp" #include "rclcpp/visibility_control.hpp" -namespace rclcpp -{ - -// Namespace escalations. -// For example, this next line escalates type "rclcpp:node::Node" to "rclcpp::Node" -using rclcpp::node::Node; -using rclcpp::publisher::Publisher; -using rclcpp::publisher::PublisherBase; -using rclcpp::subscription::Subscription; -using rclcpp::subscription::SubscriptionBase; -using rclcpp::client::Client; -using rclcpp::client::ClientBase; -using rclcpp::service::Service; -using rclcpp::service::ServiceBase; -using rclcpp::parameter_client::AsyncParametersClient; -using rclcpp::parameter_client::SyncParametersClient; -using rclcpp::parameter_service::ParameterService; -using rclcpp::rate::GenericRate; -using rclcpp::rate::WallRate; -using rclcpp::timer::GenericTimer; -using rclcpp::timer::TimerBase; -using rclcpp::timer::WallTimer; -using ContextSharedPtr = rclcpp::context::Context::SharedPtr; -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/service.hpp b/rclcpp/include/rclcpp/service.hpp index 0b05dcb8df..c84f3be27e 100644 --- a/rclcpp/include/rclcpp/service.hpp +++ b/rclcpp/include/rclcpp/service.hpp @@ -35,8 +35,6 @@ namespace rclcpp { -namespace service -{ class ServiceBase { @@ -91,8 +89,6 @@ class ServiceBase bool owns_rcl_handle_ = true; }; -using any_service_callback::AnyServiceCallback; - template class Service : public ServiceBase { @@ -223,7 +219,6 @@ class Service : public ServiceBase AnyServiceCallback any_callback_; }; -} // namespace service } // namespace rclcpp #endif // RCLCPP__SERVICE_HPP_ diff --git a/rclcpp/include/rclcpp/subscription.hpp b/rclcpp/include/rclcpp/subscription.hpp index 8471530a74..7967dc56ec 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -45,9 +45,6 @@ namespace node_interfaces class NodeTopicsInterface; } // namespace node_interfaces -namespace subscription -{ - /// Virtual base class for subscriptions. This pattern allows us to iterate over different template /// specializations of Subscription, among other things. class SubscriptionBase @@ -121,8 +118,6 @@ class SubscriptionBase RCLCPP_DISABLE_COPY(SubscriptionBase) }; -using any_subscription_callback::AnySubscriptionCallback; - /// Subscription implementation, templated on the type of message this subscription receives. template> class Subscription : public SubscriptionBase @@ -292,7 +287,6 @@ class Subscription : public SubscriptionBase uint64_t intra_process_subscription_id_; }; -} // namespace subscription } // namespace rclcpp #endif // RCLCPP__SUBSCRIPTION_HPP_ diff --git a/rclcpp/include/rclcpp/subscription_factory.hpp b/rclcpp/include/rclcpp/subscription_factory.hpp index 0173503a34..ad40f8a3a4 100644 --- a/rclcpp/include/rclcpp/subscription_factory.hpp +++ b/rclcpp/include/rclcpp/subscription_factory.hpp @@ -47,7 +47,7 @@ struct SubscriptionFactory { // Creates a Subscription object and returns it as a SubscriptionBase. using SubscriptionFactoryFunction = std::function< - rclcpp::subscription::SubscriptionBase::SharedPtr( + rclcpp::SubscriptionBase::SharedPtr( rclcpp::node_interfaces::NodeBaseInterface * node_base, const std::string & topic_name, rcl_subscription_options_t & subscription_options)>; @@ -58,7 +58,7 @@ struct SubscriptionFactory using SetupIntraProcessFunction = std::function< void( rclcpp::intra_process_manager::IntraProcessManager::SharedPtr ipm, - rclcpp::subscription::SubscriptionBase::SharedPtr subscription, + rclcpp::SubscriptionBase::SharedPtr subscription, const rcl_subscription_options_t & subscription_options)>; SetupIntraProcessFunction setup_intra_process; @@ -75,12 +75,12 @@ create_subscription_factory( { SubscriptionFactory factory; - using rclcpp::subscription::AnySubscriptionCallback; + using rclcpp::AnySubscriptionCallback; AnySubscriptionCallback any_subscription_callback(allocator); any_subscription_callback.set(std::forward(callback)); auto message_alloc = - std::make_shared::MessageAlloc>(); + std::make_shared::MessageAlloc>(); // factory function that creates a MessageT specific SubscriptionT factory.create_typed_subscription = @@ -88,13 +88,13 @@ create_subscription_factory( rclcpp::node_interfaces::NodeBaseInterface * node_base, const std::string & topic_name, rcl_subscription_options_t & subscription_options - ) -> rclcpp::subscription::SubscriptionBase::SharedPtr + ) -> rclcpp::SubscriptionBase::SharedPtr { subscription_options.allocator = rclcpp::allocator::get_rcl_allocator(*message_alloc.get()); - using rclcpp::subscription::Subscription; - using rclcpp::subscription::SubscriptionBase; + using rclcpp::Subscription; + using rclcpp::SubscriptionBase; auto sub = Subscription::make_shared( node_base->get_shared_rcl_node_handle(), @@ -110,7 +110,7 @@ create_subscription_factory( factory.setup_intra_process = [message_alloc]( rclcpp::intra_process_manager::IntraProcessManager::SharedPtr ipm, - rclcpp::subscription::SubscriptionBase::SharedPtr subscription, + rclcpp::SubscriptionBase::SharedPtr subscription, const rcl_subscription_options_t & subscription_options) { rclcpp::intra_process_manager::IntraProcessManager::WeakPtr weak_ipm = ipm; @@ -128,7 +128,7 @@ create_subscription_factory( uint64_t publisher_id, uint64_t message_sequence, uint64_t subscription_id, - typename rclcpp::subscription::Subscription::MessageUniquePtr & message) + typename rclcpp::Subscription::MessageUniquePtr & message) { auto ipm = weak_ipm.lock(); if (!ipm) { diff --git a/rclcpp/include/rclcpp/time_source.hpp b/rclcpp/include/rclcpp/time_source.hpp index 34c6424f1e..0d6f8dad30 100644 --- a/rclcpp/include/rclcpp/time_source.hpp +++ b/rclcpp/include/rclcpp/time_source.hpp @@ -36,13 +36,13 @@ class TimeSource { public: RCLCPP_PUBLIC - explicit TimeSource(rclcpp::node::Node::SharedPtr node); + explicit TimeSource(rclcpp::Node::SharedPtr node); RCLCPP_PUBLIC TimeSource(); RCLCPP_PUBLIC - void attachNode(rclcpp::node::Node::SharedPtr node); + void attachNode(rclcpp::Node::SharedPtr node); RCLCPP_PUBLIC void attachNode( @@ -77,18 +77,18 @@ class TimeSource // The subscription for the clock callback using MessageT = builtin_interfaces::msg::Time; using Alloc = std::allocator; - using SubscriptionT = rclcpp::subscription::Subscription; + using SubscriptionT = rclcpp::Subscription; std::shared_ptr clock_subscription_; // The clock callback itself void clock_cb(const builtin_interfaces::msg::Time::SharedPtr msg); // Parameter Client pointer - std::shared_ptr parameter_client_; + std::shared_ptr parameter_client_; // Parameter Event subscription using ParamMessageT = rcl_interfaces::msg::ParameterEvent; - using ParamSubscriptionT = rclcpp::subscription::Subscription; + using ParamSubscriptionT = rclcpp::Subscription; std::shared_ptr parameter_subscription_; // Callback for parameter updates diff --git a/rclcpp/include/rclcpp/timer.hpp b/rclcpp/include/rclcpp/timer.hpp index 73c1d74066..94cd537a39 100644 --- a/rclcpp/include/rclcpp/timer.hpp +++ b/rclcpp/include/rclcpp/timer.hpp @@ -37,8 +37,6 @@ namespace rclcpp { -namespace timer -{ class TimerBase { @@ -182,7 +180,6 @@ class GenericTimer : public TimerBase template using WallTimer = GenericTimer; -} // namespace timer } // namespace rclcpp #endif // RCLCPP__TIMER_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/callback_group.cpp b/rclcpp/src/rclcpp/callback_group.cpp index 6c6fa281da..52558ee2fd 100644 --- a/rclcpp/src/rclcpp/callback_group.cpp +++ b/rclcpp/src/rclcpp/callback_group.cpp @@ -23,28 +23,28 @@ CallbackGroup::CallbackGroup(CallbackGroupType group_type) : type_(group_type), can_be_taken_from_(true) {} -const std::vector & +const std::vector & CallbackGroup::get_subscription_ptrs() const { std::lock_guard lock(mutex_); return subscription_ptrs_; } -const std::vector & +const std::vector & CallbackGroup::get_timer_ptrs() const { std::lock_guard lock(mutex_); return timer_ptrs_; } -const std::vector & +const std::vector & CallbackGroup::get_service_ptrs() const { std::lock_guard lock(mutex_); return service_ptrs_; } -const std::vector & +const std::vector & CallbackGroup::get_client_ptrs() const { std::lock_guard lock(mutex_); @@ -65,28 +65,28 @@ CallbackGroup::type() const void CallbackGroup::add_subscription( - const rclcpp::subscription::SubscriptionBase::SharedPtr subscription_ptr) + const rclcpp::SubscriptionBase::SharedPtr subscription_ptr) { std::lock_guard lock(mutex_); subscription_ptrs_.push_back(subscription_ptr); } void -CallbackGroup::add_timer(const rclcpp::timer::TimerBase::SharedPtr timer_ptr) +CallbackGroup::add_timer(const rclcpp::TimerBase::SharedPtr timer_ptr) { std::lock_guard lock(mutex_); timer_ptrs_.push_back(timer_ptr); } void -CallbackGroup::add_service(const rclcpp::service::ServiceBase::SharedPtr service_ptr) +CallbackGroup::add_service(const rclcpp::ServiceBase::SharedPtr service_ptr) { std::lock_guard lock(mutex_); service_ptrs_.push_back(service_ptr); } void -CallbackGroup::add_client(const rclcpp::client::ClientBase::SharedPtr client_ptr) +CallbackGroup::add_client(const rclcpp::ClientBase::SharedPtr client_ptr) { std::lock_guard lock(mutex_); client_ptrs_.push_back(client_ptr); diff --git a/rclcpp/src/rclcpp/client.cpp b/rclcpp/src/rclcpp/client.cpp index 6a7501a883..d646005b1f 100644 --- a/rclcpp/src/rclcpp/client.cpp +++ b/rclcpp/src/rclcpp/client.cpp @@ -27,7 +27,7 @@ #include "rclcpp/node_interfaces/node_graph_interface.hpp" #include "rclcpp/utilities.hpp" -using rclcpp::client::ClientBase; +using rclcpp::ClientBase; using rclcpp::exceptions::InvalidNodeError; using rclcpp::exceptions::throw_from_rcl_error; @@ -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/context.cpp b/rclcpp/src/rclcpp/context.cpp index a5f3c17feb..fa481d796b 100644 --- a/rclcpp/src/rclcpp/context.cpp +++ b/rclcpp/src/rclcpp/context.cpp @@ -14,6 +14,6 @@ #include "rclcpp/context.hpp" -using rclcpp::context::Context; +using rclcpp::Context; Context::Context() {} diff --git a/rclcpp/src/rclcpp/event.cpp b/rclcpp/src/rclcpp/event.cpp index ab6e06c609..6be20a6335 100644 --- a/rclcpp/src/rclcpp/event.cpp +++ b/rclcpp/src/rclcpp/event.cpp @@ -16,8 +16,6 @@ namespace rclcpp { -namespace event -{ Event::Event() : state_(false) {} @@ -40,5 +38,4 @@ Event::check_and_clear() return state_.exchange(false); } -} // namespace event } // namespace rclcpp diff --git a/rclcpp/src/rclcpp/executor.cpp b/rclcpp/src/rclcpp/executor.cpp index 6334b5b8d1..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 @@ -129,7 +129,7 @@ Executor::add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_pt } void -Executor::add_node(std::shared_ptr node_ptr, bool notify) +Executor::add_node(std::shared_ptr node_ptr, bool notify) { this->add_node(node_ptr->get_node_base_interface(), notify); } @@ -163,7 +163,7 @@ Executor::remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node } void -Executor::remove_node(std::shared_ptr node_ptr, bool notify) +Executor::remove_node(std::shared_ptr node_ptr, bool notify) { this->remove_node(node_ptr->get_node_base_interface(), notify); } @@ -188,7 +188,7 @@ Executor::spin_node_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr n } void -Executor::spin_node_some(std::shared_ptr node) +Executor::spin_node_some(std::shared_ptr node) { this->spin_node_some(node->get_node_base_interface()); } @@ -269,7 +269,7 @@ Executor::execute_any_executable(AnyExecutable::SharedPtr any_exec) void Executor::execute_subscription( - rclcpp::subscription::SubscriptionBase::SharedPtr subscription) + rclcpp::SubscriptionBase::SharedPtr subscription) { std::shared_ptr message = subscription->create_message(); rmw_message_info_t message_info; @@ -290,7 +290,7 @@ Executor::execute_subscription( void Executor::execute_intra_process_subscription( - rclcpp::subscription::SubscriptionBase::SharedPtr subscription) + rclcpp::SubscriptionBase::SharedPtr subscription) { rcl_interfaces::msg::IntraProcessMessage ipm; rmw_message_info_t message_info; @@ -312,14 +312,14 @@ Executor::execute_intra_process_subscription( void Executor::execute_timer( - rclcpp::timer::TimerBase::SharedPtr timer) + rclcpp::TimerBase::SharedPtr timer) { timer->execute_callback(); } void Executor::execute_service( - rclcpp::service::ServiceBase::SharedPtr service) + rclcpp::ServiceBase::SharedPtr service) { auto request_header = service->create_request_header(); std::shared_ptr request = service->create_request(); @@ -339,7 +339,7 @@ Executor::execute_service( void Executor::execute_client( - rclcpp::client::ClientBase::SharedPtr client) + rclcpp::ClientBase::SharedPtr client) { auto request_header = client->create_request_header(); std::shared_ptr response = client->create_response(); @@ -471,7 +471,7 @@ Executor::get_node_by_group(rclcpp::callback_group::CallbackGroup::SharedPtr gro } rclcpp::callback_group::CallbackGroup::SharedPtr -Executor::get_group_by_timer(rclcpp::timer::TimerBase::SharedPtr timer) +Executor::get_group_by_timer(rclcpp::TimerBase::SharedPtr timer) { for (auto & weak_node : weak_nodes_) { auto node = weak_node.lock(); diff --git a/rclcpp/src/rclcpp/executors.cpp b/rclcpp/src/rclcpp/executors.cpp index d526808238..0a900c07da 100644 --- a/rclcpp/src/rclcpp/executors.cpp +++ b/rclcpp/src/rclcpp/executors.cpp @@ -22,7 +22,7 @@ rclcpp::spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr } void -rclcpp::spin_some(rclcpp::node::Node::SharedPtr node_ptr) +rclcpp::spin_some(rclcpp::Node::SharedPtr node_ptr) { rclcpp::spin_some(node_ptr->get_node_base_interface()); } @@ -37,7 +37,7 @@ rclcpp::spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr) } void -rclcpp::spin(rclcpp::node::Node::SharedPtr node_ptr) +rclcpp::spin(rclcpp::Node::SharedPtr node_ptr) { rclcpp::spin(node_ptr->get_node_base_interface()); } diff --git a/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp b/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp index d4889097d5..b31fbe7e0c 100644 --- a/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp +++ b/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp @@ -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) @@ -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 a4bed37208..291560d13c 100644 --- a/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp +++ b/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp @@ -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) {} @@ -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/intra_process_manager.cpp b/rclcpp/src/rclcpp/intra_process_manager.cpp index 0afcf5606b..723c43fd8d 100644 --- a/rclcpp/src/rclcpp/intra_process_manager.cpp +++ b/rclcpp/src/rclcpp/intra_process_manager.cpp @@ -31,7 +31,7 @@ IntraProcessManager::~IntraProcessManager() uint64_t IntraProcessManager::add_subscription( - rclcpp::subscription::SubscriptionBase::SharedPtr subscription) + rclcpp::SubscriptionBase::SharedPtr subscription) { auto id = IntraProcessManager::get_next_unique_id(); impl_->add_subscription(id, subscription); diff --git a/rclcpp/src/rclcpp/memory_strategy.cpp b/rclcpp/src/rclcpp/memory_strategy.cpp index 3a0db98efd..f4efb3f1b2 100644 --- a/rclcpp/src/rclcpp/memory_strategy.cpp +++ b/rclcpp/src/rclcpp/memory_strategy.cpp @@ -16,7 +16,7 @@ using rclcpp::memory_strategy::MemoryStrategy; -rclcpp::subscription::SubscriptionBase::SharedPtr +rclcpp::SubscriptionBase::SharedPtr MemoryStrategy::get_subscription_by_handle( const rcl_subscription_t * subscriber_handle, const WeakNodeVector & weak_nodes) { @@ -46,7 +46,7 @@ MemoryStrategy::get_subscription_by_handle( return nullptr; } -rclcpp::service::ServiceBase::SharedPtr +rclcpp::ServiceBase::SharedPtr MemoryStrategy::get_service_by_handle( const rcl_service_t * service_handle, const WeakNodeVector & weak_nodes) @@ -72,7 +72,7 @@ MemoryStrategy::get_service_by_handle( return nullptr; } -rclcpp::client::ClientBase::SharedPtr +rclcpp::ClientBase::SharedPtr MemoryStrategy::get_client_by_handle( const rcl_client_t * client_handle, const WeakNodeVector & weak_nodes) @@ -123,7 +123,7 @@ MemoryStrategy::get_node_by_group( rclcpp::callback_group::CallbackGroup::SharedPtr MemoryStrategy::get_group_by_subscription( - rclcpp::subscription::SubscriptionBase::SharedPtr subscription, + rclcpp::SubscriptionBase::SharedPtr subscription, const WeakNodeVector & weak_nodes) { for (auto & weak_node : weak_nodes) { @@ -149,7 +149,7 @@ MemoryStrategy::get_group_by_subscription( rclcpp::callback_group::CallbackGroup::SharedPtr MemoryStrategy::get_group_by_service( - rclcpp::service::ServiceBase::SharedPtr service, + rclcpp::ServiceBase::SharedPtr service, const WeakNodeVector & weak_nodes) { for (auto & weak_node : weak_nodes) { @@ -175,7 +175,7 @@ MemoryStrategy::get_group_by_service( rclcpp::callback_group::CallbackGroup::SharedPtr MemoryStrategy::get_group_by_client( - rclcpp::client::ClientBase::SharedPtr client, + rclcpp::ClientBase::SharedPtr client, const WeakNodeVector & weak_nodes) { for (auto & weak_node : weak_nodes) { diff --git a/rclcpp/src/rclcpp/node.cpp b/rclcpp/src/rclcpp/node.cpp index cdeab0ea76..4d55972749 100644 --- a/rclcpp/src/rclcpp/node.cpp +++ b/rclcpp/src/rclcpp/node.cpp @@ -32,7 +32,7 @@ #include "rclcpp/node_interfaces/node_timers.hpp" #include "rclcpp/node_interfaces/node_topics.hpp" -using rclcpp::node::Node; +using rclcpp::Node; using rclcpp::exceptions::throw_from_rcl_error; Node::Node( @@ -49,7 +49,7 @@ Node::Node( Node::Node( const std::string & node_name, const std::string & namespace_, - rclcpp::context::Context::SharedPtr context, + rclcpp::Context::SharedPtr context, bool use_intra_process_comms) : node_base_(new rclcpp::node_interfaces::NodeBase(node_name, namespace_, context)), node_graph_(new rclcpp::node_interfaces::NodeGraph(node_base_.get())), @@ -190,7 +190,7 @@ Node::get_callback_groups() const return node_base_->get_callback_groups(); } -rclcpp::event::Event::SharedPtr +rclcpp::Event::SharedPtr Node::get_graph_event() { return node_graph_->get_graph_event(); @@ -198,7 +198,7 @@ Node::get_graph_event() void Node::wait_for_graph_change( - rclcpp::event::Event::SharedPtr event, + rclcpp::Event::SharedPtr event, std::chrono::nanoseconds timeout) { node_graph_->wait_for_graph_change(event, timeout); diff --git a/rclcpp/src/rclcpp/node_interfaces/node_base.cpp b/rclcpp/src/rclcpp/node_interfaces/node_base.cpp index b960dcd546..e00b01ab03 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_base.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_base.cpp @@ -30,7 +30,7 @@ using rclcpp::node_interfaces::NodeBase; NodeBase::NodeBase( const std::string & node_name, const std::string & namespace_, - rclcpp::context::Context::SharedPtr context) + rclcpp::Context::SharedPtr context) : context_(context), node_handle_(nullptr), default_callback_group_(nullptr), @@ -176,7 +176,7 @@ NodeBase::get_namespace() const return rcl_node_get_namespace(node_handle_.get()); } -rclcpp::context::Context::SharedPtr +rclcpp::Context::SharedPtr NodeBase::get_context() { return context_; diff --git a/rclcpp/src/rclcpp/node_interfaces/node_graph.cpp b/rclcpp/src/rclcpp/node_interfaces/node_graph.cpp index f04f0c88f0..fc2bfbae41 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_graph.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_graph.cpp @@ -233,7 +233,7 @@ NodeGraph::notify_graph_change() std::remove_if( graph_events_.begin(), graph_events_.end(), - [](const rclcpp::event::Event::WeakPtr & wptr) { + [](const rclcpp::Event::WeakPtr & wptr) { return wptr.expired(); }), graph_events_.end()); @@ -258,10 +258,10 @@ NodeGraph::notify_shutdown() graph_cv_.notify_all(); } -rclcpp::event::Event::SharedPtr +rclcpp::Event::SharedPtr NodeGraph::get_graph_event() { - auto event = rclcpp::event::Event::make_shared(); + auto event = rclcpp::Event::make_shared(); std::lock_guard graph_changed_lock(graph_mutex_); graph_events_.push_back(event); graph_users_count_++; @@ -275,7 +275,7 @@ NodeGraph::get_graph_event() void NodeGraph::wait_for_graph_change( - rclcpp::event::Event::SharedPtr event, + rclcpp::Event::SharedPtr event, std::chrono::nanoseconds timeout) { using rclcpp::exceptions::InvalidEventError; @@ -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/node_interfaces/node_parameters.cpp b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp index b9d89b7a8b..c58d1064f4 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp @@ -33,7 +33,7 @@ NodeParameters::NodeParameters( : node_topics_(node_topics) { using MessageT = rcl_interfaces::msg::ParameterEvent; - using PublisherT = rclcpp::publisher::Publisher; + using PublisherT = rclcpp::Publisher; using AllocatorT = std::allocator; // TODO(wjwwood): expose this allocator through the Parameter interface. auto allocator = std::make_shared(); diff --git a/rclcpp/src/rclcpp/node_interfaces/node_services.cpp b/rclcpp/src/rclcpp/node_interfaces/node_services.cpp index a2585e3922..7c13438028 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_services.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_services.cpp @@ -27,7 +27,7 @@ NodeServices::~NodeServices() void NodeServices::add_service( - rclcpp::service::ServiceBase::SharedPtr service_base_ptr, + rclcpp::ServiceBase::SharedPtr service_base_ptr, rclcpp::callback_group::CallbackGroup::SharedPtr group) { if (group) { @@ -54,7 +54,7 @@ NodeServices::add_service( void NodeServices::add_client( - rclcpp::client::ClientBase::SharedPtr client_base_ptr, + rclcpp::ClientBase::SharedPtr client_base_ptr, rclcpp::callback_group::CallbackGroup::SharedPtr group) { if (group) { diff --git a/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp b/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp index 6f781c05f8..70073d2c60 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp @@ -27,7 +27,7 @@ NodeTimers::~NodeTimers() void NodeTimers::add_timer( - rclcpp::timer::TimerBase::SharedPtr timer, + rclcpp::TimerBase::SharedPtr timer, rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) { if (callback_group) { diff --git a/rclcpp/src/rclcpp/node_interfaces/node_topics.cpp b/rclcpp/src/rclcpp/node_interfaces/node_topics.cpp index 4e07d5e13e..882ac1f1b0 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_topics.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_topics.cpp @@ -30,7 +30,7 @@ NodeTopics::NodeTopics(rclcpp::node_interfaces::NodeBaseInterface * node_base) NodeTopics::~NodeTopics() {} -rclcpp::publisher::PublisherBase::SharedPtr +rclcpp::PublisherBase::SharedPtr NodeTopics::create_publisher( const std::string & topic_name, const rclcpp::PublisherFactory & publisher_factory, @@ -63,7 +63,7 @@ NodeTopics::create_publisher( void NodeTopics::add_publisher( - rclcpp::publisher::PublisherBase::SharedPtr publisher) + rclcpp::PublisherBase::SharedPtr publisher) { // The publisher is not added to a callback group or anthing like that for now. // It may be stored within the NodeTopics class or the NodeBase class in the future. @@ -79,7 +79,7 @@ NodeTopics::add_publisher( } } -rclcpp::subscription::SubscriptionBase::SharedPtr +rclcpp::SubscriptionBase::SharedPtr NodeTopics::create_subscription( const std::string & topic_name, const rclcpp::SubscriptionFactory & subscription_factory, @@ -104,7 +104,7 @@ NodeTopics::create_subscription( void NodeTopics::add_subscription( - rclcpp::subscription::SubscriptionBase::SharedPtr subscription, + rclcpp::SubscriptionBase::SharedPtr subscription, rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) { // Assign to a group. diff --git a/rclcpp/src/rclcpp/parameter_client.cpp b/rclcpp/src/rclcpp/parameter_client.cpp index 1b1812a857..18dad919b3 100644 --- a/rclcpp/src/rclcpp/parameter_client.cpp +++ b/rclcpp/src/rclcpp/parameter_client.cpp @@ -21,8 +21,8 @@ #include "./parameter_service_names.hpp" -using rclcpp::parameter_client::AsyncParametersClient; -using rclcpp::parameter_client::SyncParametersClient; +using rclcpp::AsyncParametersClient; +using rclcpp::SyncParametersClient; AsyncParametersClient::AsyncParametersClient( const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, @@ -42,8 +42,8 @@ AsyncParametersClient::AsyncParametersClient( rcl_client_options_t options = rcl_client_get_default_options(); options.qos = qos_profile; - using rclcpp::client::Client; - using rclcpp::client::ClientBase; + using rclcpp::Client; + using rclcpp::ClientBase; get_parameters_client_ = Client::make_shared( node_base_interface.get(), @@ -89,7 +89,7 @@ AsyncParametersClient::AsyncParametersClient( } AsyncParametersClient::AsyncParametersClient( - const rclcpp::node::Node::SharedPtr node, + const rclcpp::Node::SharedPtr node, const std::string & remote_node_name, const rmw_qos_profile_t & qos_profile) : AsyncParametersClient( @@ -102,7 +102,7 @@ AsyncParametersClient::AsyncParametersClient( {} AsyncParametersClient::AsyncParametersClient( - rclcpp::node::Node * node, + rclcpp::Node * node, const std::string & remote_node_name, const rmw_qos_profile_t & qos_profile) : AsyncParametersClient( @@ -131,7 +131,7 @@ AsyncParametersClient::get_parameters( get_parameters_client_->async_send_request( request, [request, promise_result, future_result, callback]( - rclcpp::client::Client::SharedFuture cb_f) + rclcpp::Client::SharedFuture cb_f) { std::vector parameter_variants; auto & pvalues = cb_f.get()->values; @@ -172,7 +172,7 @@ AsyncParametersClient::get_parameter_types( get_parameter_types_client_->async_send_request( request, [promise_result, future_result, callback]( - rclcpp::client::Client::SharedFuture cb_f) + rclcpp::Client::SharedFuture cb_f) { std::vector types; auto & pts = cb_f.get()->types; @@ -211,7 +211,7 @@ AsyncParametersClient::set_parameters( set_parameters_client_->async_send_request( request, [promise_result, future_result, callback]( - rclcpp::client::Client::SharedFuture cb_f) + rclcpp::Client::SharedFuture cb_f) { promise_result->set_value(cb_f.get()->results); if (callback != nullptr) { @@ -245,7 +245,7 @@ AsyncParametersClient::set_parameters_atomically( set_parameters_atomically_client_->async_send_request( request, [promise_result, future_result, callback]( - rclcpp::client::Client::SharedFuture cb_f) + rclcpp::Client::SharedFuture cb_f) { promise_result->set_value(cb_f.get()->result); if (callback != nullptr) { @@ -276,7 +276,7 @@ AsyncParametersClient::list_parameters( list_parameters_client_->async_send_request( request, [promise_result, future_result, callback]( - rclcpp::client::Client::SharedFuture cb_f) + rclcpp::Client::SharedFuture cb_f) { promise_result->set_value(cb_f.get()->result); if (callback != nullptr) { @@ -302,7 +302,7 @@ AsyncParametersClient::service_is_ready() const bool AsyncParametersClient::wait_for_service_nanoseconds(std::chrono::nanoseconds timeout) { - const std::vector> clients = { + const std::vector> clients = { get_parameters_client_, get_parameter_types_client_, set_parameters_client_, @@ -326,7 +326,7 @@ AsyncParametersClient::wait_for_service_nanoseconds(std::chrono::nanoseconds tim } SyncParametersClient::SyncParametersClient( - rclcpp::node::Node::SharedPtr node, + rclcpp::Node::SharedPtr node, const std::string & remote_node_name, const rmw_qos_profile_t & qos_profile) : SyncParametersClient( @@ -338,7 +338,7 @@ SyncParametersClient::SyncParametersClient( SyncParametersClient::SyncParametersClient( rclcpp::executor::Executor::SharedPtr executor, - rclcpp::node::Node::SharedPtr node, + rclcpp::Node::SharedPtr node, const std::string & remote_node_name, const rmw_qos_profile_t & qos_profile) : executor_(executor), node_(node) diff --git a/rclcpp/src/rclcpp/parameter_service.cpp b/rclcpp/src/rclcpp/parameter_service.cpp index 8ce773f4e7..86ca433ffd 100644 --- a/rclcpp/src/rclcpp/parameter_service.cpp +++ b/rclcpp/src/rclcpp/parameter_service.cpp @@ -21,14 +21,14 @@ #include "./parameter_service_names.hpp" -using rclcpp::parameter_service::ParameterService; +using rclcpp::ParameterService; ParameterService::ParameterService( - const rclcpp::node::Node::SharedPtr node, + const rclcpp::Node::SharedPtr node, const rmw_qos_profile_t & qos_profile) : node_(node) { - std::weak_ptr captured_node = node_; + std::weak_ptr captured_node = node_; get_parameters_service_ = node_->create_service( std::string(node_->get_name()) + "/" + parameter_service_names::get_parameters, [captured_node]( diff --git a/rclcpp/src/rclcpp/publisher.cpp b/rclcpp/src/rclcpp/publisher.cpp index 7302f6cf18..5a488d119b 100644 --- a/rclcpp/src/rclcpp/publisher.cpp +++ b/rclcpp/src/rclcpp/publisher.cpp @@ -33,7 +33,7 @@ #include "rclcpp/node.hpp" #include "rclcpp/expand_topic_or_service_name.hpp" -using rclcpp::publisher::PublisherBase; +using rclcpp::PublisherBase; PublisherBase::PublisherBase( rclcpp::node_interfaces::NodeBaseInterface * node_base, diff --git a/rclcpp/src/rclcpp/service.cpp b/rclcpp/src/rclcpp/service.cpp index 4a421e232f..441c2f67e6 100644 --- a/rclcpp/src/rclcpp/service.cpp +++ b/rclcpp/src/rclcpp/service.cpp @@ -25,7 +25,7 @@ #include "rmw/error_handling.h" #include "rmw/rmw.h" -using rclcpp::service::ServiceBase; +using rclcpp::ServiceBase; ServiceBase::ServiceBase( std::shared_ptr node_handle, diff --git a/rclcpp/src/rclcpp/subscription.cpp b/rclcpp/src/rclcpp/subscription.cpp index 1b84088c85..79170acdf8 100644 --- a/rclcpp/src/rclcpp/subscription.cpp +++ b/rclcpp/src/rclcpp/subscription.cpp @@ -25,7 +25,7 @@ #include "rmw/rmw.h" -using rclcpp::subscription::SubscriptionBase; +using rclcpp::SubscriptionBase; SubscriptionBase::SubscriptionBase( std::shared_ptr node_handle, diff --git a/rclcpp/src/rclcpp/time_source.cpp b/rclcpp/src/rclcpp/time_source.cpp index 38a0bcebd5..54c72dbdc4 100644 --- a/rclcpp/src/rclcpp/time_source.cpp +++ b/rclcpp/src/rclcpp/time_source.cpp @@ -33,7 +33,7 @@ namespace rclcpp { -TimeSource::TimeSource(std::shared_ptr node) +TimeSource::TimeSource(std::shared_ptr node) : ros_time_active_(false) { this->attachNode(node); @@ -44,7 +44,7 @@ TimeSource::TimeSource() { } -void TimeSource::attachNode(rclcpp::node::Node::SharedPtr node) +void TimeSource::attachNode(rclcpp::Node::SharedPtr node) { attachNode( node->get_node_base_interface(), @@ -85,7 +85,7 @@ void TimeSource::attachNode( msg_mem_strat, allocator); - parameter_client_ = std::make_shared( + parameter_client_ = std::make_shared( node_base_, node_topics_, node_graph_, diff --git a/rclcpp/src/rclcpp/timer.cpp b/rclcpp/src/rclcpp/timer.cpp index e15d68323f..db03d6b69e 100644 --- a/rclcpp/src/rclcpp/timer.cpp +++ b/rclcpp/src/rclcpp/timer.cpp @@ -17,7 +17,7 @@ #include #include -using rclcpp::timer::TimerBase; +using rclcpp::TimerBase; TimerBase::TimerBase(std::chrono::nanoseconds period) { 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_client.cpp b/rclcpp/test/test_client.cpp index 52fca58715..96c86f174a 100644 --- a/rclcpp/test/test_client.cpp +++ b/rclcpp/test/test_client.cpp @@ -32,7 +32,7 @@ class TestClient : public ::testing::Test void SetUp() { - node = std::make_shared("my_node", "/ns"); + node = std::make_shared("my_node", "/ns"); } void TearDown() @@ -40,7 +40,7 @@ class TestClient : public ::testing::Test node.reset(); } - rclcpp::node::Node::SharedPtr node; + rclcpp::Node::SharedPtr node; }; /* diff --git a/rclcpp/test/test_executor.cpp b/rclcpp/test/test_executor.cpp index f57b9614c7..4b51cf19b3 100644 --- a/rclcpp/test/test_executor.cpp +++ b/rclcpp/test/test_executor.cpp @@ -38,7 +38,7 @@ class TestExcutors : public ::testing::Test void SetUp() { - node = std::make_shared("my_node"); + node = std::make_shared("my_node"); } void TearDown() @@ -46,7 +46,7 @@ class TestExcutors : public ::testing::Test node.reset(); } - rclcpp::node::Node::SharedPtr node; + rclcpp::Node::SharedPtr node; }; // Make sure that executors detach from nodes when destructing diff --git a/rclcpp/test/test_externally_defined_services.cpp b/rclcpp/test/test_externally_defined_services.cpp index 3c3aec94f9..1045c8025d 100644 --- a/rclcpp/test/test_externally_defined_services.cpp +++ b/rclcpp/test/test_externally_defined_services.cpp @@ -43,7 +43,7 @@ callback( {} TEST_F(TestExternallyDefinedServices, default_behavior) { - auto node_handle = rclcpp::node::Node::make_shared("base_node"); + auto node_handle = rclcpp::Node::make_shared("base_node"); try { auto srv = node_handle->create_service("test", @@ -57,17 +57,17 @@ TEST_F(TestExternallyDefinedServices, default_behavior) { TEST_F(TestExternallyDefinedServices, extern_defined_uninitialized) { - auto node_handle = rclcpp::node::Node::make_shared("base_node"); + auto node_handle = rclcpp::Node::make_shared("base_node"); // mock for externally defined service rcl_service_t service_handle = rcl_get_zero_initialized_service(); - rclcpp::any_service_callback::AnyServiceCallback cb; + rclcpp::AnyServiceCallback cb; // don't initialize the service // expect fail try { - rclcpp::service::Service( + rclcpp::Service( node_handle->get_node_base_interface()->get_shared_rcl_node_handle(), &service_handle, cb); } catch (const std::runtime_error &) { @@ -79,7 +79,7 @@ TEST_F(TestExternallyDefinedServices, extern_defined_uninitialized) { } TEST_F(TestExternallyDefinedServices, extern_defined_initialized) { - auto node_handle = rclcpp::node::Node::make_shared("base_node"); + auto node_handle = rclcpp::Node::make_shared("base_node"); // mock for externally defined service rcl_service_t service_handle = rcl_get_zero_initialized_service(); @@ -95,10 +95,10 @@ TEST_F(TestExternallyDefinedServices, extern_defined_initialized) { return; } - rclcpp::any_service_callback::AnyServiceCallback cb; + rclcpp::AnyServiceCallback cb; try { - rclcpp::service::Service( + rclcpp::Service( node_handle->get_node_base_interface()->get_shared_rcl_node_handle(), &service_handle, cb); } catch (const std::runtime_error &) { @@ -110,7 +110,7 @@ TEST_F(TestExternallyDefinedServices, extern_defined_initialized) { } TEST_F(TestExternallyDefinedServices, extern_defined_destructor) { - auto node_handle = rclcpp::node::Node::make_shared("base_node"); + auto node_handle = rclcpp::Node::make_shared("base_node"); // mock for externally defined service rcl_service_t service_handle = rcl_get_zero_initialized_service(); @@ -125,11 +125,11 @@ TEST_F(TestExternallyDefinedServices, extern_defined_destructor) { FAIL(); return; } - rclcpp::any_service_callback::AnyServiceCallback cb; + rclcpp::AnyServiceCallback cb; { // Call constructor - rclcpp::service::Service srv_cpp( + rclcpp::Service srv_cpp( node_handle->get_node_base_interface()->get_shared_rcl_node_handle(), &service_handle, cb); // Call destructor diff --git a/rclcpp/test/test_find_weak_nodes.cpp b/rclcpp/test/test_find_weak_nodes.cpp index 13126718cc..4d9ede7a30 100644 --- a/rclcpp/test/test_find_weak_nodes.cpp +++ b/rclcpp/test/test_find_weak_nodes.cpp @@ -34,8 +34,8 @@ TEST_F(TestFindWeakNodes, allocator_strategy_with_weak_nodes) { // A vector of weak pointers to nodes auto memory_strategy = std::make_shared< rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy<>>(); - auto existing_node = rclcpp::node::Node::make_shared("existing_node"); - auto dead_node = rclcpp::node::Node::make_shared("dead_node"); + auto existing_node = rclcpp::Node::make_shared("existing_node"); + auto dead_node = rclcpp::Node::make_shared("dead_node"); rclcpp::memory_strategy::MemoryStrategy::WeakNodeVector weak_nodes; weak_nodes.push_back(existing_node->get_node_base_interface()); weak_nodes.push_back(dead_node->get_node_base_interface()); @@ -59,8 +59,8 @@ TEST_F(TestFindWeakNodes, allocator_strategy_no_weak_nodes) { // A vector of weak pointers to nodes, all valid auto memory_strategy = std::make_shared< rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy<>>(); - auto existing_node1 = rclcpp::node::Node::make_shared("existing_node1"); - auto existing_node2 = rclcpp::node::Node::make_shared("existing_node2"); + auto existing_node1 = rclcpp::Node::make_shared("existing_node1"); + auto existing_node2 = rclcpp::Node::make_shared("existing_node2"); rclcpp::memory_strategy::MemoryStrategy::WeakNodeVector weak_nodes; weak_nodes.push_back(existing_node1->get_node_base_interface()); weak_nodes.push_back(existing_node2->get_node_base_interface()); diff --git a/rclcpp/test/test_intra_process_manager.cpp b/rclcpp/test/test_intra_process_manager.cpp index df9b7e1e00..5128ece832 100644 --- a/rclcpp/test/test_intra_process_manager.cpp +++ b/rclcpp/test/test_intra_process_manager.cpp @@ -23,8 +23,6 @@ // Mock up publisher and subscription base to avoid needing an rmw impl. namespace rclcpp { -namespace publisher -{ namespace mock { @@ -80,13 +78,10 @@ class Publisher : public PublisherBase }; } // namespace mock -} // namespace publisher } // namespace rclcpp namespace rclcpp { -namespace subscription -{ namespace mock { @@ -112,7 +107,6 @@ class SubscriptionBase }; } // namespace mock -} // namespace subscription } // namespace rclcpp // Prevent rclcpp/publisher.hpp and rclcpp/subscription.hpp from being imported. @@ -146,18 +140,18 @@ TEST(TestIntraProcessManager, nominal) { rclcpp::intra_process_manager::IntraProcessManager ipm; auto p1 = std::make_shared< - rclcpp::publisher::mock::Publisher + rclcpp::mock::Publisher >(); p1->mock_topic_name = "nominal1"; p1->mock_queue_size = 2; auto p2 = std::make_shared< - rclcpp::publisher::mock::Publisher + rclcpp::mock::Publisher >(); p2->mock_topic_name = "nominal2"; p2->mock_queue_size = 10; - auto s1 = std::make_shared(); + auto s1 = std::make_shared(); s1->mock_topic_name = "nominal1"; s1->mock_queue_size = 10; @@ -237,12 +231,12 @@ TEST(TestIntraProcessManager, remove_publisher_before_trying_to_take) { rclcpp::intra_process_manager::IntraProcessManager ipm; auto p1 = std::make_shared< - rclcpp::publisher::mock::Publisher + rclcpp::mock::Publisher >(); p1->mock_topic_name = "nominal1"; p1->mock_queue_size = 10; - auto s1 = std::make_shared(); + auto s1 = std::make_shared(); s1->mock_topic_name = "nominal1"; s1->mock_queue_size = 10; @@ -279,20 +273,20 @@ TEST(TestIntraProcessManager, removed_subscription_affects_take) { rclcpp::intra_process_manager::IntraProcessManager ipm; auto p1 = std::make_shared< - rclcpp::publisher::mock::Publisher + rclcpp::mock::Publisher >(); p1->mock_topic_name = "nominal1"; p1->mock_queue_size = 10; - auto s1 = std::make_shared(); + auto s1 = std::make_shared(); s1->mock_topic_name = "nominal1"; s1->mock_queue_size = 10; - auto s2 = std::make_shared(); + auto s2 = std::make_shared(); s2->mock_topic_name = "nominal1"; s2->mock_queue_size = 10; - auto s3 = std::make_shared(); + auto s3 = std::make_shared(); s3->mock_topic_name = "nominal1"; s3->mock_queue_size = 10; @@ -350,20 +344,20 @@ TEST(TestIntraProcessManager, multiple_subscriptions_one_publisher) { rclcpp::intra_process_manager::IntraProcessManager ipm; auto p1 = std::make_shared< - rclcpp::publisher::mock::Publisher + rclcpp::mock::Publisher >(); p1->mock_topic_name = "nominal1"; p1->mock_queue_size = 10; - auto s1 = std::make_shared(); + auto s1 = std::make_shared(); s1->mock_topic_name = "nominal1"; s1->mock_queue_size = 10; - auto s2 = std::make_shared(); + auto s2 = std::make_shared(); s2->mock_topic_name = "nominal1"; s2->mock_queue_size = 10; - auto s3 = std::make_shared(); + auto s3 = std::make_shared(); s3->mock_topic_name = "nominal1"; s3->mock_queue_size = 10; @@ -422,24 +416,24 @@ TEST(TestIntraProcessManager, multiple_publishers_one_subscription) { rclcpp::intra_process_manager::IntraProcessManager ipm; auto p1 = std::make_shared< - rclcpp::publisher::mock::Publisher + rclcpp::mock::Publisher >(); p1->mock_topic_name = "nominal1"; p1->mock_queue_size = 10; auto p2 = std::make_shared< - rclcpp::publisher::mock::Publisher + rclcpp::mock::Publisher >(); p2->mock_topic_name = "nominal1"; p2->mock_queue_size = 10; auto p3 = std::make_shared< - rclcpp::publisher::mock::Publisher + rclcpp::mock::Publisher >(); p3->mock_topic_name = "nominal1"; p3->mock_queue_size = 10; - auto s1 = std::make_shared(); + auto s1 = std::make_shared(); s1->mock_topic_name = "nominal1"; s1->mock_queue_size = 10; @@ -522,32 +516,32 @@ TEST(TestIntraProcessManager, multiple_publishers_multiple_subscription) { rclcpp::intra_process_manager::IntraProcessManager ipm; auto p1 = std::make_shared< - rclcpp::publisher::mock::Publisher + rclcpp::mock::Publisher >(); p1->mock_topic_name = "nominal1"; p1->mock_queue_size = 10; auto p2 = std::make_shared< - rclcpp::publisher::mock::Publisher + rclcpp::mock::Publisher >(); p2->mock_topic_name = "nominal1"; p2->mock_queue_size = 10; auto p3 = std::make_shared< - rclcpp::publisher::mock::Publisher + rclcpp::mock::Publisher >(); p3->mock_topic_name = "nominal1"; p3->mock_queue_size = 10; - auto s1 = std::make_shared(); + auto s1 = std::make_shared(); s1->mock_topic_name = "nominal1"; s1->mock_queue_size = 10; - auto s2 = std::make_shared(); + auto s2 = std::make_shared(); s2->mock_topic_name = "nominal1"; s2->mock_queue_size = 10; - auto s3 = std::make_shared(); + auto s3 = std::make_shared(); s3->mock_topic_name = "nominal1"; s3->mock_queue_size = 10; @@ -689,12 +683,12 @@ TEST(TestIntraProcessManager, ring_buffer_displacement) { rclcpp::intra_process_manager::IntraProcessManager ipm; auto p1 = std::make_shared< - rclcpp::publisher::mock::Publisher + rclcpp::mock::Publisher >(); p1->mock_topic_name = "nominal1"; p1->mock_queue_size = 2; - auto s1 = std::make_shared(); + auto s1 = std::make_shared(); s1->mock_topic_name = "nominal1"; s1->mock_queue_size = 10; @@ -760,7 +754,7 @@ TEST(TestIntraProcessManager, subscription_creation_race_condition) { rclcpp::intra_process_manager::IntraProcessManager ipm; auto p1 = std::make_shared< - rclcpp::publisher::mock::Publisher + rclcpp::mock::Publisher >(); p1->mock_topic_name = "nominal1"; p1->mock_queue_size = 2; @@ -778,7 +772,7 @@ TEST(TestIntraProcessManager, subscription_creation_race_condition) { auto p1_m1_id = ipm.store_intra_process_message(p1_id, unique_msg); ASSERT_EQ(nullptr, unique_msg); - auto s1 = std::make_shared(); + auto s1 = std::make_shared(); s1->mock_topic_name = "nominal1"; s1->mock_queue_size = 10; @@ -799,7 +793,7 @@ TEST(TestIntraProcessManager, subscription_creation_race_condition) { TEST(TestIntraProcessManager, publisher_out_of_scope_take) { rclcpp::intra_process_manager::IntraProcessManager ipm; - auto s1 = std::make_shared(); + auto s1 = std::make_shared(); s1->mock_topic_name = "nominal1"; s1->mock_queue_size = 10; @@ -809,7 +803,7 @@ TEST(TestIntraProcessManager, publisher_out_of_scope_take) { uint64_t p1_m1_id; { auto p1 = std::make_shared< - rclcpp::publisher::mock::Publisher + rclcpp::mock::Publisher >(); p1->mock_topic_name = "nominal1"; p1->mock_queue_size = 2; @@ -848,7 +842,7 @@ TEST(TestIntraProcessManager, publisher_out_of_scope_store) { uint64_t p1_id; { auto p1 = std::make_shared< - rclcpp::publisher::mock::Publisher + rclcpp::mock::Publisher >(); p1->mock_topic_name = "nominal1"; p1->mock_queue_size = 2; diff --git a/rclcpp/test/test_node.cpp b/rclcpp/test/test_node.cpp index b1781a5bf9..8ee9aa77f6 100644 --- a/rclcpp/test/test_node.cpp +++ b/rclcpp/test/test_node.cpp @@ -35,40 +35,40 @@ class TestNode : public ::testing::Test */ TEST_F(TestNode, construction_and_destruction) { { - auto node = std::make_shared("my_node", "/ns"); + auto node = std::make_shared("my_node", "/ns"); } { ASSERT_THROW({ - auto node = std::make_shared("invalid_node?", "/ns"); + auto node = std::make_shared("invalid_node?", "/ns"); }, rclcpp::exceptions::InvalidNodeNameError); } { ASSERT_THROW({ - auto node = std::make_shared("my_node", "/invalid_ns?"); + auto node = std::make_shared("my_node", "/invalid_ns?"); }, rclcpp::exceptions::InvalidNamespaceError); } } TEST_F(TestNode, get_name_and_namespace) { { - auto node = std::make_shared("my_node", "/ns"); + auto node = std::make_shared("my_node", "/ns"); EXPECT_STREQ("my_node", node->get_name()); EXPECT_STREQ("/ns", node->get_namespace()); } { - auto node = std::make_shared("my_node", "ns"); + auto node = std::make_shared("my_node", "ns"); EXPECT_STREQ("my_node", node->get_name()); EXPECT_STREQ("/ns", node->get_namespace()); } { - auto node = std::make_shared("my_node", "/my/ns"); + auto node = std::make_shared("my_node", "/my/ns"); EXPECT_STREQ("my_node", node->get_name()); EXPECT_STREQ("/my/ns", node->get_namespace()); } { - auto node = std::make_shared("my_node", "my/ns"); + auto node = std::make_shared("my_node", "my/ns"); EXPECT_STREQ("my_node", node->get_name()); EXPECT_STREQ("/my/ns", node->get_namespace()); } @@ -77,24 +77,24 @@ TEST_F(TestNode, get_name_and_namespace) { TEST_F(TestNode, get_logger) { // Currently the namespace is not taken into account with the node logger name { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); EXPECT_STREQ("my_node", node->get_logger().get_name()); } { - auto node = std::make_shared("my_node", "/ns"); + auto node = std::make_shared("my_node", "/ns"); EXPECT_STREQ("my_node", node->get_logger().get_name()); } } TEST_F(TestNode, get_clock) { - auto node = std::make_shared("my_node", "/ns"); + auto node = std::make_shared("my_node", "/ns"); auto ros_clock = node->get_clock(); EXPECT_TRUE(ros_clock != nullptr); EXPECT_EQ(ros_clock->get_clock_type(), RCL_ROS_TIME); } TEST_F(TestNode, now) { - auto node = std::make_shared("my_node", "/ns"); + auto node = std::make_shared("my_node", "/ns"); auto clock = node->get_clock(); auto now_builtin = node->now().nanoseconds(); auto now_external = clock->now().nanoseconds(); diff --git a/rclcpp/test/test_publisher.cpp b/rclcpp/test/test_publisher.cpp index e7cb7f7cef..d60be7b062 100644 --- a/rclcpp/test/test_publisher.cpp +++ b/rclcpp/test/test_publisher.cpp @@ -32,7 +32,7 @@ class TestPublisher : public ::testing::Test void SetUp() { - node = std::make_shared("my_node", "/ns"); + node = std::make_shared("my_node", "/ns"); } void TearDown() @@ -40,7 +40,7 @@ class TestPublisher : public ::testing::Test node.reset(); } - rclcpp::node::Node::SharedPtr node; + rclcpp::Node::SharedPtr node; }; /* diff --git a/rclcpp/test/test_rate.cpp b/rclcpp/test/test_rate.cpp index b6e9306c2f..a4c1c4386a 100644 --- a/rclcpp/test/test_rate.cpp +++ b/rclcpp/test/test_rate.cpp @@ -28,7 +28,7 @@ TEST(TestRate, rate_basics) { double overrun_ratio = 1.5; auto start = std::chrono::system_clock::now(); - rclcpp::rate::Rate r(period); + rclcpp::Rate r(period); ASSERT_FALSE(r.is_steady()); ASSERT_TRUE(r.sleep()); auto one = std::chrono::system_clock::now(); @@ -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(); @@ -67,7 +67,7 @@ TEST(TestRate, wall_rate_basics) { double overrun_ratio = 1.5; auto start = std::chrono::steady_clock::now(); - rclcpp::rate::WallRate r(period); + rclcpp::WallRate r(period); ASSERT_TRUE(r.is_steady()); ASSERT_TRUE(r.sleep()); auto one = std::chrono::steady_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(); diff --git a/rclcpp/test/test_service.cpp b/rclcpp/test/test_service.cpp index 02752ba3a3..4531d2b388 100644 --- a/rclcpp/test/test_service.cpp +++ b/rclcpp/test/test_service.cpp @@ -32,7 +32,7 @@ class TestService : public ::testing::Test void SetUp() { - node = std::make_shared("my_node", "/ns"); + node = std::make_shared("my_node", "/ns"); } void TearDown() @@ -40,7 +40,7 @@ class TestService : public ::testing::Test node.reset(); } - rclcpp::node::Node::SharedPtr node; + rclcpp::Node::SharedPtr node; }; /* diff --git a/rclcpp/test/test_subscription.cpp b/rclcpp/test/test_subscription.cpp index 44f9c991c2..e3be4c70ac 100644 --- a/rclcpp/test/test_subscription.cpp +++ b/rclcpp/test/test_subscription.cpp @@ -32,7 +32,7 @@ class TestSubscription : public ::testing::Test void SetUp() { - node = std::make_shared("my_node", "/ns"); + node = std::make_shared("my_node", "/ns"); } void TearDown() @@ -40,7 +40,7 @@ class TestSubscription : public ::testing::Test node.reset(); } - rclcpp::node::Node::SharedPtr node; + rclcpp::Node::SharedPtr node; }; /* diff --git a/rclcpp/test/test_time_source.cpp b/rclcpp/test/test_time_source.cpp index 00f07b51f5..5443f66bfb 100644 --- a/rclcpp/test/test_time_source.cpp +++ b/rclcpp/test/test_time_source.cpp @@ -39,7 +39,7 @@ class TestTimeSource : public ::testing::Test void SetUp() { - node = std::make_shared("my_node"); + node = std::make_shared("my_node"); } void TearDown() @@ -47,7 +47,7 @@ class TestTimeSource : public ::testing::Test node.reset(); } - rclcpp::node::Node::SharedPtr node; + rclcpp::Node::SharedPtr node; }; @@ -228,7 +228,7 @@ TEST_F(TestTimeSource, callbacks) { } void trigger_clock_changes( - rclcpp::node::Node::SharedPtr node) + rclcpp::Node::SharedPtr node) { auto clock_pub = node->create_publisher("clock", rmw_qos_profile_default); @@ -334,8 +334,8 @@ TEST_F(TestTimeSource, parameter_activation) { ts.attachClock(ros_clock); EXPECT_FALSE(ros_clock->ros_time_is_active()); - auto parameter_service = std::make_shared(node); - auto parameters_client = std::make_shared(node); + auto parameter_service = std::make_shared(node); + auto parameters_client = std::make_shared(node); using namespace std::chrono_literals; EXPECT_TRUE(parameters_client->wait_for_service(2s)); diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp index 52c21a094c..12137e5d7b 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp @@ -83,7 +83,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, const std::string & namespace_ = "", bool use_intra_process_comms = false); - /// Create a node based on the node name and a rclcpp::context::Context. + /// Create a node based on the node name and a rclcpp::Context. /** * \param[in] node_name Name of the node. * \param[in] node_name Namespace of the node. @@ -95,7 +95,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, LifecycleNode( const std::string & node_name, const std::string & namespace_, - rclcpp::context::Context::SharedPtr context, + rclcpp::Context::SharedPtr context, bool use_intra_process_comms = false); RCLCPP_LIFECYCLE_PUBLIC @@ -172,7 +172,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, typename MessageT, typename CallbackT, typename Alloc = std::allocator, - typename SubscriptionT = rclcpp::subscription::Subscription> + typename SubscriptionT = rclcpp::Subscription> std::shared_ptr create_subscription( const std::string & topic_name, @@ -202,7 +202,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, typename MessageT, typename CallbackT, typename Alloc = std::allocator, - typename SubscriptionT = rclcpp::subscription::Subscription> + typename SubscriptionT = rclcpp::Subscription> std::shared_ptr create_subscription( const std::string & topic_name, @@ -221,7 +221,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, * \param[in] group Callback group to execute this timer's callback in. */ template - typename rclcpp::timer::WallTimer::SharedPtr + typename rclcpp::WallTimer::SharedPtr create_wall_timer( std::chrono::duration period, CallbackT callback, @@ -229,7 +229,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, /* Create and return a Client. */ template - typename rclcpp::client::Client::SharedPtr + typename rclcpp::Client::SharedPtr create_client( const std::string & service_name, const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, @@ -237,7 +237,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, /* Create and return a Service. */ template - typename rclcpp::service::Service::SharedPtr + typename rclcpp::Service::SharedPtr create_service( const std::string & service_name, CallbackT && callback, @@ -313,7 +313,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, * out of scope. */ RCLCPP_LIFECYCLE_PUBLIC - rclcpp::event::Event::SharedPtr + rclcpp::Event::SharedPtr get_graph_event(); /// Wait for a graph event to occur by waiting on an Event to become set. @@ -326,7 +326,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, RCLCPP_LIFECYCLE_PUBLIC void wait_for_graph_change( - rclcpp::event::Event::SharedPtr event, + rclcpp::Event::SharedPtr event, std::chrono::nanoseconds timeout); RCLCPP_LIFECYCLE_PUBLIC @@ -480,7 +480,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, RCLCPP_LIFECYCLE_PUBLIC void - add_timer_handle(std::shared_ptr timer); + add_timer_handle(std::shared_ptr timer); private: RCLCPP_DISABLE_COPY(LifecycleNode) diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp index e038fe8fc2..37a55afd9d 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp @@ -90,7 +90,7 @@ LifecycleNode::create_subscription( return rclcpp::create_subscription< MessageT, CallbackT, Alloc, - rclcpp::subscription::Subscription>( + rclcpp::Subscription>( this->node_topics_.get(), topic_name, std::forward(callback), @@ -131,13 +131,13 @@ LifecycleNode::create_subscription( } template -typename rclcpp::timer::WallTimer::SharedPtr +typename rclcpp::WallTimer::SharedPtr LifecycleNode::create_wall_timer( std::chrono::duration period, CallbackT callback, rclcpp::callback_group::CallbackGroup::SharedPtr group) { - auto timer = rclcpp::timer::WallTimer::make_shared( + auto timer = rclcpp::WallTimer::make_shared( std::chrono::duration_cast(period), std::move(callback)); node_timers_->add_timer(timer, group); @@ -145,7 +145,7 @@ LifecycleNode::create_wall_timer( } template -typename rclcpp::client::Client::SharedPtr +typename rclcpp::Client::SharedPtr LifecycleNode::create_client( const std::string & service_name, const rmw_qos_profile_t & qos_profile, @@ -154,8 +154,8 @@ LifecycleNode::create_client( rcl_client_options_t options = rcl_client_get_default_options(); options.qos = qos_profile; - using rclcpp::client::Client; - using rclcpp::client::ClientBase; + using rclcpp::Client; + using rclcpp::ClientBase; auto cli = Client::make_shared( node_base_.get(), @@ -169,23 +169,23 @@ LifecycleNode::create_client( } template -typename rclcpp::service::Service::SharedPtr +typename rclcpp::Service::SharedPtr LifecycleNode::create_service( const std::string & service_name, CallbackT && callback, const rmw_qos_profile_t & qos_profile, rclcpp::callback_group::CallbackGroup::SharedPtr group) { - rclcpp::service::AnyServiceCallback any_service_callback; + rclcpp::AnyServiceCallback any_service_callback; any_service_callback.set(std::forward(callback)); rcl_service_options_t service_options = rcl_service_get_default_options(); service_options.qos = qos_profile; - auto serv = rclcpp::service::Service::make_shared( + auto serv = rclcpp::Service::make_shared( node_base_->get_shared_rcl_node_handle(), service_name, any_service_callback, service_options); - auto serv_base_ptr = std::dynamic_pointer_cast(serv); + auto serv_base_ptr = std::dynamic_pointer_cast(serv); node_services_->add_service(serv_base_ptr, group); return serv; } diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_publisher.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_publisher.hpp index 19e4195989..a9e8df87cb 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_publisher.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_publisher.hpp @@ -45,7 +45,7 @@ class LifecyclePublisherInterface */ template> class LifecyclePublisher : public LifecyclePublisherInterface, - public rclcpp::publisher::Publisher + public rclcpp::Publisher { public: using MessageAllocTraits = rclcpp::allocator::AllocRebind; @@ -58,7 +58,7 @@ class LifecyclePublisher : public LifecyclePublisherInterface, const std::string & topic, const rcl_publisher_options_t & publisher_options, std::shared_ptr allocator) - : rclcpp::publisher::Publisher( + : rclcpp::Publisher( node_base, topic, publisher_options, allocator), enabled_(false) {} @@ -77,7 +77,7 @@ class LifecyclePublisher : public LifecyclePublisherInterface, if (!enabled_) { return; } - rclcpp::publisher::Publisher::publish(msg); + rclcpp::Publisher::publish(msg); } /// LifecyclePublisher publish function @@ -92,7 +92,7 @@ class LifecyclePublisher : public LifecyclePublisherInterface, if (!enabled_) { return; } - rclcpp::publisher::Publisher::publish(msg); + rclcpp::Publisher::publish(msg); } /// LifecyclePublisher publish function @@ -107,7 +107,7 @@ class LifecyclePublisher : public LifecyclePublisherInterface, if (!enabled_) { return; } - rclcpp::publisher::Publisher::publish(msg); + rclcpp::Publisher::publish(msg); } /// LifecyclePublisher publish function @@ -122,7 +122,7 @@ class LifecyclePublisher : public LifecyclePublisherInterface, if (!enabled_) { return; } - rclcpp::publisher::Publisher::publish(msg); + rclcpp::Publisher::publish(msg); } virtual void @@ -146,7 +146,7 @@ class LifecyclePublisher : public LifecyclePublisherInterface, if (!enabled_) { return; } - rclcpp::publisher::Publisher::publish(msg); + rclcpp::Publisher::publish(msg); } virtual void diff --git a/rclcpp_lifecycle/src/lifecycle_node.cpp b/rclcpp_lifecycle/src/lifecycle_node.cpp index 0eae7008d9..c03175ff93 100644 --- a/rclcpp_lifecycle/src/lifecycle_node.cpp +++ b/rclcpp_lifecycle/src/lifecycle_node.cpp @@ -55,7 +55,7 @@ LifecycleNode::LifecycleNode( LifecycleNode::LifecycleNode( const std::string & node_name, const std::string & namespace_, - rclcpp::context::Context::SharedPtr context, + rclcpp::Context::SharedPtr context, bool use_intra_process_comms) : node_base_(new rclcpp::node_interfaces::NodeBase(node_name, namespace_, context)), node_graph_(new rclcpp::node_interfaces::NodeGraph(node_base_.get())), @@ -209,7 +209,7 @@ LifecycleNode::get_callback_groups() const return node_base_->get_callback_groups(); } -rclcpp::event::Event::SharedPtr +rclcpp::Event::SharedPtr LifecycleNode::get_graph_event() { return node_graph_->get_graph_event(); @@ -217,7 +217,7 @@ LifecycleNode::get_graph_event() void LifecycleNode::wait_for_graph_change( - rclcpp::event::Event::SharedPtr event, + rclcpp::Event::SharedPtr event, std::chrono::nanoseconds timeout) { node_graph_->wait_for_graph_change(event, timeout); @@ -449,7 +449,7 @@ LifecycleNode::add_publisher_handle( } void -LifecycleNode::add_timer_handle(std::shared_ptr timer) +LifecycleNode::add_timer_handle(std::shared_ptr timer) { impl_->add_timer_handle(timer); } diff --git a/rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp b/rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp index f511a96e5e..3d1a9802b4 100644 --- a/rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp +++ b/rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp @@ -104,61 +104,61 @@ class LifecycleNode::LifecycleNodeInterfaceImpl { // change_state auto cb = std::bind(&LifecycleNodeInterfaceImpl::on_change_state, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); - rclcpp::any_service_callback::AnyServiceCallback any_cb; + rclcpp::AnyServiceCallback any_cb; any_cb.set(std::move(cb)); - srv_change_state_ = std::make_shared>( + srv_change_state_ = std::make_shared>( node_base_interface_->get_shared_rcl_node_handle(), &state_machine_.com_interface.srv_change_state, any_cb); node_services_interface_->add_service( - std::dynamic_pointer_cast(srv_change_state_), + std::dynamic_pointer_cast(srv_change_state_), nullptr); } { // get_state auto cb = std::bind(&LifecycleNodeInterfaceImpl::on_get_state, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); - rclcpp::any_service_callback::AnyServiceCallback any_cb; + rclcpp::AnyServiceCallback any_cb; any_cb.set(std::move(cb)); - srv_get_state_ = std::make_shared>( + srv_get_state_ = std::make_shared>( node_base_interface_->get_shared_rcl_node_handle(), &state_machine_.com_interface.srv_get_state, any_cb); node_services_interface_->add_service( - std::dynamic_pointer_cast(srv_get_state_), + std::dynamic_pointer_cast(srv_get_state_), nullptr); } { // get_available_states auto cb = std::bind(&LifecycleNodeInterfaceImpl::on_get_available_states, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); - rclcpp::any_service_callback::AnyServiceCallback any_cb; + rclcpp::AnyServiceCallback any_cb; any_cb.set(std::move(cb)); - srv_get_available_states_ = std::make_shared>( + srv_get_available_states_ = std::make_shared>( node_base_interface_->get_shared_rcl_node_handle(), &state_machine_.com_interface.srv_get_available_states, any_cb); node_services_interface_->add_service( - std::dynamic_pointer_cast(srv_get_available_states_), + std::dynamic_pointer_cast(srv_get_available_states_), nullptr); } { // get_available_transitions auto cb = std::bind(&LifecycleNodeInterfaceImpl::on_get_available_transitions, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); - rclcpp::any_service_callback::AnyServiceCallback any_cb; + rclcpp::AnyServiceCallback any_cb; any_cb.set(std::move(cb)); srv_get_available_transitions_ = - std::make_shared>( + std::make_shared>( node_base_interface_->get_shared_rcl_node_handle(), &state_machine_.com_interface.srv_get_available_transitions, any_cb); node_services_interface_->add_service( - std::dynamic_pointer_cast(srv_get_available_transitions_), + std::dynamic_pointer_cast(srv_get_available_transitions_), nullptr); } } @@ -391,7 +391,7 @@ class LifecycleNode::LifecycleNodeInterfaceImpl } void - add_timer_handle(std::shared_ptr timer) + add_timer_handle(std::shared_ptr timer) { weak_timers_.push_back(timer); } @@ -404,12 +404,12 @@ class LifecycleNode::LifecycleNodeInterfaceImpl using NodeBasePtr = std::shared_ptr; using NodeServicesPtr = std::shared_ptr; - using ChangeStateSrvPtr = std::shared_ptr>; - using GetStateSrvPtr = std::shared_ptr>; + using ChangeStateSrvPtr = std::shared_ptr>; + using GetStateSrvPtr = std::shared_ptr>; using GetAvailableStatesSrvPtr = - std::shared_ptr>; + std::shared_ptr>; using GetAvailableTransitionsSrvPtr = - std::shared_ptr>; + std::shared_ptr>; NodeBasePtr node_base_interface_; NodeServicesPtr node_services_interface_; @@ -420,7 +420,7 @@ class LifecycleNode::LifecycleNodeInterfaceImpl // to controllable things std::vector> weak_pubs_; - std::vector> weak_timers_; + std::vector> weak_timers_; }; } // namespace rclcpp_lifecycle