Program Listing for File clock.hpp

Return to documentation for file (include/rclcpp/clock.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__CLOCK_HPP_
#define RCLCPP__CLOCK_HPP_

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

#include "rclcpp/contexts/default_context.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp/visibility_control.hpp"

#include "rcl/time.h"
#include "rcutils/time.h"
#include "rcutils/types/rcutils_ret.h"

namespace rclcpp
{

class TimeSource;

class JumpHandler
{
public:
  RCLCPP_SMART_PTR_DEFINITIONS(JumpHandler)

  using pre_callback_t = std::function<void ()>;
  using post_callback_t = std::function<void (const rcl_time_jump_t &)>;

  JumpHandler(
    pre_callback_t pre_callback,
    post_callback_t post_callback,
    const rcl_jump_threshold_t & threshold);

  pre_callback_t pre_callback;
  post_callback_t post_callback;
  rcl_jump_threshold_t notice_threshold;
};

class Clock
{
public:
  RCLCPP_SMART_PTR_DEFINITIONS(Clock)


  RCLCPP_PUBLIC
  explicit Clock(rcl_clock_type_t clock_type = RCL_SYSTEM_TIME);

  RCLCPP_PUBLIC
  ~Clock();

  RCLCPP_PUBLIC
  Time
  now();

  RCLCPP_PUBLIC
  bool
  sleep_until(
    Time until,
    Context::SharedPtr context = contexts::get_global_default_context());

  RCLCPP_PUBLIC
  bool
  sleep_for(
    Duration rel_time,
    Context::SharedPtr context = contexts::get_global_default_context());

  RCLCPP_PUBLIC
  bool
  started();

  RCLCPP_PUBLIC
  bool
  wait_until_started(Context::SharedPtr context = contexts::get_global_default_context());

  RCLCPP_PUBLIC
  bool
  wait_until_started(
    const rclcpp::Duration & timeout,
    Context::SharedPtr context = contexts::get_global_default_context(),
    const rclcpp::Duration & wait_tick_ns = rclcpp::Duration(0, static_cast<uint32_t>(1e7)));

  RCLCPP_PUBLIC
  bool
  ros_time_is_active();

  RCLCPP_PUBLIC
  rcl_clock_t *
  get_clock_handle() noexcept;

  RCLCPP_PUBLIC
  rcl_clock_type_t
  get_clock_type() const noexcept;

  RCLCPP_PUBLIC
  std::mutex &
  get_clock_mutex() noexcept;

  // Add a callback to invoke if the jump threshold is exceeded.
  RCLCPP_PUBLIC
  JumpHandler::SharedPtr
  create_jump_callback(
    JumpHandler::pre_callback_t pre_callback,
    JumpHandler::post_callback_t post_callback,
    const rcl_jump_threshold_t & threshold);

private:
  // Invoke time jump callback
  RCLCPP_PUBLIC
  static void
  on_time_jump(
    const rcl_time_jump_t * time_jump,
    bool before_jump,
    void * user_data);

  class Impl;

  std::shared_ptr<Impl> impl_;
};

}  // namespace rclcpp

#endif  // RCLCPP__CLOCK_HPP_