Program Listing for File context.hpp

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

// Copyright 2014 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__CONTEXT_HPP_
#define RCLCPP__CONTEXT_HPP_

#include <condition_variable>
#include <functional>
#include <memory>
#include <mutex>
#include <string>
#include <typeindex>
#include <typeinfo>
#include <unordered_map>
#include <unordered_set>
#include <utility>
#include <vector>
#include <stdexcept>

#include "rcl/context.h"
#include "rcl/guard_condition.h"
#include "rcl/wait.h"
#include "rclcpp/init_options.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/visibility_control.hpp"

namespace rclcpp
{

class ContextAlreadyInitialized : public std::runtime_error
{
public:
  ContextAlreadyInitialized()
  : std::runtime_error("context is already initialized") {}
};

class WeakContextsWrapper;

class ShutdownCallbackHandle
{
  friend class Context;

public:
  using ShutdownCallbackType = std::function<void ()>;

private:
  std::weak_ptr<ShutdownCallbackType> callback;
};

using OnShutdownCallbackHandle = ShutdownCallbackHandle;
using PreShutdownCallbackHandle = ShutdownCallbackHandle;


class Context : public std::enable_shared_from_this<Context>
{
public:
  RCLCPP_SMART_PTR_DEFINITIONS(Context)


  RCLCPP_PUBLIC
  Context();

  RCLCPP_PUBLIC
  virtual
  ~Context();


  RCLCPP_PUBLIC
  virtual
  void
  init(
    int argc,
    char const * const * argv,
    const rclcpp::InitOptions & init_options = rclcpp::InitOptions());


  RCLCPP_PUBLIC
  bool
  is_valid() const;

  RCLCPP_PUBLIC
  const rclcpp::InitOptions &
  get_init_options() const;

  RCLCPP_PUBLIC
  rclcpp::InitOptions
  get_init_options();

  RCLCPP_PUBLIC
  size_t
  get_domain_id() const;


  RCLCPP_PUBLIC
  std::string
  shutdown_reason() const;


  RCLCPP_PUBLIC
  virtual
  bool
  shutdown(const std::string & reason);

  using OnShutdownCallback = OnShutdownCallbackHandle::ShutdownCallbackType;


  RCLCPP_PUBLIC
  virtual
  OnShutdownCallback
  on_shutdown(OnShutdownCallback callback);


  RCLCPP_PUBLIC
  virtual
  OnShutdownCallbackHandle
  add_on_shutdown_callback(OnShutdownCallback callback);


  RCLCPP_PUBLIC
  virtual
  bool
  remove_on_shutdown_callback(const OnShutdownCallbackHandle & callback_handle);

  using PreShutdownCallback = PreShutdownCallbackHandle::ShutdownCallbackType;


  RCLCPP_PUBLIC
  virtual
  PreShutdownCallbackHandle
  add_pre_shutdown_callback(PreShutdownCallback callback);


  RCLCPP_PUBLIC
  virtual
  bool
  remove_pre_shutdown_callback(const PreShutdownCallbackHandle & callback_handle);


  RCLCPP_PUBLIC
  std::vector<OnShutdownCallback>
  get_on_shutdown_callbacks() const;


  RCLCPP_PUBLIC
  std::vector<PreShutdownCallback>
  get_pre_shutdown_callbacks() const;

  RCLCPP_PUBLIC
  std::shared_ptr<rcl_context_t>
  get_rcl_context();


  RCLCPP_PUBLIC
  bool
  sleep_for(const std::chrono::nanoseconds & nanoseconds);

  RCLCPP_PUBLIC
  virtual
  void
  interrupt_all_sleep_for();

  template<typename SubContext, typename ... Args>
  std::shared_ptr<SubContext>
  get_sub_context(Args && ... args)
  {
    std::lock_guard<std::recursive_mutex> lock(sub_contexts_mutex_);

    std::type_index type_i(typeid(SubContext));
    std::shared_ptr<SubContext> sub_context;
    auto it = sub_contexts_.find(type_i);
    if (it == sub_contexts_.end()) {
      // It doesn't exist yet, make it
      sub_context = std::shared_ptr<SubContext>(
        new SubContext(std::forward<Args>(args) ...),
        [](SubContext * sub_context_ptr) {
          delete sub_context_ptr;
        });
      sub_contexts_[type_i] = sub_context;
    } else {
      // It exists, get it out and cast it.
      sub_context = std::static_pointer_cast<SubContext>(it->second);
    }
    return sub_context;
  }

protected:
  // Called by constructor and destructor to clean up by finalizing the
  // shutdown rcl context and preparing for a new init cycle.
  RCLCPP_PUBLIC
  virtual
  void
  clean_up();

private:
  RCLCPP_DISABLE_COPY(Context)

  // This mutex is recursive so that the destructor can ensure atomicity
  // between is_initialized and shutdown.
  mutable std::recursive_mutex init_mutex_;
  std::shared_ptr<rcl_context_t> rcl_context_;
  rclcpp::InitOptions init_options_;
  std::string shutdown_reason_;

  // Keep shared ownership of the global logging mutex.
  std::shared_ptr<std::recursive_mutex> logging_mutex_;

  std::unordered_map<std::type_index, std::shared_ptr<void>> sub_contexts_;
  // This mutex is recursive so that the constructor of a sub context may
  // attempt to acquire another sub context.
  std::recursive_mutex sub_contexts_mutex_;

  std::unordered_set<std::shared_ptr<OnShutdownCallback>> on_shutdown_callbacks_;
  mutable std::mutex on_shutdown_callbacks_mutex_;

  std::unordered_set<std::shared_ptr<PreShutdownCallback>> pre_shutdown_callbacks_;
  mutable std::mutex pre_shutdown_callbacks_mutex_;

  std::condition_variable interrupt_condition_variable_;
  std::mutex interrupt_mutex_;

  std::shared_ptr<WeakContextsWrapper> weak_contexts_;

  enum class ShutdownType
  {
    pre_shutdown,
    on_shutdown
  };

  using ShutdownCallback = ShutdownCallbackHandle::ShutdownCallbackType;

  RCLCPP_LOCAL
  ShutdownCallbackHandle
  add_shutdown_callback(
    ShutdownType shutdown_type,
    ShutdownCallback callback);

  RCLCPP_LOCAL
  bool
  remove_shutdown_callback(
    ShutdownType shutdown_type,
    const ShutdownCallbackHandle & callback_handle);

  std::vector<rclcpp::Context::ShutdownCallback>
  get_shutdown_callback(ShutdownType shutdown_type) const;
};


RCLCPP_PUBLIC
std::vector<Context::SharedPtr>
get_contexts();

}  // namespace rclcpp

#endif  // RCLCPP__CONTEXT_HPP_