Program Listing for File waitable.hpp
↰ Return to documentation for file (include/rclcpp/waitable.hpp
)
// Copyright 2018 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__WAITABLE_HPP_
#define RCLCPP__WAITABLE_HPP_
#include <atomic>
#include <functional>
#include <memory>
#include "rclcpp/macros.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rcl/wait.h"
namespace rclcpp
{
class Waitable
{
public:
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(Waitable)
RCLCPP_PUBLIC
virtual ~Waitable() = default;
RCLCPP_PUBLIC
virtual
size_t
get_number_of_ready_subscriptions();
RCLCPP_PUBLIC
virtual
size_t
get_number_of_ready_timers();
RCLCPP_PUBLIC
virtual
size_t
get_number_of_ready_clients();
RCLCPP_PUBLIC
virtual
size_t
get_number_of_ready_events();
RCLCPP_PUBLIC
virtual
size_t
get_number_of_ready_services();
RCLCPP_PUBLIC
virtual
size_t
get_number_of_ready_guard_conditions();
RCLCPP_PUBLIC
virtual
void
add_to_wait_set(rcl_wait_set_t * wait_set) = 0;
RCLCPP_PUBLIC
virtual
bool
is_ready(rcl_wait_set_t * wait_set) = 0;
RCLCPP_PUBLIC
virtual
std::shared_ptr<void>
take_data() = 0;
RCLCPP_PUBLIC
virtual
std::shared_ptr<void>
take_data_by_entity_id(size_t id);
RCLCPP_PUBLIC
virtual
void
execute(std::shared_ptr<void> & data) = 0;
RCLCPP_PUBLIC
bool
exchange_in_use_by_wait_set_state(bool in_use_state);
RCLCPP_PUBLIC
virtual
void
set_on_ready_callback(std::function<void(size_t, int)> callback);
RCLCPP_PUBLIC
virtual
void
clear_on_ready_callback();
private:
std::atomic<bool> in_use_by_wait_set_{false};
}; // class Waitable
} // namespace rclcpp
#endif // RCLCPP__WAITABLE_HPP_