Program Listing for File executor_notify_waitable.hpp

Return to documentation for file (include/rclcpp/executors/executor_notify_waitable.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_NOTIFY_WAITABLE_HPP_
#define RCLCPP__EXECUTORS__EXECUTOR_NOTIFY_WAITABLE_HPP_

#include <functional>
#include <memory>
#include <mutex>
#include <set>

#include "rclcpp/guard_condition.hpp"
#include "rclcpp/waitable.hpp"

namespace rclcpp
{
namespace executors
{

class ExecutorNotifyWaitable : public rclcpp::Waitable
{
public:
  RCLCPP_SMART_PTR_DEFINITIONS(ExecutorNotifyWaitable)

  // Constructor
  RCLCPP_PUBLIC
  explicit ExecutorNotifyWaitable(std::function<void(void)> on_execute_callback = {});

  // Destructor
  RCLCPP_PUBLIC
  ~ExecutorNotifyWaitable() override = default;

  RCLCPP_PUBLIC
  ExecutorNotifyWaitable(ExecutorNotifyWaitable & other);

  RCLCPP_PUBLIC
  ExecutorNotifyWaitable & operator=(ExecutorNotifyWaitable & other);


  RCLCPP_PUBLIC
  void
  add_to_wait_set(rcl_wait_set_t & wait_set) override;


  RCLCPP_PUBLIC
  bool
  is_ready(const rcl_wait_set_t & wait_set) override;


  RCLCPP_PUBLIC
  void
  execute(const std::shared_ptr<void> & data) override;


  RCLCPP_PUBLIC
  std::shared_ptr<void>
  take_data() override;


  RCLCPP_PUBLIC
  std::shared_ptr<void>
  take_data_by_entity_id(size_t id) override;


  RCLCPP_PUBLIC
  void
  set_on_ready_callback(std::function<void(size_t, int)> callback) override;


  RCLCPP_PUBLIC
  void
  add_guard_condition(rclcpp::GuardCondition::WeakPtr guard_condition);


  RCLCPP_PUBLIC
  void
  clear_on_ready_callback() override;


  RCLCPP_PUBLIC
  void
  remove_guard_condition(rclcpp::GuardCondition::WeakPtr weak_guard_condition);


  RCLCPP_PUBLIC
  size_t
  get_number_of_ready_guard_conditions() override;

private:
  std::function<void(void)> execute_callback_;

  std::mutex guard_condition_mutex_;

  std::function<void(size_t)> on_ready_callback_;

  std::set<rclcpp::GuardCondition::WeakPtr,
    std::owner_less<rclcpp::GuardCondition::WeakPtr>> notify_guard_conditions_;
};

}  // namespace executors
}  // namespace rclcpp

#endif  // RCLCPP__EXECUTORS__EXECUTOR_NOTIFY_WAITABLE_HPP_