Program Listing for File time_source.hpp
↰ Return to documentation for file (include/rclcpp/time_source.hpp
)
// Copyright 2017 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__TIME_SOURCE_HPP_
#define RCLCPP__TIME_SOURCE_HPP_
#include <memory>
#include <vector>
#include "rcl/time.h"
#include "builtin_interfaces/msg/time.hpp"
#include "rosgraph_msgs/msg/clock.hpp"
#include "rcl_interfaces/msg/parameter_event.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/executors.hpp"
#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
namespace rclcpp
{
class Clock;
class TimeSource
{
public:
RCLCPP_PUBLIC
explicit TimeSource(
rclcpp::Node::SharedPtr node,
const rclcpp::QoS & qos = rclcpp::ClockQoS(),
bool use_clock_thread = true);
RCLCPP_PUBLIC
explicit TimeSource(
const rclcpp::QoS & qos = rclcpp::ClockQoS(),
bool use_clock_thread = true);
// The TimeSource is uncopyable
TimeSource(const TimeSource &) = delete;
TimeSource & operator=(const TimeSource &) = delete;
// The TimeSource is moveable
TimeSource(TimeSource &&) = default;
TimeSource & operator=(TimeSource &&) = default;
RCLCPP_PUBLIC
void attachNode(rclcpp::Node::SharedPtr node);
RCLCPP_PUBLIC
void attachNode(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface,
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface);
RCLCPP_PUBLIC
void detachNode();
RCLCPP_PUBLIC
void attachClock(rclcpp::Clock::SharedPtr clock);
RCLCPP_PUBLIC
void detachClock(rclcpp::Clock::SharedPtr clock);
RCLCPP_PUBLIC
bool get_use_clock_thread();
RCLCPP_PUBLIC
void set_use_clock_thread(bool use_clock_thread);
RCLCPP_PUBLIC
bool clock_thread_is_joinable();
RCLCPP_PUBLIC
~TimeSource();
private:
class NodeState;
std::shared_ptr<NodeState> node_state_;
// Preserve the arguments received by the constructor for reuse at runtime
bool constructed_use_clock_thread_;
rclcpp::QoS constructed_qos_;
};
} // namespace rclcpp
#endif // RCLCPP__TIME_SOURCE_HPP_