Program Listing for File executor_entities_collector.hpp

Return to documentation for file (include/rclcpp/executors/executor_entities_collector.hpp)

// Copyright 2023 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__EXECUTORS__EXECUTOR_ENTITIES_COLLECTOR_HPP_
#define RCLCPP__EXECUTORS__EXECUTOR_ENTITIES_COLLECTOR_HPP_

#include <map>
#include <memory>
#include <mutex>
#include <set>
#include <vector>

#include "rcpputils/thread_safety_annotations.hpp"

#include <rclcpp/any_executable.hpp>
#include <rclcpp/node_interfaces/node_base.hpp>
#include <rclcpp/callback_group.hpp>
#include <rclcpp/executors/executor_notify_waitable.hpp>
#include <rclcpp/visibility_control.hpp>
#include <rclcpp/wait_set.hpp>
#include <rclcpp/wait_result.hpp>

namespace rclcpp
{
namespace executors
{


class ExecutorEntitiesCollector
{
public:

  RCLCPP_PUBLIC
  explicit ExecutorEntitiesCollector(
    std::shared_ptr<ExecutorNotifyWaitable> notify_waitable);

  RCLCPP_PUBLIC
  ~ExecutorEntitiesCollector();


  bool has_pending() const;


  RCLCPP_PUBLIC
  void
  add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr);


  RCLCPP_PUBLIC
  void
  remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr);


  RCLCPP_PUBLIC
  void
  add_callback_group(rclcpp::CallbackGroup::SharedPtr group_ptr);


  RCLCPP_PUBLIC
  void
  remove_callback_group(rclcpp::CallbackGroup::SharedPtr group_ptr);


  RCLCPP_PUBLIC
  std::vector<rclcpp::CallbackGroup::WeakPtr>
  get_all_callback_groups() const;


  RCLCPP_PUBLIC
  std::vector<rclcpp::CallbackGroup::WeakPtr>
  get_manually_added_callback_groups() const;


  RCLCPP_PUBLIC
  std::vector<rclcpp::CallbackGroup::WeakPtr>
  get_automatically_added_callback_groups() const;


  RCLCPP_PUBLIC
  void
  update_collections();

protected:
  using NodeCollection = std::set<
    rclcpp::node_interfaces::NodeBaseInterface::WeakPtr,
    std::owner_less<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>>;

  using CallbackGroupCollection = std::set<
    rclcpp::CallbackGroup::WeakPtr,
    std::owner_less<rclcpp::CallbackGroup::WeakPtr>>;

  using WeakNodesToGuardConditionsMap = std::map<
    rclcpp::node_interfaces::NodeBaseInterface::WeakPtr,
    rclcpp::GuardCondition::WeakPtr,
    std::owner_less<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>>;

  using WeakGroupsToGuardConditionsMap = std::map<
    rclcpp::CallbackGroup::WeakPtr,
    rclcpp::GuardCondition::WeakPtr,
    std::owner_less<rclcpp::CallbackGroup::WeakPtr>>;


  RCLCPP_PUBLIC
  NodeCollection::iterator
  remove_weak_node(NodeCollection::iterator weak_node) RCPPUTILS_TSA_REQUIRES(mutex_);


  RCLCPP_PUBLIC
  CallbackGroupCollection::iterator
  remove_weak_callback_group(
    CallbackGroupCollection::iterator weak_group_it,
    CallbackGroupCollection & collection) RCPPUTILS_TSA_REQUIRES(mutex_);


  RCLCPP_PUBLIC
  void
  add_callback_group_to_collection(
    rclcpp::CallbackGroup::SharedPtr group_ptr,
    CallbackGroupCollection & collection)  RCPPUTILS_TSA_REQUIRES(mutex_);

  RCLCPP_PUBLIC
  void
  process_queues() RCPPUTILS_TSA_REQUIRES(mutex_);

  RCLCPP_PUBLIC
  void
  add_automatically_associated_callback_groups(
    const NodeCollection & nodes_to_check) RCPPUTILS_TSA_REQUIRES(mutex_);

  RCLCPP_PUBLIC
  void
  prune_invalid_nodes_and_groups() RCPPUTILS_TSA_REQUIRES(mutex_);

  mutable std::mutex mutex_;

  CallbackGroupCollection manually_added_groups_ RCPPUTILS_TSA_GUARDED_BY(mutex_);

  CallbackGroupCollection automatically_added_groups_ RCPPUTILS_TSA_GUARDED_BY(mutex_);

  NodeCollection weak_nodes_ RCPPUTILS_TSA_GUARDED_BY(mutex_);

  WeakNodesToGuardConditionsMap weak_nodes_to_guard_conditions_ RCPPUTILS_TSA_GUARDED_BY(mutex_);

  WeakGroupsToGuardConditionsMap weak_groups_to_guard_conditions_ RCPPUTILS_TSA_GUARDED_BY(mutex_);

  NodeCollection pending_added_nodes_ RCPPUTILS_TSA_GUARDED_BY(mutex_);

  NodeCollection pending_removed_nodes_ RCPPUTILS_TSA_GUARDED_BY(mutex_);

  CallbackGroupCollection pending_manually_added_groups_ RCPPUTILS_TSA_GUARDED_BY(mutex_);

  CallbackGroupCollection pending_manually_removed_groups_ RCPPUTILS_TSA_GUARDED_BY(mutex_);

  std::shared_ptr<ExecutorNotifyWaitable> notify_waitable_;
};
}  // namespace executors
}  // namespace rclcpp
//
#endif  // RCLCPP__EXECUTORS__EXECUTOR_ENTITIES_COLLECTOR_HPP_