Program Listing for File logger.hpp

Return to documentation for file (include/rclcpp/logger.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__LOGGER_HPP_
#define RCLCPP__LOGGER_HPP_

#include <memory>
#include <string>

#include "rclcpp/visibility_control.hpp"

#include "rcl/node.h"
#include "rcutils/logging.h"
#include "rcpputils/filesystem_helper.hpp"

// TODO(dhood): determine this automatically from `RCLCPP_LOG_MIN_SEVERITY`
#ifndef RCLCPP_LOGGING_ENABLED
#define RCLCPP_LOGGING_ENABLED 1
#endif

namespace rclcpp
{

// Forward declaration is used for friend statement.
namespace node_interfaces
{
class NodeLogging;
}

class Logger;


RCLCPP_PUBLIC
Logger
get_logger(const std::string & name);


RCLCPP_PUBLIC
Logger
get_node_logger(const rcl_node_t * node);


RCLCPP_PUBLIC
rcpputils::fs::path
get_logging_directory();

class Logger
{
public:
  enum class Level
  {
    Unset = RCUTILS_LOG_SEVERITY_UNSET,
    Debug = RCUTILS_LOG_SEVERITY_DEBUG,
    Info = RCUTILS_LOG_SEVERITY_INFO,
    Warn = RCUTILS_LOG_SEVERITY_WARN,
    Error = RCUTILS_LOG_SEVERITY_ERROR,
    Fatal = RCUTILS_LOG_SEVERITY_FATAL,
  };

private:
  friend Logger rclcpp::get_logger(const std::string & name);
  friend ::rclcpp::node_interfaces::NodeLogging;


  Logger()
  : name_(nullptr) {}


  explicit Logger(const std::string & name)
  : name_(new std::string(name)) {}

  std::shared_ptr<const std::string> name_;

public:
  RCLCPP_PUBLIC
  Logger(const Logger &) = default;


  RCLCPP_PUBLIC
  const char *
  get_name() const
  {
    if (!name_) {
      return nullptr;
    }
    return name_->c_str();
  }


  RCLCPP_PUBLIC
  Logger
  get_child(const std::string & suffix)
  {
    if (!name_) {
      return Logger();
    }
    return Logger(*name_ + "." + suffix);
  }


  RCLCPP_PUBLIC
  void
  set_level(Level level);
};

}  // namespace rclcpp

#endif  // RCLCPP__LOGGER_HPP_