diff --git a/rclcpp/include/rclcpp/callback_group.hpp b/rclcpp/include/rclcpp/callback_group.hpp index b4a4d4e9a6..a8225e1664 100644 --- a/rclcpp/include/rclcpp/callback_group.hpp +++ b/rclcpp/include/rclcpp/callback_group.hpp @@ -106,35 +106,35 @@ class CallbackGroup template rclcpp::SubscriptionBase::SharedPtr - find_subscription_ptrs_if(Function func) const + find_subscription_ptrs_if(const Function & func) const { return _find_ptrs_if_impl(func, subscription_ptrs_); } template rclcpp::TimerBase::SharedPtr - find_timer_ptrs_if(Function func) const + find_timer_ptrs_if(const Function & func) const { return _find_ptrs_if_impl(func, timer_ptrs_); } template rclcpp::ServiceBase::SharedPtr - find_service_ptrs_if(Function func) const + find_service_ptrs_if(const Function & func) const { return _find_ptrs_if_impl(func, service_ptrs_); } template rclcpp::ClientBase::SharedPtr - find_client_ptrs_if(Function func) const + find_client_ptrs_if(const Function & func) const { return _find_ptrs_if_impl(func, client_ptrs_); } template rclcpp::Waitable::SharedPtr - find_waitable_ptrs_if(Function func) const + find_waitable_ptrs_if(const Function & func) const { return _find_ptrs_if_impl(func, waitable_ptrs_); } @@ -179,11 +179,11 @@ class CallbackGroup RCLCPP_PUBLIC void collect_all_ptrs( - std::function sub_func, - std::function service_func, - std::function client_func, - std::function timer_func, - std::function waitable_func) const; + const std::function & sub_func, + const std::function & service_func, + const std::function & client_func, + const std::function & timer_func, + const std::function & waitable_func) const; /// Return a reference to the 'associated with executor' atomic boolean. /** @@ -228,31 +228,31 @@ class CallbackGroup RCLCPP_PUBLIC void - add_publisher(const rclcpp::PublisherBase::SharedPtr publisher_ptr); + add_publisher(const rclcpp::PublisherBase::SharedPtr & publisher_ptr); RCLCPP_PUBLIC void - add_subscription(const rclcpp::SubscriptionBase::SharedPtr subscription_ptr); + add_subscription(const rclcpp::SubscriptionBase::SharedPtr & subscription_ptr); RCLCPP_PUBLIC void - add_timer(const rclcpp::TimerBase::SharedPtr timer_ptr); + add_timer(const rclcpp::TimerBase::SharedPtr & timer_ptr); RCLCPP_PUBLIC void - add_service(const rclcpp::ServiceBase::SharedPtr service_ptr); + add_service(const rclcpp::ServiceBase::SharedPtr & service_ptr); RCLCPP_PUBLIC void - add_client(const rclcpp::ClientBase::SharedPtr client_ptr); + add_client(const rclcpp::ClientBase::SharedPtr & client_ptr); RCLCPP_PUBLIC void - add_waitable(const rclcpp::Waitable::SharedPtr waitable_ptr); + add_waitable(const rclcpp::Waitable::SharedPtr & waitable_ptr); RCLCPP_PUBLIC void - remove_waitable(const rclcpp::Waitable::SharedPtr waitable_ptr) noexcept; + remove_waitable(const rclcpp::Waitable::SharedPtr & waitable_ptr) noexcept; CallbackGroupType type_; // Mutex to protect the subsequent vectors of pointers. @@ -274,7 +274,7 @@ class CallbackGroup private: template typename TypeT::SharedPtr _find_ptrs_if_impl( - Function func, const std::vector & vect_ptrs) const + const Function & func, const std::vector & vect_ptrs) const { std::lock_guard lock(mutex_); for (auto & weak_ptr : vect_ptrs) { diff --git a/rclcpp/include/rclcpp/client.hpp b/rclcpp/include/rclcpp/client.hpp index 4e50f8a040..7f4486925b 100644 --- a/rclcpp/include/rclcpp/client.hpp +++ b/rclcpp/include/rclcpp/client.hpp @@ -145,7 +145,7 @@ class ClientBase RCLCPP_PUBLIC ClientBase( rclcpp::node_interfaces::NodeBaseInterface * node_base, - rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph); + const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr & node_graph); RCLCPP_PUBLIC virtual ~ClientBase() = default; @@ -221,7 +221,8 @@ class ClientBase virtual std::shared_ptr create_response() = 0; virtual std::shared_ptr create_request_header() = 0; virtual void handle_response( - std::shared_ptr request_header, std::shared_ptr response) = 0; + const std::shared_ptr & request_header, + const std::shared_ptr & response) = 0; /// Exchange the "in use by wait set" state for this client. /** @@ -296,7 +297,7 @@ class ClientBase * \param[in] callback functor to be called when a new response is received */ void - set_on_new_response_callback(std::function callback) + set_on_new_response_callback(const std::function & callback) { if (!callback) { throw std::invalid_argument( @@ -477,7 +478,7 @@ class Client : public ClientBase */ Client( rclcpp::node_interfaces::NodeBaseInterface * node_base, - rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph, + const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr & node_graph, const std::string & service_name, rcl_client_options_t & client_options) : ClientBase(node_base, node_graph), @@ -556,8 +557,8 @@ class Client : public ClientBase */ void handle_response( - std::shared_ptr request_header, - std::shared_ptr response) override + const std::shared_ptr & request_header, + const std::shared_ptr & response) override { std::optional optional_pending_request = this->get_and_erase_pending_request(request_header->sequence_number); @@ -566,7 +567,7 @@ class Client : public ClientBase } auto & value = *optional_pending_request; auto typed_response = std::static_pointer_cast( - std::move(response)); + response); if (std::holds_alternative(value)) { auto & promise = std::get(value); promise.set_value(std::move(typed_response)); @@ -617,7 +618,7 @@ class Client : public ClientBase * \return a FutureAndRequestId instance. */ FutureAndRequestId - async_send_request(SharedRequest request) + async_send_request(const SharedRequest & request) { Promise promise; auto future = promise.get_future(); @@ -652,7 +653,7 @@ class Client : public ClientBase >::type * = nullptr > SharedFutureAndRequestId - async_send_request(SharedRequest request, CallbackT && cb) + async_send_request(const SharedRequest & request, CallbackT && cb) { Promise promise; auto shared_future = promise.get_future().share(); @@ -683,7 +684,7 @@ class Client : public ClientBase >::type * = nullptr > SharedFutureWithRequestAndRequestId - async_send_request(SharedRequest request, CallbackT && cb) + async_send_request(const SharedRequest & request, CallbackT && cb) { PromiseWithRequest promise; auto shared_future = promise.get_future().share(); @@ -795,7 +796,7 @@ class Client : public ClientBase */ void configure_introspection( - Clock::SharedPtr clock, const QoS & qos_service_event_pub, + const Clock::SharedPtr & clock, const QoS & qos_service_event_pub, rcl_service_introspection_state_t introspection_state) { rcl_publisher_options_t pub_opts = rcl_publisher_get_default_options(); diff --git a/rclcpp/include/rclcpp/clock.hpp b/rclcpp/include/rclcpp/clock.hpp index 412d682e71..0196fe825b 100644 --- a/rclcpp/include/rclcpp/clock.hpp +++ b/rclcpp/include/rclcpp/clock.hpp @@ -118,7 +118,7 @@ class Clock bool sleep_until( Time until, - Context::SharedPtr context = contexts::get_global_default_context()); + const Context::SharedPtr & context = contexts::get_global_default_context()); /** * Sleep for a specified Duration. @@ -142,7 +142,7 @@ class Clock bool sleep_for( Duration rel_time, - Context::SharedPtr context = contexts::get_global_default_context()); + const Context::SharedPtr & context = contexts::get_global_default_context()); /** * Check if the clock is started. @@ -168,7 +168,7 @@ class Clock */ RCLCPP_PUBLIC bool - wait_until_started(Context::SharedPtr context = contexts::get_global_default_context()); + wait_until_started(const Context::SharedPtr & context = contexts::get_global_default_context()); /** * Wait for clock to start, with timeout. @@ -186,7 +186,7 @@ class Clock bool wait_until_started( const rclcpp::Duration & timeout, - Context::SharedPtr context = contexts::get_global_default_context(), + const Context::SharedPtr & context = contexts::get_global_default_context(), const rclcpp::Duration & wait_tick_ns = rclcpp::Duration(0, static_cast(1e7))); /** @@ -238,8 +238,8 @@ class Clock RCLCPP_PUBLIC JumpHandler::SharedPtr create_jump_callback( - JumpHandler::pre_callback_t pre_callback, - JumpHandler::post_callback_t post_callback, + const JumpHandler::pre_callback_t & pre_callback, + const JumpHandler::post_callback_t & post_callback, const rcl_jump_threshold_t & threshold); private: @@ -327,7 +327,7 @@ class ClockConditionalVariable RCLCPP_PUBLIC ClockConditionalVariable( const rclcpp::Clock::SharedPtr & clock, - rclcpp::Context::SharedPtr context = rclcpp::contexts::get_global_default_context()); + const rclcpp::Context::SharedPtr & context = rclcpp::contexts::get_global_default_context()); RCLCPP_PUBLIC ~ClockConditionalVariable(); diff --git a/rclcpp/include/rclcpp/context.hpp b/rclcpp/include/rclcpp/context.hpp index ff78f36bd1..313826cd64 100644 --- a/rclcpp/include/rclcpp/context.hpp +++ b/rclcpp/include/rclcpp/context.hpp @@ -229,7 +229,7 @@ class Context : public std::enable_shared_from_this RCLCPP_PUBLIC virtual OnShutdownCallback - on_shutdown(OnShutdownCallback callback); + on_shutdown(const OnShutdownCallback & callback); /// Add a on_shutdown callback to be called when shutdown is called for this context. /** @@ -253,7 +253,7 @@ class Context : public std::enable_shared_from_this RCLCPP_PUBLIC virtual OnShutdownCallbackHandle - add_on_shutdown_callback(OnShutdownCallback callback); + add_on_shutdown_callback(const OnShutdownCallback & callback); /// Remove an registered on_shutdown callbacks. /** @@ -280,7 +280,7 @@ class Context : public std::enable_shared_from_this RCLCPP_PUBLIC virtual PreShutdownCallbackHandle - add_pre_shutdown_callback(PreShutdownCallback callback); + add_pre_shutdown_callback(const PreShutdownCallback & callback); /// Remove an registered pre_shutdown callback. /** diff --git a/rclcpp/include/rclcpp/create_generic_client.hpp b/rclcpp/include/rclcpp/create_generic_client.hpp index eade7bd9f1..acfb9f763b 100644 --- a/rclcpp/include/rclcpp/create_generic_client.hpp +++ b/rclcpp/include/rclcpp/create_generic_client.hpp @@ -46,13 +46,13 @@ namespace rclcpp RCLCPP_PUBLIC rclcpp::GenericClient::SharedPtr create_generic_client( - std::shared_ptr node_base, - std::shared_ptr node_graph, - std::shared_ptr node_services, + const std::shared_ptr & node_base, + const std::shared_ptr & node_graph, + const std::shared_ptr & node_services, const std::string & service_name, const std::string & service_type, const rclcpp::QoS & qos = rclcpp::ServicesQoS(), - rclcpp::CallbackGroup::SharedPtr group = nullptr); + const rclcpp::CallbackGroup::SharedPtr & group = rclcpp::CallbackGroup::SharedPtr()); /// Create a generic service client with a name of given type. /** diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index fcc48da055..87e0f3efdd 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -102,8 +102,8 @@ class Executor RCLCPP_PUBLIC virtual void add_callback_group( - rclcpp::CallbackGroup::SharedPtr group_ptr, - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, + const rclcpp::CallbackGroup::SharedPtr & group_ptr, + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr, bool notify = true); /// Get callback groups that belong to executor. @@ -173,7 +173,7 @@ class Executor RCLCPP_PUBLIC virtual void remove_callback_group( - rclcpp::CallbackGroup::SharedPtr group_ptr, + const rclcpp::CallbackGroup::SharedPtr & group_ptr, bool notify = true); /// Add a node to the executor. @@ -197,7 +197,9 @@ class Executor */ RCLCPP_PUBLIC virtual void - add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true); + add_node( + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr, + bool notify = true); /// Convenience function which takes Node and forwards NodeBaseInterface. /** @@ -205,7 +207,7 @@ class Executor */ RCLCPP_PUBLIC virtual void - add_node(std::shared_ptr node_ptr, bool notify = true); + add_node(const std::shared_ptr & node_ptr, bool notify = true); /// Remove a node from the executor. /** @@ -225,7 +227,9 @@ class Executor */ RCLCPP_PUBLIC virtual void - remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true); + remove_node( + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr, + bool notify = true); /// Convenience function which takes Node and forwards NodeBaseInterface. /** @@ -233,7 +237,7 @@ class Executor */ RCLCPP_PUBLIC virtual void - remove_node(std::shared_ptr node_ptr, bool notify = true); + remove_node(const std::shared_ptr & node_ptr, bool notify = true); /// Add a node to executor, execute the next available unit of work, and remove the node. /** @@ -245,7 +249,7 @@ class Executor template void spin_node_once( - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node, std::chrono::duration timeout = std::chrono::duration(-1)) { return spin_node_once_nanoseconds( @@ -258,7 +262,7 @@ class Executor template void spin_node_once( - std::shared_ptr node, + const std::shared_ptr & node, std::chrono::duration timeout = std::chrono::duration(-1)) { return spin_node_once_nanoseconds( @@ -273,12 +277,12 @@ class Executor */ RCLCPP_PUBLIC virtual void - spin_node_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node); + spin_node_some(const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node); /// Convenience function which takes Node and forwards NodeBaseInterface. RCLCPP_PUBLIC virtual void - spin_node_some(std::shared_ptr node); + spin_node_some(const std::shared_ptr & node); /// Collect work once and execute all available work, optionally within a max duration. /** @@ -321,13 +325,13 @@ class Executor RCLCPP_PUBLIC virtual void spin_node_all( - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node, std::chrono::nanoseconds max_duration); /// Convenience function which takes Node and forwards NodeBaseInterface. RCLCPP_PUBLIC virtual void - spin_node_all(std::shared_ptr node, std::chrono::nanoseconds max_duration); + spin_node_all(const std::shared_ptr & node, std::chrono::nanoseconds max_duration); /// Collect and execute work repeatedly within a duration or until no more work is available. /** @@ -427,7 +431,7 @@ class Executor RCLCPP_PUBLIC void spin_node_once_nanoseconds( - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node, std::chrono::nanoseconds timeout); /// Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted. @@ -478,7 +482,7 @@ class Executor RCLCPP_PUBLIC static void execute_subscription( - rclcpp::SubscriptionBase::SharedPtr subscription); + const rclcpp::SubscriptionBase::SharedPtr & subscription); /// Run timer executable. /** @@ -487,7 +491,7 @@ class Executor */ RCLCPP_PUBLIC static void - execute_timer(rclcpp::TimerBase::SharedPtr timer, const std::shared_ptr & data_ptr); + execute_timer(const rclcpp::TimerBase::SharedPtr & timer, const std::shared_ptr & data_ptr); /// Run service server executable. /** @@ -496,7 +500,7 @@ class Executor */ RCLCPP_PUBLIC static void - execute_service(rclcpp::ServiceBase::SharedPtr service); + execute_service(const rclcpp::ServiceBase::SharedPtr & service); /// Run service client executable. /** @@ -505,7 +509,7 @@ class Executor */ RCLCPP_PUBLIC static void - execute_client(rclcpp::ClientBase::SharedPtr client); + execute_client(const rclcpp::ClientBase::SharedPtr & client); /// Gather all of the waitable entities from associated nodes and callback groups. RCLCPP_PUBLIC diff --git a/rclcpp/include/rclcpp/executors.hpp b/rclcpp/include/rclcpp/executors.hpp index 3466b90b3d..efba44c2b5 100644 --- a/rclcpp/include/rclcpp/executors.hpp +++ b/rclcpp/include/rclcpp/executors.hpp @@ -47,7 +47,7 @@ namespace rclcpp RCLCPP_PUBLIC void spin_all( - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr, std::chrono::nanoseconds max_duration); /** @@ -68,7 +68,7 @@ spin_all( [[deprecated("use SingleThreadedExecutor::spin_all instead")]] RCLCPP_PUBLIC void -spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration); +spin_all(const rclcpp::Node::SharedPtr & node_ptr, std::chrono::nanoseconds max_duration); /** * @brief Create a default single-threaded executor and execute any immediately available work. @@ -87,7 +87,7 @@ spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration [[deprecated("use SingleThreadedExecutor::spin_some instead")]] RCLCPP_PUBLIC void -spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr); +spin_some(const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr); /** * @brief Create a default single-threaded executor and execute any immediately available work. @@ -106,17 +106,17 @@ spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr); [[deprecated("use SingleThreadedExecutor::spin_some instead")]] RCLCPP_PUBLIC void -spin_some(rclcpp::Node::SharedPtr node_ptr); +spin_some(const 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. */ RCLCPP_PUBLIC void -spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr); +spin(const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr); RCLCPP_PUBLIC void -spin(rclcpp::Node::SharedPtr node_ptr); +spin(const rclcpp::Node::SharedPtr & node_ptr); namespace executors { @@ -140,7 +140,7 @@ template timeout = std::chrono::duration(-1)) { @@ -157,7 +157,7 @@ template node_ptr, + const std::shared_ptr & node_ptr, const FutureT & future, std::chrono::duration timeout = std::chrono::duration(-1)) { @@ -173,7 +173,7 @@ spin_node_until_future_complete( template rclcpp::FutureReturnCode spin_until_future_complete( - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr, const FutureT & future, std::chrono::duration timeout = std::chrono::duration(-1)) { @@ -187,7 +187,7 @@ template rclcpp::FutureReturnCode spin_until_future_complete( - std::shared_ptr node_ptr, + const std::shared_ptr & node_ptr, const FutureT & future, std::chrono::duration timeout = std::chrono::duration(-1)) { diff --git a/rclcpp/include/rclcpp/executors/executor_entities_collector.hpp b/rclcpp/include/rclcpp/executors/executor_entities_collector.hpp index ad9bc84fad..3421c22b18 100644 --- a/rclcpp/include/rclcpp/executors/executor_entities_collector.hpp +++ b/rclcpp/include/rclcpp/executors/executor_entities_collector.hpp @@ -82,7 +82,7 @@ class ExecutorEntitiesCollector */ RCLCPP_PUBLIC void - add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr); + add_node(const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr); /// Remove a node from the entity collector /** @@ -92,7 +92,7 @@ class ExecutorEntitiesCollector */ RCLCPP_PUBLIC void - remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr); + remove_node(const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr); /// Add a callback group to the entity collector /** @@ -101,7 +101,7 @@ class ExecutorEntitiesCollector */ RCLCPP_PUBLIC void - add_callback_group(rclcpp::CallbackGroup::SharedPtr group_ptr); + add_callback_group(const rclcpp::CallbackGroup::SharedPtr & group_ptr); /// Remove a callback group from the entity collector /** @@ -111,7 +111,7 @@ class ExecutorEntitiesCollector */ RCLCPP_PUBLIC void - remove_callback_group(rclcpp::CallbackGroup::SharedPtr group_ptr); + remove_callback_group(const rclcpp::CallbackGroup::SharedPtr & group_ptr); /// Get all callback groups known to this entity collector /** @@ -211,7 +211,7 @@ class ExecutorEntitiesCollector RCLCPP_PUBLIC void add_callback_group_to_collection( - rclcpp::CallbackGroup::SharedPtr group_ptr, + const rclcpp::CallbackGroup::SharedPtr & group_ptr, CallbackGroupCollection & collection) RCPPUTILS_TSA_REQUIRES(mutex_); /// Iterate over queued added/remove nodes and callback_groups diff --git a/rclcpp/include/rclcpp/executors/executor_notify_waitable.hpp b/rclcpp/include/rclcpp/executors/executor_notify_waitable.hpp index 41f6de6b72..2c9bb8edbc 100644 --- a/rclcpp/include/rclcpp/executors/executor_notify_waitable.hpp +++ b/rclcpp/include/rclcpp/executors/executor_notify_waitable.hpp @@ -115,7 +115,7 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable */ RCLCPP_PUBLIC void - add_guard_condition(rclcpp::GuardCondition::WeakPtr guard_condition); + add_guard_condition(const rclcpp::GuardCondition::WeakPtr & guard_condition); /// Unset any callback registered via set_on_ready_callback. /** @@ -139,7 +139,7 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable */ RCLCPP_PUBLIC void - remove_guard_condition(rclcpp::GuardCondition::WeakPtr weak_guard_condition); + remove_guard_condition(const rclcpp::GuardCondition::WeakPtr & weak_guard_condition); /// Get the number of ready guard_conditions /** diff --git a/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp b/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp index a403c20c8b..84b01cebd9 100644 --- a/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp +++ b/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp @@ -118,7 +118,8 @@ class IntraProcessManager typename Alloc = std::allocator > uint64_t - add_subscription(rclcpp::experimental::SubscriptionIntraProcessBase::SharedPtr subscription) + add_subscription( + const rclcpp::experimental::SubscriptionIntraProcessBase::SharedPtr & subscription) { std::unique_lock lock(mutex_); @@ -175,8 +176,8 @@ class IntraProcessManager RCLCPP_PUBLIC uint64_t add_publisher( - rclcpp::PublisherBase::SharedPtr publisher, - rclcpp::experimental::buffers::IntraProcessBufferBase::SharedPtr buffer = + const rclcpp::PublisherBase::SharedPtr & publisher, + const rclcpp::experimental::buffers::IntraProcessBufferBase::SharedPtr & buffer = rclcpp::experimental::buffers::IntraProcessBufferBase::SharedPtr()); /// Unregister a publisher using the publisher's unique id. @@ -410,8 +411,8 @@ class IntraProcessManager RCLCPP_PUBLIC bool can_communicate( - rclcpp::PublisherBase::SharedPtr pub, - rclcpp::experimental::SubscriptionIntraProcessBase::SharedPtr sub) const; + const rclcpp::PublisherBase::SharedPtr & pub, + const rclcpp::experimental::SubscriptionIntraProcessBase::SharedPtr & sub) const; template< typename ROSMessageType, diff --git a/rclcpp/include/rclcpp/experimental/timers_manager.hpp b/rclcpp/include/rclcpp/experimental/timers_manager.hpp index af3337bfd6..998e56a31f 100644 --- a/rclcpp/include/rclcpp/experimental/timers_manager.hpp +++ b/rclcpp/include/rclcpp/experimental/timers_manager.hpp @@ -103,7 +103,7 @@ class TimersManager * @throws std::invalid_argument if timer is a nullptr. */ RCLCPP_PUBLIC - void add_timer(rclcpp::TimerBase::SharedPtr timer); + void add_timer(const rclcpp::TimerBase::SharedPtr & timer); /** * @brief Remove a single timer from the object storage. @@ -113,7 +113,7 @@ class TimersManager * @param timer the timer to remove. */ RCLCPP_PUBLIC - void remove_timer(rclcpp::TimerBase::SharedPtr timer); + void remove_timer(const rclcpp::TimerBase::SharedPtr & timer); /** * @brief Remove all the timers stored in the object. diff --git a/rclcpp/include/rclcpp/generic_client.hpp b/rclcpp/include/rclcpp/generic_client.hpp index 1b853e0b6e..89d5b4a133 100644 --- a/rclcpp/include/rclcpp/generic_client.hpp +++ b/rclcpp/include/rclcpp/generic_client.hpp @@ -111,8 +111,8 @@ class GenericClient : public ClientBase RCLCPP_PUBLIC void handle_response( - std::shared_ptr request_header, - std::shared_ptr response) override; + const std::shared_ptr & request_header, + const std::shared_ptr & response) override; /// Send a request to the service server. /** @@ -144,7 +144,7 @@ class GenericClient : public ClientBase */ RCLCPP_PUBLIC FutureAndRequestId - async_send_request(const Request request); + async_send_request(const Request & request); /// Send a request to the service server and schedule a callback in the executor. /** @@ -172,7 +172,7 @@ class GenericClient : public ClientBase >::type * = nullptr > SharedFutureAndRequestId - async_send_request(const Request request, CallbackT && cb) + async_send_request(const Request & request, CallbackT && cb) { Promise promise; auto shared_future = promise.get_future().share(); @@ -280,7 +280,7 @@ class GenericClient : public ClientBase RCLCPP_PUBLIC int64_t async_send_request_impl( - const Request request, + const Request & request, CallbackInfoVariant value); std::optional diff --git a/rclcpp/include/rclcpp/generic_service.hpp b/rclcpp/include/rclcpp/generic_service.hpp index b4c8d5d9a7..8a4468aa1f 100644 --- a/rclcpp/include/rclcpp/generic_service.hpp +++ b/rclcpp/include/rclcpp/generic_service.hpp @@ -159,10 +159,10 @@ class GenericServiceCallback if (std::holds_alternative(callback_)) { (void)request_header; const auto & cb = std::get(callback_); - cb(std::move(request), std::move(response)); + cb(std::move(request), response); } else if (std::holds_alternative(callback_)) { const auto & cb = std::get(callback_); - cb(request_header, std::move(request), std::move(response)); + cb(request_header, std::move(request), response); } TRACETOOLS_TRACEPOINT(callback_end, static_cast(this)); return response; @@ -245,7 +245,7 @@ class GenericService */ RCLCPP_PUBLIC GenericService( - std::shared_ptr node_handle, + const std::shared_ptr & node_handle, const std::string & service_name, const std::string & service_type, GenericServiceCallback any_callback, @@ -270,7 +270,7 @@ class GenericService */ RCLCPP_PUBLIC bool - take_request(SharedRequest request_out, rmw_request_id_t & request_id_out); + take_request(SharedRequest & request_out, rmw_request_id_t & request_id_out); RCLCPP_PUBLIC std::shared_ptr @@ -287,8 +287,8 @@ class GenericService RCLCPP_PUBLIC void handle_request( - std::shared_ptr request_header, - std::shared_ptr request) override; + const std::shared_ptr & request_header, + const std::shared_ptr & request) override; RCLCPP_PUBLIC void diff --git a/rclcpp/include/rclcpp/guard_condition.hpp b/rclcpp/include/rclcpp/guard_condition.hpp index 594234657c..def708b1b3 100644 --- a/rclcpp/include/rclcpp/guard_condition.hpp +++ b/rclcpp/include/rclcpp/guard_condition.hpp @@ -120,7 +120,7 @@ class GuardCondition */ RCLCPP_PUBLIC void - set_on_trigger_callback(std::function callback); + set_on_trigger_callback(const std::function & callback); protected: rcl_guard_condition_t rcl_guard_condition_; diff --git a/rclcpp/include/rclcpp/node_interfaces/node_type_descriptions.hpp b/rclcpp/include/rclcpp/node_interfaces/node_type_descriptions.hpp index 8aa563bba2..0e2e85748a 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_type_descriptions.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_type_descriptions.hpp @@ -39,10 +39,10 @@ class NodeTypeDescriptions : public NodeTypeDescriptionsInterface RCLCPP_PUBLIC explicit NodeTypeDescriptions( - NodeBaseInterface::SharedPtr node_base, - NodeLoggingInterface::SharedPtr node_logging, - NodeParametersInterface::SharedPtr node_parameters, - NodeServicesInterface::SharedPtr node_services); + const NodeBaseInterface::SharedPtr & node_base, + const NodeLoggingInterface::SharedPtr & node_logging, + const NodeParametersInterface::SharedPtr & node_parameters, + const NodeServicesInterface::SharedPtr & node_services); RCLCPP_PUBLIC virtual diff --git a/rclcpp/include/rclcpp/publisher_base.hpp b/rclcpp/include/rclcpp/publisher_base.hpp index 9a6c398eeb..6327a99443 100644 --- a/rclcpp/include/rclcpp/publisher_base.hpp +++ b/rclcpp/include/rclcpp/publisher_base.hpp @@ -210,7 +210,7 @@ class PublisherBase : public std::enable_shared_from_this void setup_intra_process( uint64_t intra_process_publisher_id, - IntraProcessManagerSharedPtr ipm); + const IntraProcessManagerSharedPtr & ipm); /// Get network flow endpoints /** @@ -300,7 +300,7 @@ class PublisherBase : public std::enable_shared_from_this */ void set_on_new_qos_event_callback( - std::function callback, + const std::function & callback, rcl_publisher_event_type_t event_type) { if (event_handlers_.count(event_type) == 0) { @@ -319,7 +319,7 @@ class PublisherBase : public std::enable_shared_from_this // The on_ready_callback signature has an extra `int` argument used to disambiguate between // possible different entities within a generic waitable. // We hide that detail to users of this method. - std::function new_callback = std::bind(callback, std::placeholders::_1); + std::function new_callback = [callback] (size_t nr, int) {callback(nr);}; event_handlers_[event_type]->set_on_ready_callback(new_callback); } diff --git a/rclcpp/include/rclcpp/rate.hpp b/rclcpp/include/rclcpp/rate.hpp index 281ddf9de3..4f8b3d9f83 100644 --- a/rclcpp/include/rclcpp/rate.hpp +++ b/rclcpp/include/rclcpp/rate.hpp @@ -58,12 +58,12 @@ class Rate : public RateBase RCLCPP_PUBLIC explicit Rate( const double rate, - Clock::SharedPtr clock = std::make_shared(RCL_SYSTEM_TIME)); + const Clock::SharedPtr & clock = std::make_shared(RCL_SYSTEM_TIME)); RCLCPP_PUBLIC explicit Rate( const Duration & period, - Clock::SharedPtr clock = std::make_shared(RCL_SYSTEM_TIME)); + const Clock::SharedPtr & clock = std::make_shared(RCL_SYSTEM_TIME)); RCLCPP_PUBLIC virtual bool diff --git a/rclcpp/include/rclcpp/service.hpp b/rclcpp/include/rclcpp/service.hpp index cbf2370346..df92a6abe9 100644 --- a/rclcpp/include/rclcpp/service.hpp +++ b/rclcpp/include/rclcpp/service.hpp @@ -54,7 +54,7 @@ class ServiceBase RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ServiceBase) RCLCPP_PUBLIC - explicit ServiceBase(std::shared_ptr node_handle); + explicit ServiceBase(const std::shared_ptr & node_handle); RCLCPP_PUBLIC virtual ~ServiceBase() = default; @@ -113,8 +113,8 @@ class ServiceBase virtual void handle_request( - std::shared_ptr request_header, - std::shared_ptr request) = 0; + const std::shared_ptr & request_header, + const std::shared_ptr & request) = 0; /// Exchange the "in use by wait set" state for this service. /** @@ -190,7 +190,7 @@ class ServiceBase * \param[in] callback functor to be called when a new request is received */ void - set_on_new_request_callback(std::function callback) + set_on_new_request_callback(const std::function & callback) { if (!callback) { throw std::invalid_argument( @@ -372,10 +372,10 @@ class Service * \param[in] any_callback User defined callback to call when a client request is received. */ Service( - std::shared_ptr node_handle, - std::shared_ptr service_handle, + const std::shared_ptr & node_handle, + const std::shared_ptr & service_handle, AnyServiceCallback any_callback) - : ServiceBase(node_handle), any_callback_(any_callback), + : ServiceBase(node_handle), any_callback_(std::move(any_callback)), srv_type_support_handle_(rosidl_typesupport_cpp::get_service_type_support_handle()) { // check if service handle was initialized @@ -407,10 +407,10 @@ class Service * \param[in] any_callback User defined callback to call when a client request is received. */ Service( - std::shared_ptr node_handle, + const std::shared_ptr & node_handle, rcl_service_t * service_handle, AnyServiceCallback any_callback) - : ServiceBase(node_handle), any_callback_(any_callback), + : ServiceBase(node_handle), any_callback_(std::move(any_callback)), srv_type_support_handle_(rosidl_typesupport_cpp::get_service_type_support_handle()) { // check if service handle was initialized @@ -471,8 +471,8 @@ class Service void handle_request( - std::shared_ptr request_header, - std::shared_ptr request) override + const std::shared_ptr & request_header, + const std::shared_ptr & request) override { auto typed_request = std::static_pointer_cast(request); auto response = any_callback_.dispatch(this->shared_from_this(), request_header, typed_request); @@ -510,7 +510,7 @@ class Service */ void configure_introspection( - Clock::SharedPtr clock, const QoS & qos_service_event_pub, + const Clock::SharedPtr & clock, const QoS & qos_service_event_pub, rcl_service_introspection_state_t introspection_state) { rcl_publisher_options_t pub_opts = rcl_publisher_get_default_options(); diff --git a/rclcpp/include/rclcpp/subscription_base.hpp b/rclcpp/include/rclcpp/subscription_base.hpp index 1fc967c493..ace5dfdc44 100644 --- a/rclcpp/include/rclcpp/subscription_base.hpp +++ b/rclcpp/include/rclcpp/subscription_base.hpp @@ -372,7 +372,7 @@ class SubscriptionBase : public std::enable_shared_from_this * \param[in] callback functor to be called when a new message is received */ void - set_on_new_message_callback(std::function callback) + set_on_new_message_callback(const std::function & callback) { if (!callback) { throw std::invalid_argument( @@ -450,7 +450,7 @@ class SubscriptionBase : public std::enable_shared_from_this * \param[in] callback functor to be called when a new message is received */ void - set_on_new_intra_process_message_callback(std::function callback) + set_on_new_intra_process_message_callback(const std::function & callback) { if (!use_intra_process_) { RCLCPP_WARN( @@ -468,7 +468,7 @@ class SubscriptionBase : public std::enable_shared_from_this // The on_ready_callback signature has an extra `int` argument used to disambiguate between // possible different entities within a generic waitable. // We hide that detail to users of this method. - std::function new_callback = std::bind(callback, std::placeholders::_1); + std::function new_callback = [callback] (size_t nr, int) {callback(nr);}; subscription_intra_process_->set_on_ready_callback(new_callback); } @@ -514,7 +514,7 @@ class SubscriptionBase : public std::enable_shared_from_this */ void set_on_new_qos_event_callback( - std::function callback, + const std::function & callback, rcl_subscription_event_type_t event_type) { if (event_handlers_.count(event_type) == 0) { @@ -533,7 +533,7 @@ class SubscriptionBase : public std::enable_shared_from_this // The on_ready_callback signature has an extra `int` argument used to disambiguate between // possible different entities within a generic waitable. // We hide that detail to users of this method. - std::function new_callback = std::bind(callback, std::placeholders::_1); + std::function new_callback = [callback] (size_t nr, int) {callback(nr);}; event_handlers_[event_type]->set_on_ready_callback(new_callback); } diff --git a/rclcpp/include/rclcpp/time_source.hpp b/rclcpp/include/rclcpp/time_source.hpp index 0de9b368e8..b9e86294d2 100644 --- a/rclcpp/include/rclcpp/time_source.hpp +++ b/rclcpp/include/rclcpp/time_source.hpp @@ -60,7 +60,7 @@ class TimeSource */ RCLCPP_PUBLIC explicit TimeSource( - rclcpp::Node::SharedPtr node, + const rclcpp::Node::SharedPtr & node, const rclcpp::QoS & qos = rclcpp::ClockQoS(), bool use_clock_thread = true); @@ -89,7 +89,7 @@ class TimeSource * \param node std::shared pointer to a initialized node */ RCLCPP_PUBLIC - void attachNode(rclcpp::Node::SharedPtr node); + void attachNode(const rclcpp::Node::SharedPtr & node); /// Attach node to the time source. /** @@ -124,11 +124,11 @@ class TimeSource * \throws std::invalid_argument the time source must be a RCL_ROS_TIME otherwise throws an exception */ RCLCPP_PUBLIC - void attachClock(rclcpp::Clock::SharedPtr clock); + void attachClock(const rclcpp::Clock::SharedPtr & clock); /// Detach a clock from the time source RCLCPP_PUBLIC - void detachClock(rclcpp::Clock::SharedPtr clock); + void detachClock(const rclcpp::Clock::SharedPtr & clock); /// Get whether a separate clock thread is used or not RCLCPP_PUBLIC diff --git a/rclcpp/src/rclcpp/callback_group.cpp b/rclcpp/src/rclcpp/callback_group.cpp index 73cd458bbc..33d2a1bebe 100644 --- a/rclcpp/src/rclcpp/callback_group.cpp +++ b/rclcpp/src/rclcpp/callback_group.cpp @@ -36,7 +36,7 @@ CallbackGroup::CallbackGroup( : type_(group_type), associated_with_executor_(false), can_be_taken_from_(true), automatically_add_to_executor_with_node_(automatically_add_to_executor_with_node), - context_(context) + context_(std::move(context)) {} CallbackGroup::~CallbackGroup() @@ -69,11 +69,11 @@ CallbackGroup::size() const } void CallbackGroup::collect_all_ptrs( - std::function sub_func, - std::function service_func, - std::function client_func, - std::function timer_func, - std::function waitable_func) const + const std::function & sub_func, + const std::function & service_func, + const std::function & client_func, + const std::function & timer_func, + const std::function & waitable_func) const { std::lock_guard lock(mutex_); @@ -150,7 +150,7 @@ CallbackGroup::trigger_notify_guard_condition() void CallbackGroup::add_subscription( - const rclcpp::SubscriptionBase::SharedPtr subscription_ptr) + const rclcpp::SubscriptionBase::SharedPtr & subscription_ptr) { std::lock_guard lock(mutex_); subscription_ptrs_.push_back(subscription_ptr); @@ -163,7 +163,7 @@ CallbackGroup::add_subscription( } void -CallbackGroup::add_timer(const rclcpp::TimerBase::SharedPtr timer_ptr) +CallbackGroup::add_timer(const rclcpp::TimerBase::SharedPtr & timer_ptr) { std::lock_guard lock(mutex_); timer_ptrs_.push_back(timer_ptr); @@ -176,7 +176,7 @@ CallbackGroup::add_timer(const rclcpp::TimerBase::SharedPtr timer_ptr) } void -CallbackGroup::add_service(const rclcpp::ServiceBase::SharedPtr service_ptr) +CallbackGroup::add_service(const rclcpp::ServiceBase::SharedPtr & service_ptr) { std::lock_guard lock(mutex_); service_ptrs_.push_back(service_ptr); @@ -189,7 +189,7 @@ CallbackGroup::add_service(const rclcpp::ServiceBase::SharedPtr service_ptr) } void -CallbackGroup::add_client(const rclcpp::ClientBase::SharedPtr client_ptr) +CallbackGroup::add_client(const rclcpp::ClientBase::SharedPtr & client_ptr) { std::lock_guard lock(mutex_); client_ptrs_.push_back(client_ptr); @@ -202,7 +202,7 @@ CallbackGroup::add_client(const rclcpp::ClientBase::SharedPtr client_ptr) } void -CallbackGroup::add_waitable(const rclcpp::Waitable::SharedPtr waitable_ptr) +CallbackGroup::add_waitable(const rclcpp::Waitable::SharedPtr & waitable_ptr) { std::lock_guard lock(mutex_); waitable_ptrs_.push_back(waitable_ptr); @@ -215,7 +215,7 @@ CallbackGroup::add_waitable(const rclcpp::Waitable::SharedPtr waitable_ptr) } void -CallbackGroup::remove_waitable(const rclcpp::Waitable::SharedPtr waitable_ptr) noexcept +CallbackGroup::remove_waitable(const rclcpp::Waitable::SharedPtr & waitable_ptr) noexcept { std::lock_guard lock(mutex_); for (auto iter = waitable_ptrs_.begin(); iter != waitable_ptrs_.end(); ++iter) { diff --git a/rclcpp/src/rclcpp/client.cpp b/rclcpp/src/rclcpp/client.cpp index 8388ee1888..45b2899eec 100644 --- a/rclcpp/src/rclcpp/client.cpp +++ b/rclcpp/src/rclcpp/client.cpp @@ -37,7 +37,7 @@ using rclcpp::exceptions::throw_from_rcl_error; ClientBase::ClientBase( rclcpp::node_interfaces::NodeBaseInterface * node_base, - rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph) + const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr & node_graph) : node_graph_(node_graph), node_handle_(node_base->get_shared_rcl_node_handle()), context_(node_base->get_context()), diff --git a/rclcpp/src/rclcpp/clock.cpp b/rclcpp/src/rclcpp/clock.cpp index 46c1f09981..95a52b8b9e 100644 --- a/rclcpp/src/rclcpp/clock.cpp +++ b/rclcpp/src/rclcpp/clock.cpp @@ -60,8 +60,8 @@ JumpHandler::JumpHandler( pre_callback_t pre_callback, post_callback_t post_callback, const rcl_jump_threshold_t & threshold) -: pre_callback(pre_callback), - post_callback(post_callback), +: pre_callback(std::move(pre_callback)), + post_callback(std::move(post_callback)), notice_threshold(threshold) {} @@ -86,7 +86,7 @@ Clock::now() const bool Clock::sleep_until( Time until, - Context::SharedPtr context) + const Context::SharedPtr & context) { if (!context || !context->is_valid()) { throw std::runtime_error("context cannot be slept with because it's invalid"); @@ -194,7 +194,7 @@ Clock::sleep_until( } bool -Clock::sleep_for(Duration rel_time, Context::SharedPtr context) +Clock::sleep_for(Duration rel_time, const Context::SharedPtr & context) { return sleep_until(now() + rel_time, context); } @@ -209,7 +209,7 @@ Clock::started() } bool -Clock::wait_until_started(Context::SharedPtr context) +Clock::wait_until_started(const Context::SharedPtr & context) { if (!context || !context->is_valid()) { throw std::runtime_error("context cannot be slept with because it's invalid"); @@ -229,7 +229,7 @@ Clock::wait_until_started(Context::SharedPtr context) bool Clock::wait_until_started( const Duration & timeout, - Context::SharedPtr context, + const Context::SharedPtr & context, const Duration & wait_tick_ns) { if (!context || !context->is_valid()) { @@ -318,8 +318,8 @@ Clock::on_time_jump( JumpHandler::SharedPtr Clock::create_jump_callback( - JumpHandler::pre_callback_t pre_callback, - JumpHandler::post_callback_t post_callback, + const JumpHandler::pre_callback_t & pre_callback, + const JumpHandler::post_callback_t & post_callback, const rcl_jump_threshold_t & threshold) { // Allocate a new jump handler @@ -516,7 +516,7 @@ class ClockConditionalVariable::Impl ClockWaiter::UniquePtr clock_; public: - Impl(const rclcpp::Clock::SharedPtr & clock, rclcpp::Context::SharedPtr context) + Impl(const rclcpp::Clock::SharedPtr & clock, const rclcpp::Context::SharedPtr & context) :context_(context), clock_(std::make_unique(clock)) { @@ -571,7 +571,7 @@ class ClockConditionalVariable::Impl ClockConditionalVariable::ClockConditionalVariable( const rclcpp::Clock::SharedPtr & clock, - rclcpp::Context::SharedPtr context) + const rclcpp::Context::SharedPtr & context) :impl_(std::make_unique(clock, context)) { } diff --git a/rclcpp/src/rclcpp/context.cpp b/rclcpp/src/rclcpp/context.cpp index a8c0380304..3c9de7a1ac 100644 --- a/rclcpp/src/rclcpp/context.cpp +++ b/rclcpp/src/rclcpp/context.cpp @@ -388,14 +388,14 @@ Context::shutdown(const std::string & reason) } rclcpp::Context::OnShutdownCallback -Context::on_shutdown(OnShutdownCallback callback) +Context::on_shutdown(const OnShutdownCallback & callback) { add_on_shutdown_callback(callback); return callback; } rclcpp::OnShutdownCallbackHandle -Context::add_on_shutdown_callback(OnShutdownCallback callback) +Context::add_on_shutdown_callback(const OnShutdownCallback & callback) { return add_shutdown_callback(callback); } @@ -407,7 +407,7 @@ Context::remove_on_shutdown_callback(const OnShutdownCallbackHandle & callback_h } rclcpp::PreShutdownCallbackHandle -Context::add_pre_shutdown_callback(PreShutdownCallback callback) +Context::add_pre_shutdown_callback(const PreShutdownCallback & callback) { return add_shutdown_callback(callback); } diff --git a/rclcpp/src/rclcpp/create_generic_client.cpp b/rclcpp/src/rclcpp/create_generic_client.cpp index 4b3b7ddc35..57e189f2fa 100644 --- a/rclcpp/src/rclcpp/create_generic_client.cpp +++ b/rclcpp/src/rclcpp/create_generic_client.cpp @@ -19,13 +19,13 @@ namespace rclcpp { rclcpp::GenericClient::SharedPtr create_generic_client( - std::shared_ptr node_base, - std::shared_ptr node_graph, - std::shared_ptr node_services, + const std::shared_ptr & node_base, + const std::shared_ptr & node_graph, + const std::shared_ptr & node_services, const std::string & service_name, const std::string & service_type, const rclcpp::QoS & qos, - rclcpp::CallbackGroup::SharedPtr group) + const rclcpp::CallbackGroup::SharedPtr & group) { rcl_client_options_t options = rcl_client_get_default_options(); options.qos = qos.get_rmw_qos_profile(); diff --git a/rclcpp/src/rclcpp/executor.cpp b/rclcpp/src/rclcpp/executor.cpp index c0c65e8cac..eacc23f351 100644 --- a/rclcpp/src/rclcpp/executor.cpp +++ b/rclcpp/src/rclcpp/executor.cpp @@ -170,8 +170,8 @@ Executor::get_automatically_added_callback_groups_from_nodes() void Executor::add_callback_group( - rclcpp::CallbackGroup::SharedPtr group_ptr, - [[maybe_unused]] rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, + const rclcpp::CallbackGroup::SharedPtr & group_ptr, + [[maybe_unused]] const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr, bool notify) { this->collector_.add_callback_group(group_ptr); @@ -186,7 +186,9 @@ Executor::add_callback_group( } void -Executor::add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify) +Executor::add_node( + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr, + bool notify) { if (node_ptr->get_context() != context_) { throw std::runtime_error( @@ -206,7 +208,7 @@ Executor::add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_pt void Executor::remove_callback_group( - rclcpp::CallbackGroup::SharedPtr group_ptr, + const rclcpp::CallbackGroup::SharedPtr & group_ptr, bool notify) { this->collector_.remove_callback_group(group_ptr); @@ -221,13 +223,15 @@ Executor::remove_callback_group( } void -Executor::add_node(std::shared_ptr node_ptr, bool notify) +Executor::add_node(const std::shared_ptr & node_ptr, bool notify) { this->add_node(node_ptr->get_node_base_interface(), notify); } void -Executor::remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify) +Executor::remove_node( + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr, + bool notify) { this->collector_.remove_node(node_ptr); @@ -241,14 +245,14 @@ Executor::remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node } void -Executor::remove_node(std::shared_ptr node_ptr, bool notify) +Executor::remove_node(const std::shared_ptr & node_ptr, bool notify) { this->remove_node(node_ptr->get_node_base_interface(), notify); } void Executor::spin_node_once_nanoseconds( - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node, std::chrono::nanoseconds timeout) { this->add_node(node, false); @@ -311,7 +315,7 @@ Executor::spin_until_future_complete_impl( } void -Executor::spin_node_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node) +Executor::spin_node_some(const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node) { this->add_node(node, false); spin_some(); @@ -319,7 +323,7 @@ Executor::spin_node_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr n } void -Executor::spin_node_some(std::shared_ptr node) +Executor::spin_node_some(const std::shared_ptr & node) { this->spin_node_some(node->get_node_base_interface()); } @@ -331,7 +335,7 @@ void Executor::spin_some(std::chrono::nanoseconds max_duration) void Executor::spin_node_all( - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node, std::chrono::nanoseconds max_duration) { this->add_node(node, false); @@ -340,7 +344,9 @@ Executor::spin_node_all( } void -Executor::spin_node_all(std::shared_ptr node, std::chrono::nanoseconds max_duration) +Executor::spin_node_all( + const std::shared_ptr & node, + std::chrono::nanoseconds max_duration) { this->spin_node_all(node->get_node_base_interface(), max_duration); } @@ -546,7 +552,7 @@ take_and_do_error_handling( } void -Executor::execute_subscription(rclcpp::SubscriptionBase::SharedPtr subscription) +Executor::execute_subscription(const rclcpp::SubscriptionBase::SharedPtr & subscription) { using rclcpp::dynamic_typesupport::DynamicMessage; @@ -648,13 +654,15 @@ Executor::execute_subscription(rclcpp::SubscriptionBase::SharedPtr subscription) } void -Executor::execute_timer(rclcpp::TimerBase::SharedPtr timer, const std::shared_ptr & data_ptr) +Executor::execute_timer( + const rclcpp::TimerBase::SharedPtr & timer, + const std::shared_ptr & data_ptr) { timer->execute_callback(data_ptr); } void -Executor::execute_service(rclcpp::ServiceBase::SharedPtr service) +Executor::execute_service(const rclcpp::ServiceBase::SharedPtr & service) { auto request_header = service->create_request_header(); std::shared_ptr request = service->create_request(); @@ -666,7 +674,7 @@ Executor::execute_service(rclcpp::ServiceBase::SharedPtr service) } void -Executor::execute_client(rclcpp::ClientBase::SharedPtr client) +Executor::execute_client(const rclcpp::ClientBase::SharedPtr & client) { auto request_header = client->create_request_header(); std::shared_ptr response = client->create_response(); diff --git a/rclcpp/src/rclcpp/executors.cpp b/rclcpp/src/rclcpp/executors.cpp index cd3180697f..4b1a7be4d0 100644 --- a/rclcpp/src/rclcpp/executors.cpp +++ b/rclcpp/src/rclcpp/executors.cpp @@ -17,7 +17,7 @@ void rclcpp::spin_all( - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr, std::chrono::nanoseconds max_duration) { rclcpp::ExecutorOptions options; @@ -27,7 +27,7 @@ rclcpp::spin_all( } void -rclcpp::spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr) +rclcpp::spin_some(const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr) { rclcpp::ExecutorOptions options; options.context = node_ptr->get_context(); @@ -36,7 +36,7 @@ rclcpp::spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr } void -rclcpp::spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr) +rclcpp::spin(const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr) { rclcpp::ExecutorOptions options; options.context = node_ptr->get_context(); @@ -47,13 +47,13 @@ rclcpp::spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr) } void -rclcpp::spin(rclcpp::Node::SharedPtr node_ptr) +rclcpp::spin(const rclcpp::Node::SharedPtr & node_ptr) { rclcpp::spin(node_ptr->get_node_base_interface()); } void -rclcpp::spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration) +rclcpp::spin_all(const rclcpp::Node::SharedPtr & node_ptr, std::chrono::nanoseconds max_duration) { RCPPUTILS_DEPRECATION_WARNING_OFF_START rclcpp::spin_all(node_ptr->get_node_base_interface(), max_duration); @@ -61,7 +61,7 @@ rclcpp::spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_ } void -rclcpp::spin_some(rclcpp::Node::SharedPtr node_ptr) +rclcpp::spin_some(const rclcpp::Node::SharedPtr & node_ptr) { RCPPUTILS_DEPRECATION_WARNING_OFF_START rclcpp::spin_some(node_ptr->get_node_base_interface()); diff --git a/rclcpp/src/rclcpp/executors/executor_entities_collector.cpp b/rclcpp/src/rclcpp/executors/executor_entities_collector.cpp index 702716a758..85e2dd1d35 100644 --- a/rclcpp/src/rclcpp/executors/executor_entities_collector.cpp +++ b/rclcpp/src/rclcpp/executors/executor_entities_collector.cpp @@ -83,7 +83,8 @@ ExecutorEntitiesCollector::has_pending() const } void -ExecutorEntitiesCollector::add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr) +ExecutorEntitiesCollector::add_node( + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr) { // If the node already has an executor std::atomic_bool & has_executor = node_ptr->get_associated_with_executor_atomic(); @@ -109,7 +110,7 @@ ExecutorEntitiesCollector::add_node(rclcpp::node_interfaces::NodeBaseInterface:: void ExecutorEntitiesCollector::remove_node( - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr) + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr) { std::atomic_bool & has_executor = node_ptr->get_associated_with_executor_atomic(); if (!has_executor.exchange(false)) { @@ -133,7 +134,7 @@ ExecutorEntitiesCollector::remove_node( } void -ExecutorEntitiesCollector::add_callback_group(rclcpp::CallbackGroup::SharedPtr group_ptr) +ExecutorEntitiesCollector::add_callback_group(const rclcpp::CallbackGroup::SharedPtr & group_ptr) { std::atomic_bool & has_executor = group_ptr->get_associated_with_executor_atomic(); if (has_executor.exchange(true)) { @@ -158,7 +159,7 @@ ExecutorEntitiesCollector::add_callback_group(rclcpp::CallbackGroup::SharedPtr g } void -ExecutorEntitiesCollector::remove_callback_group(rclcpp::CallbackGroup::SharedPtr group_ptr) +ExecutorEntitiesCollector::remove_callback_group(const rclcpp::CallbackGroup::SharedPtr & group_ptr) { if (!group_ptr->get_associated_with_executor_atomic().load()) { throw std::runtime_error("Callback group needs to be associated with an executor."); @@ -288,7 +289,7 @@ ExecutorEntitiesCollector::remove_weak_callback_group( void ExecutorEntitiesCollector::add_callback_group_to_collection( - rclcpp::CallbackGroup::SharedPtr group_ptr, + const rclcpp::CallbackGroup::SharedPtr & group_ptr, CallbackGroupCollection & collection) { auto iter = collection.insert(group_ptr); diff --git a/rclcpp/src/rclcpp/executors/executor_notify_waitable.cpp b/rclcpp/src/rclcpp/executors/executor_notify_waitable.cpp index b5d88e162e..3aad60bf46 100644 --- a/rclcpp/src/rclcpp/executors/executor_notify_waitable.cpp +++ b/rclcpp/src/rclcpp/executors/executor_notify_waitable.cpp @@ -23,7 +23,7 @@ namespace executors ExecutorNotifyWaitable::ExecutorNotifyWaitable( std::function on_execute_callback, const rclcpp::Context::SharedPtr & context) -: execute_callback_(on_execute_callback), +: execute_callback_(std::move(on_execute_callback)), guard_condition_(std::make_shared(context)) { } @@ -144,13 +144,13 @@ ExecutorNotifyWaitable::take_data_by_entity_id([[maybe_unused]] size_t id) } void -ExecutorNotifyWaitable::set_on_ready_callback(std::function callback) +ExecutorNotifyWaitable::set_on_ready_callback(std::function callback_in) { // The second argument of the callback could be used to identify which guard condition // triggered the event. // We could indicate which of the guard conditions was triggered, but the executor // is already going to check that. - auto gc_callback = [callback](size_t count) { + auto gc_callback = [callback = std::move(callback_in)](size_t count) { callback(count, 0); }; @@ -179,11 +179,12 @@ void ExecutorNotifyWaitable::set_execute_callback(std::function on_execute_callback) { std::lock_guard lock(execute_mutex_); - execute_callback_ = on_execute_callback; + execute_callback_ = std::move(on_execute_callback); } void -ExecutorNotifyWaitable::add_guard_condition(rclcpp::GuardCondition::WeakPtr weak_guard_condition) +ExecutorNotifyWaitable::add_guard_condition( + const rclcpp::GuardCondition::WeakPtr & weak_guard_condition) { std::lock_guard lock(guard_condition_mutex_); const auto & guard_condition = weak_guard_condition.lock(); @@ -196,7 +197,8 @@ ExecutorNotifyWaitable::add_guard_condition(rclcpp::GuardCondition::WeakPtr weak } void -ExecutorNotifyWaitable::remove_guard_condition(rclcpp::GuardCondition::WeakPtr weak_guard_condition) +ExecutorNotifyWaitable::remove_guard_condition( + const rclcpp::GuardCondition::WeakPtr & weak_guard_condition) { std::lock_guard lock(guard_condition_mutex_); const auto & guard_condition = weak_guard_condition.lock(); diff --git a/rclcpp/src/rclcpp/experimental/timers_manager.cpp b/rclcpp/src/rclcpp/experimental/timers_manager.cpp index 2caa0a6b15..abf2edd8d3 100644 --- a/rclcpp/src/rclcpp/experimental/timers_manager.cpp +++ b/rclcpp/src/rclcpp/experimental/timers_manager.cpp @@ -29,7 +29,7 @@ TimersManager::TimersManager( std::shared_ptr context, std::function &)> on_ready_callback) : on_ready_callback_(on_ready_callback), - context_(context) + context_(std::move(context)) { } @@ -42,7 +42,7 @@ TimersManager::~TimersManager() this->stop(); } -void TimersManager::add_timer(rclcpp::TimerBase::SharedPtr timer) +void TimersManager::add_timer(const rclcpp::TimerBase::SharedPtr & timer) { if (!timer) { throw std::invalid_argument("TimersManager::add_timer() trying to add nullptr timer"); @@ -311,7 +311,7 @@ void TimersManager::clear() timers_cv_.notify_one(); } -void TimersManager::remove_timer(TimerPtr timer) +void TimersManager::remove_timer(const TimerPtr & timer) { bool removed = false; { diff --git a/rclcpp/src/rclcpp/generic_client.cpp b/rclcpp/src/rclcpp/generic_client.cpp index 0ac9a86e15..f68742b9d0 100644 --- a/rclcpp/src/rclcpp/generic_client.cpp +++ b/rclcpp/src/rclcpp/generic_client.cpp @@ -97,8 +97,8 @@ GenericClient::create_request_header() void GenericClient::handle_response( - std::shared_ptr request_header, - std::shared_ptr response) + const std::shared_ptr & request_header, + const std::shared_ptr & response) { auto optional_pending_request = this->get_and_erase_pending_request(request_header->sequence_number); @@ -164,7 +164,7 @@ GenericClient::get_and_erase_pending_request(int64_t request_number) } GenericClient::FutureAndRequestId -GenericClient::async_send_request(const Request request) +GenericClient::async_send_request(const Request & request) { Promise promise; auto future = promise.get_future(); @@ -175,7 +175,7 @@ GenericClient::async_send_request(const Request request) } int64_t -GenericClient::async_send_request_impl(const Request request, CallbackInfoVariant value) +GenericClient::async_send_request_impl(const Request & request, CallbackInfoVariant value) { int64_t sequence_number; std::lock_guard lock(pending_requests_mutex_); diff --git a/rclcpp/src/rclcpp/generic_service.cpp b/rclcpp/src/rclcpp/generic_service.cpp index 75b34993bf..d37a6fd41b 100644 --- a/rclcpp/src/rclcpp/generic_service.cpp +++ b/rclcpp/src/rclcpp/generic_service.cpp @@ -17,13 +17,13 @@ namespace rclcpp { GenericService::GenericService( - std::shared_ptr node_handle, + const std::shared_ptr & node_handle, const std::string & service_name, const std::string & service_type, GenericServiceCallback any_callback, rcl_service_options_t & service_options) : ServiceBase(node_handle), - any_callback_(any_callback) + any_callback_(std::move(any_callback)) { const rosidl_service_type_support_t * service_ts; try { @@ -98,7 +98,7 @@ GenericService::GenericService( bool GenericService::take_request( - SharedRequest request_out, + SharedRequest & request_out, rmw_request_id_t & request_id_out) { request_out = create_request(); @@ -141,8 +141,8 @@ GenericService::create_request_header() void GenericService::handle_request( - std::shared_ptr request_header, - std::shared_ptr request) + const std::shared_ptr & request_header, + const std::shared_ptr & request) { auto response = any_callback_.dispatch( this->shared_from_this(), request_header, request, create_response()); diff --git a/rclcpp/src/rclcpp/guard_condition.cpp b/rclcpp/src/rclcpp/guard_condition.cpp index 700985f620..2e0e8d4148 100644 --- a/rclcpp/src/rclcpp/guard_condition.cpp +++ b/rclcpp/src/rclcpp/guard_condition.cpp @@ -112,7 +112,7 @@ GuardCondition::add_to_wait_set(rcl_wait_set_t & wait_set) } void -GuardCondition::set_on_trigger_callback(std::function callback) +GuardCondition::set_on_trigger_callback(const std::function & callback) { std::lock_guard lock(reentrant_mutex_); diff --git a/rclcpp/src/rclcpp/intra_process_manager.cpp b/rclcpp/src/rclcpp/intra_process_manager.cpp index 831ffdf2ca..810d79951c 100644 --- a/rclcpp/src/rclcpp/intra_process_manager.cpp +++ b/rclcpp/src/rclcpp/intra_process_manager.cpp @@ -33,14 +33,14 @@ IntraProcessManager::~IntraProcessManager() uint64_t IntraProcessManager::add_publisher( - rclcpp::PublisherBase::SharedPtr publisher, - rclcpp::experimental::buffers::IntraProcessBufferBase::SharedPtr buffer) + const rclcpp::PublisherBase::SharedPtr & publisher, + const rclcpp::experimental::buffers::IntraProcessBufferBase::SharedPtr & buffer) { std::unique_lock lock(mutex_); uint64_t pub_id = IntraProcessManager::get_next_unique_id(); - publishers_[pub_id] = publisher; + publishers_[pub_id] = std::move(publisher); if (publisher->is_durability_transient_local()) { if (buffer) { publisher_buffers_[pub_id] = buffer; @@ -197,8 +197,8 @@ IntraProcessManager::insert_sub_id_for_pub( bool IntraProcessManager::can_communicate( - rclcpp::PublisherBase::SharedPtr pub, - rclcpp::experimental::SubscriptionIntraProcessBase::SharedPtr sub) const + const rclcpp::PublisherBase::SharedPtr & pub, + const rclcpp::experimental::SubscriptionIntraProcessBase::SharedPtr & sub) const { // publisher and subscription must be on the same topic if (strcmp(pub->get_topic_name(), sub->get_topic_name()) != 0) { diff --git a/rclcpp/src/rclcpp/node_interfaces/node_base.cpp b/rclcpp/src/rclcpp/node_interfaces/node_base.cpp index 5a004faf71..9c27776264 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_base.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_base.cpp @@ -42,13 +42,13 @@ NodeBase::NodeBase( bool use_intra_process_default, bool enable_topic_statistics_default, rclcpp::CallbackGroup::SharedPtr default_callback_group) -: context_(context), +: context_(std::move(context)), use_intra_process_default_(use_intra_process_default), enable_topic_statistics_default_(enable_topic_statistics_default), node_handle_(nullptr), - default_callback_group_(default_callback_group), + default_callback_group_(std::move(default_callback_group)), associated_with_executor_(false), - notify_guard_condition_(std::make_shared(context)), + notify_guard_condition_(std::make_shared(context_)), notify_guard_condition_is_valid_(false) { // Create the rcl node and store it in a shared_ptr with a custom destructor. diff --git a/rclcpp/src/rclcpp/node_interfaces/node_clock.cpp b/rclcpp/src/rclcpp/node_interfaces/node_clock.cpp index a37c65b71b..7050dd46c3 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_clock.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_clock.cpp @@ -26,11 +26,11 @@ NodeClock::NodeClock( rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, rcl_clock_type_t clock_type) -: node_base_(node_base), - node_topics_(node_topics), - node_graph_(node_graph), - node_services_(node_services), - node_logging_(node_logging), +: node_base_(std::move(node_base)), + node_topics_(std::move(node_topics)), + node_graph_(std::move(node_graph)), + node_services_(std::move(node_services)), + node_logging_(std::move(node_logging)), clock_(std::make_shared(clock_type)) {} diff --git a/rclcpp/src/rclcpp/node_interfaces/node_time_source.cpp b/rclcpp/src/rclcpp/node_interfaces/node_time_source.cpp index 2bd3a098b6..39a2b4de30 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_time_source.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_time_source.cpp @@ -29,13 +29,13 @@ NodeTimeSource::NodeTimeSource( rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters, const rclcpp::QoS & qos, bool use_clock_thread) -: node_base_(node_base), - node_topics_(node_topics), - node_graph_(node_graph), - node_services_(node_services), - node_logging_(node_logging), - node_clock_(node_clock), - node_parameters_(node_parameters), +: node_base_(std::move(node_base)), + node_topics_(std::move(node_topics)), + node_graph_(std::move(node_graph)), + node_services_(std::move(node_services)), + node_logging_(std::move(node_logging)), + node_clock_(std::move(node_clock)), + node_parameters_(std::move(node_parameters)), time_source_(qos, use_clock_thread) { time_source_.attachNode( diff --git a/rclcpp/src/rclcpp/node_interfaces/node_type_descriptions.cpp b/rclcpp/src/rclcpp/node_interfaces/node_type_descriptions.cpp index 0a681b1942..dfc4c99f36 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_type_descriptions.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_type_descriptions.cpp @@ -59,11 +59,11 @@ class NodeTypeDescriptions::NodeTypeDescriptionsImpl NodeTypeDescriptionsImpl( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, - rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, - rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters, - rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services) + const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & node_logging, + const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node_parameters, + const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr & node_services) : logger_(node_logging->get_logger()), - node_base_(node_base) + node_base_(std::move(node_base)) { rclcpp::ParameterValue enable_param; const std::string enable_param_name = "start_type_description_service"; @@ -92,7 +92,7 @@ class NodeTypeDescriptions::NodeTypeDescriptionsImpl } if (enable_param.get()) { - auto * rcl_node = node_base->get_rcl_node_handle(); + auto * rcl_node = node_base_->get_rcl_node_handle(); std::shared_ptr rcl_srv( new rcl_service_t, [rcl_node, logger = this->logger_](rcl_service_t * service) @@ -144,10 +144,10 @@ class NodeTypeDescriptions::NodeTypeDescriptionsImpl }; NodeTypeDescriptions::NodeTypeDescriptions( - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, - rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, - rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters, - rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services) + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_base, + const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & node_logging, + const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node_parameters, + const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr & node_services) : impl_(new NodeTypeDescriptionsImpl( node_base, node_logging, diff --git a/rclcpp/src/rclcpp/parameter_events_filter.cpp b/rclcpp/src/rclcpp/parameter_events_filter.cpp index 44e7f57d55..32cc2438ee 100644 --- a/rclcpp/src/rclcpp/parameter_events_filter.cpp +++ b/rclcpp/src/rclcpp/parameter_events_filter.cpp @@ -26,13 +26,13 @@ ParameterEventsFilter::ParameterEventsFilter( std::shared_ptr event, const std::vector & names, const std::vector & types) -: event_(event) +: event_(std::move(event)) { - if (!event) { + if (!event_) { throw std::invalid_argument("event cannot be null"); } if (std::find(types.begin(), types.end(), EventType::NEW) != types.end()) { - for (auto & new_parameter : event->new_parameters) { + for (auto & new_parameter : event_->new_parameters) { if (std::find(names.begin(), names.end(), new_parameter.name) != names.end()) { result_.push_back( EventPair(EventType::NEW, &new_parameter)); @@ -40,7 +40,7 @@ ParameterEventsFilter::ParameterEventsFilter( } } if (std::find(types.begin(), types.end(), EventType::CHANGED) != types.end()) { - for (auto & changed_parameter : event->changed_parameters) { + for (auto & changed_parameter : event_->changed_parameters) { if (std::find(names.begin(), names.end(), changed_parameter.name) != names.end()) { result_.push_back( EventPair(EventType::CHANGED, &changed_parameter)); @@ -48,7 +48,7 @@ ParameterEventsFilter::ParameterEventsFilter( } } if (std::find(types.begin(), types.end(), EventType::DELETED) != types.end()) { - for (auto & deleted_parameter : event->deleted_parameters) { + for (auto & deleted_parameter : event_->deleted_parameters) { if (std::find(names.begin(), names.end(), deleted_parameter.name) != names.end()) { result_.push_back( EventPair(EventType::DELETED, &deleted_parameter)); diff --git a/rclcpp/src/rclcpp/publisher_base.cpp b/rclcpp/src/rclcpp/publisher_base.cpp index bcade9b1bf..ff9eae8582 100644 --- a/rclcpp/src/rclcpp/publisher_base.cpp +++ b/rclcpp/src/rclcpp/publisher_base.cpp @@ -344,7 +344,7 @@ PublisherBase::operator==(const rmw_gid_t * gid) const void PublisherBase::setup_intra_process( uint64_t intra_process_publisher_id, - IntraProcessManagerSharedPtr ipm) + const IntraProcessManagerSharedPtr & ipm) { intra_process_publisher_id_ = intra_process_publisher_id; weak_ipm_ = ipm; diff --git a/rclcpp/src/rclcpp/qos_overriding_options.cpp b/rclcpp/src/rclcpp/qos_overriding_options.cpp index ab5d705bf3..039c92dfb1 100644 --- a/rclcpp/src/rclcpp/qos_overriding_options.cpp +++ b/rclcpp/src/rclcpp/qos_overriding_options.cpp @@ -60,7 +60,7 @@ QosOverridingOptions::with_default_policies( QosCallback validation_callback, std::string id) { - return QosOverridingOptions{kDefaultPolicies, validation_callback, id}; + return QosOverridingOptions{kDefaultPolicies, std::move(validation_callback), id}; } const std::string & diff --git a/rclcpp/src/rclcpp/rate.cpp b/rclcpp/src/rclcpp/rate.cpp index 6bc0984fed..0d04a22c66 100644 --- a/rclcpp/src/rclcpp/rate.cpp +++ b/rclcpp/src/rclcpp/rate.cpp @@ -21,8 +21,8 @@ namespace rclcpp { Rate::Rate( - const double rate, Clock::SharedPtr clock) -: clock_(clock), period_(0, 0), last_interval_(clock_->now()) + const double rate, const Clock::SharedPtr & clock) +: clock_(std::move(clock)), period_(0, 0), last_interval_(clock_->now()) { if (rate <= 0.0) { throw std::invalid_argument{"rate must be greater than 0"}; @@ -31,7 +31,7 @@ Rate::Rate( } Rate::Rate( - const Duration & period, Clock::SharedPtr clock) + const Duration & period, const Clock::SharedPtr & clock) : clock_(clock), period_(period), last_interval_(clock_->now()) { if (period <= Duration(0, 0)) { diff --git a/rclcpp/src/rclcpp/service.cpp b/rclcpp/src/rclcpp/service.cpp index 9c246e4b6b..5b7fc57343 100644 --- a/rclcpp/src/rclcpp/service.cpp +++ b/rclcpp/src/rclcpp/service.cpp @@ -28,7 +28,7 @@ using rclcpp::ServiceBase; -ServiceBase::ServiceBase(std::shared_ptr node_handle) +ServiceBase::ServiceBase(const std::shared_ptr & node_handle) : node_handle_(node_handle), node_logger_(rclcpp::get_node_logger(node_handle_.get())) {} diff --git a/rclcpp/src/rclcpp/subscription_base.cpp b/rclcpp/src/rclcpp/subscription_base.cpp index 5ff0df3309..9cf1a07c0e 100644 --- a/rclcpp/src/rclcpp/subscription_base.cpp +++ b/rclcpp/src/rclcpp/subscription_base.cpp @@ -323,7 +323,7 @@ SubscriptionBase::setup_intra_process( IntraProcessManagerWeakPtr weak_ipm) { intra_process_subscription_id_ = intra_process_subscription_id; - weak_ipm_ = weak_ipm; + weak_ipm_ = std::move(weak_ipm); use_intra_process_ = true; } diff --git a/rclcpp/src/rclcpp/time_source.cpp b/rclcpp/src/rclcpp/time_source.cpp index 8c0126dcfb..e9a08388e2 100644 --- a/rclcpp/src/rclcpp/time_source.cpp +++ b/rclcpp/src/rclcpp/time_source.cpp @@ -81,7 +81,7 @@ class ClocksState final } // Attach a clock - void attachClock(rclcpp::Clock::SharedPtr clock) + void attachClock(const rclcpp::Clock::SharedPtr & clock) { { std::lock_guard clock_guard(clock->get_clock_mutex()); @@ -97,7 +97,7 @@ class ClocksState final } // Detach a clock - void detachClock(rclcpp::Clock::SharedPtr clock) + void detachClock(const rclcpp::Clock::SharedPtr & clock) { std::lock_guard guard(clock_list_lock_); auto removed = associated_clocks_.erase(clock); @@ -108,9 +108,9 @@ class ClocksState final // Internal helper function used inside iterators static void set_clock( - const builtin_interfaces::msg::Time::SharedPtr msg, + const builtin_interfaces::msg::Time::SharedPtr & msg, bool set_ros_time_enabled, - rclcpp::Clock::SharedPtr clock) + const rclcpp::Clock::SharedPtr & clock) { std::lock_guard clock_guard(clock->get_clock_mutex()); @@ -145,7 +145,7 @@ class ClocksState final // Internal helper function void set_all_clocks( - const builtin_interfaces::msg::Time::SharedPtr msg, + const builtin_interfaces::msg::Time::SharedPtr & msg, bool set_ros_time_enabled) { std::lock_guard guard(clock_list_lock_); @@ -155,7 +155,7 @@ class ClocksState final } // Cache the last clock message received - void cache_last_msg(std::shared_ptr msg) + void cache_last_msg(std::shared_ptr & msg) { last_time_msg_ = std::make_shared(msg->clock); } @@ -237,13 +237,13 @@ class TimeSource::NodeState final rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface) { std::lock_guard guard(node_base_lock_); - node_base_ = node_base_interface; - node_topics_ = node_topics_interface; - node_graph_ = node_graph_interface; - node_services_ = node_services_interface; - node_logging_ = node_logging_interface; - node_clock_ = node_clock_interface; - node_parameters_ = node_parameters_interface; + node_base_ = std::move(node_base_interface); + node_topics_ = std::move(node_topics_interface); + node_graph_ = std::move(node_graph_interface); + node_services_ = std::move(node_services_interface); + node_logging_ = std::move(node_logging_interface); + node_clock_ = std::move(node_clock_interface); + node_parameters_ = std::move(node_parameters_interface); // TODO(tfoote): Update QOS logger_ = node_logging_->get_logger(); @@ -305,14 +305,14 @@ class TimeSource::NodeState final node_parameters_.reset(); } - void attachClock(std::shared_ptr clock) + void attachClock(const std::shared_ptr & clock) { - clocks_state_.attachClock(std::move(clock)); + clocks_state_.attachClock(clock); } - void detachClock(std::shared_ptr clock) + void detachClock(const std::shared_ptr & clock) { - clocks_state_.detachClock(std::move(clock)); + clocks_state_.detachClock(clock); } private: @@ -484,7 +484,7 @@ class TimeSource::NodeState final }; TimeSource::TimeSource( - std::shared_ptr node, + const std::shared_ptr & node, const rclcpp::QoS & qos, bool use_clock_thread) : TimeSource(qos, use_clock_thread) @@ -501,7 +501,7 @@ TimeSource::TimeSource( node_state_ = std::make_shared(qos, use_clock_thread); } -void TimeSource::attachNode(rclcpp::Node::SharedPtr node) +void TimeSource::attachNode(const rclcpp::Node::SharedPtr & node) { node_state_->set_use_clock_thread(node->get_node_options().use_clock_thread()); attachNode( @@ -541,14 +541,14 @@ void TimeSource::detachNode() constructed_use_clock_thread_); } -void TimeSource::attachClock(std::shared_ptr clock) +void TimeSource::attachClock(const std::shared_ptr & clock) { - node_state_->attachClock(std::move(clock)); + node_state_->attachClock(clock); } -void TimeSource::detachClock(std::shared_ptr clock) +void TimeSource::detachClock(const std::shared_ptr & clock) { - node_state_->detachClock(std::move(clock)); + node_state_->detachClock(clock); } bool TimeSource::get_use_clock_thread() diff --git a/rclcpp/test/rclcpp/executors/test_waitable.cpp b/rclcpp/test/rclcpp/executors/test_waitable.cpp index 7ee002ccdb..5955ed096e 100644 --- a/rclcpp/test/rclcpp/executors/test_waitable.cpp +++ b/rclcpp/test/rclcpp/executors/test_waitable.cpp @@ -88,7 +88,7 @@ TestWaitable::execute(const std::shared_ptr &) void TestWaitable::set_on_execute_callback(std::function on_execute_callback) { - on_execute_callback_ = on_execute_callback; + on_execute_callback_ = std::move(on_execute_callback); } void diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp index 7b00fea972..4d33948517 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp @@ -34,7 +34,9 @@ class TestService : public rclcpp::ServiceBase std::shared_ptr create_request() override {return nullptr;} std::shared_ptr create_request_header() override {return nullptr;} - void handle_request(std::shared_ptr, std::shared_ptr) override {} + void handle_request( + const std::shared_ptr &, + const std::shared_ptr &) override {} }; class TestClient : public rclcpp::ClientBase @@ -46,7 +48,7 @@ class TestClient : public rclcpp::ClientBase std::shared_ptr create_response() override {return nullptr;} std::shared_ptr create_request_header() override {return nullptr;} void handle_response( - std::shared_ptr, std::shared_ptr) override {} + const std::shared_ptr &, const std::shared_ptr &) override {} }; class TestNodeService : public ::testing::Test