.. _program_listing_file_include_rclcpp_wait_set_policies_static_storage.hpp: Program Listing for File static_storage.hpp =========================================== |exhale_lsh| :ref:`Return to documentation for file ` (``include/rclcpp/wait_set_policies/static_storage.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2020 Open Source Robotics Foundation, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #ifndef RCLCPP__WAIT_SET_POLICIES__STATIC_STORAGE_HPP_ #define RCLCPP__WAIT_SET_POLICIES__STATIC_STORAGE_HPP_ #include #include #include #include "rclcpp/client.hpp" #include "rclcpp/guard_condition.hpp" #include "rclcpp/macros.hpp" #include "rclcpp/service.hpp" #include "rclcpp/subscription_base.hpp" #include "rclcpp/subscription_wait_set_mask.hpp" #include "rclcpp/timer.hpp" #include "rclcpp/visibility_control.hpp" #include "rclcpp/wait_set_policies/detail/storage_policy_common.hpp" #include "rclcpp/waitable.hpp" namespace rclcpp { namespace wait_set_policies { template< std::size_t NumberOfSubscriptions, std::size_t NumberOfGuardCondtions, std::size_t NumberOfTimers, std::size_t NumberOfClients, std::size_t NumberOfServices, std::size_t NumberOfWaitables > class StaticStorage : public rclcpp::wait_set_policies::detail::StoragePolicyCommon { protected: using is_mutable = std::false_type; class SubscriptionEntry { public: std::shared_ptr subscription; rclcpp::SubscriptionWaitSetMask mask; SubscriptionEntry( std::shared_ptr subscription_in = nullptr, rclcpp::SubscriptionWaitSetMask mask_in = {}) : subscription(std::move(subscription_in)), mask(mask_in) {} }; using ArrayOfSubscriptions = std::array< SubscriptionEntry, NumberOfSubscriptions >; using SubscriptionsIterable = ArrayOfSubscriptions; using ArrayOfGuardConditions = std::array< std::shared_ptr, NumberOfGuardCondtions >; using GuardConditionsIterable = ArrayOfGuardConditions; using ArrayOfTimers = std::array< std::shared_ptr, NumberOfTimers >; using TimersIterable = ArrayOfTimers; using ArrayOfClients = std::array< std::shared_ptr, NumberOfClients >; using ClientsIterable = ArrayOfClients; using ArrayOfServices = std::array< std::shared_ptr, NumberOfServices >; using ServicesIterable = ArrayOfServices; struct WaitableEntry { WaitableEntry( std::shared_ptr waitable_in = nullptr, std::shared_ptr associated_entity_in = nullptr) noexcept : waitable(std::move(waitable_in)), associated_entity(std::move(associated_entity_in)) {} std::shared_ptr waitable; std::shared_ptr associated_entity; }; using ArrayOfWaitables = std::array< WaitableEntry, NumberOfWaitables >; using WaitablesIterable = ArrayOfWaitables; template explicit StaticStorage( const ArrayOfSubscriptions & subscriptions, const ArrayOfGuardConditions & guard_conditions, const ArrayOfExtraGuardConditions & extra_guard_conditions, const ArrayOfTimers & timers, const ArrayOfClients & clients, const ArrayOfServices & services, const ArrayOfWaitables & waitables, rclcpp::Context::SharedPtr context ) : StoragePolicyCommon( subscriptions, guard_conditions, extra_guard_conditions, timers, clients, services, waitables, context), subscriptions_(subscriptions), guard_conditions_(guard_conditions), timers_(timers), clients_(clients), services_(services), waitables_(waitables) {} ~StaticStorage() = default; template void storage_rebuild_rcl_wait_set(const ArrayOfExtraGuardConditions & extra_guard_conditions) { this->storage_rebuild_rcl_wait_set_with_sets( subscriptions_, guard_conditions_, extra_guard_conditions, timers_, clients_, services_, waitables_ ); } // storage_add_subscription() explicitly not declared here // storage_remove_subscription() explicitly not declared here // storage_add_guard_condition() explicitly not declared here // storage_remove_guard_condition() explicitly not declared here // storage_add_timer() explicitly not declared here // storage_remove_timer() explicitly not declared here // storage_add_client() explicitly not declared here // storage_remove_client() explicitly not declared here // storage_add_service() explicitly not declared here // storage_remove_service() explicitly not declared here // storage_add_waitable() explicitly not declared here // storage_remove_waitable() explicitly not declared here // storage_prune_deleted_entities() explicitly not declared here void storage_acquire_ownerships() { // Explicitly do nothing. } void storage_release_ownerships() { // Explicitly do nothing. } const ArrayOfSubscriptions subscriptions_; const ArrayOfGuardConditions guard_conditions_; const ArrayOfTimers timers_; const ArrayOfClients clients_; const ArrayOfServices services_; const ArrayOfWaitables waitables_; }; } // namespace wait_set_policies } // namespace rclcpp #endif // RCLCPP__WAIT_SET_POLICIES__STATIC_STORAGE_HPP_