Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(autoware_utils_system): split package #38

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 0 additions & 3 deletions autoware_utils/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -52,9 +52,6 @@ The ROS module provides utilities for working with ROS messages and nodes:

The system module provides low-level utilities for performance monitoring and error handling:

- **`backtrace.hpp`**: Prints backtraces for debugging.
- **`lru_cache.hpp`**: Implements an LRU (Least Recently Used) cache.
- **`stop_watch.hpp`**: Measures elapsed time for profiling.
- **`time_keeper.hpp`**: Tracks and reports the processing time of various functions.

## Usage
Expand Down
13 changes: 8 additions & 5 deletions autoware_utils/include/autoware_utils/system/backtrace.hpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 Tier IV, Inc.
// Copyright 2025 The Autoware Contributors
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -15,11 +15,14 @@
#ifndef AUTOWARE_UTILS__SYSTEM__BACKTRACE_HPP_
#define AUTOWARE_UTILS__SYSTEM__BACKTRACE_HPP_

namespace autoware_utils
{
// NOLINTBEGIN(build/namespaces, whitespace/line_length)
// clang-format off

void print_backtrace();
#pragma message("#include <autoware_utils/system/backtrace.hpp> is deprecated. Use #include <autoware_utils_system/backtrace.hpp> instead.")
#include <autoware_utils_system/backtrace.hpp>
namespace autoware_utils { using namespace autoware_utils_system; }

} // namespace autoware_utils
// clang-format on
// NOLINTEND

#endif // AUTOWARE_UTILS__SYSTEM__BACKTRACE_HPP_
132 changes: 9 additions & 123 deletions autoware_utils/include/autoware_utils/system/lru_cache.hpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2024 TIER IV, Inc.
// Copyright 2025 The Autoware Contributors
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -11,132 +11,18 @@
// 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 AUTOWARE_UTILS__SYSTEM__LRU_CACHE_HPP_
#define AUTOWARE_UTILS__SYSTEM__LRU_CACHE_HPP_

#include <cstddef>
#include <list>
#include <optional>
#include <unordered_map>
#include <utility>

namespace autoware_utils
{

/**
* @brief A template class for LRU (Least Recently Used) Cache.
*
* This class implements a simple LRU cache using a combination of a list and a hash map.
*
* @tparam Key The type of keys.
* @tparam Value The type of values.
* @tparam Map The type of underlying map, defaulted to std::unordered_map.
*/
template <typename Key, typename Value, template <typename...> class Map = std::unordered_map>
class LRUCache
{
private:
size_t capacity_; ///< The maximum capacity of the cache.
std::list<std::pair<Key, Value>> cache_list_; ///< List to maintain the order of elements.
Map<Key, typename std::list<std::pair<Key, Value>>::iterator>
cache_map_; ///< Map for fast access to elements.

public:
/**
* @brief Construct a new LRUCache object.
*
* @param size The capacity of the cache.
*/
explicit LRUCache(size_t size) : capacity_(size) {}

/**
* @brief Get the capacity of the cache.
*
* @return The capacity of the cache.
*/
[[nodiscard]] size_t capacity() const { return capacity_; }

/**
* @brief Insert a key-value pair into the cache.
*
* If the key already exists, its value is updated and it is moved to the front.
* If the cache exceeds its capacity, the least recently used element is removed.
*
* @param key The key to insert.
* @param value The value to insert.
*/
void put(const Key & key, const Value & value)
{
auto it = cache_map_.find(key);
if (it != cache_map_.end()) {
cache_list_.erase(it->second);
}
cache_list_.push_front({key, value});
cache_map_[key] = cache_list_.begin();

if (cache_map_.size() > capacity_) {
auto last = cache_list_.back();
cache_map_.erase(last.first);
cache_list_.pop_back();
}
}

/**
* @brief Retrieve a value from the cache.
*
* If the key does not exist in the cache, std::nullopt is returned.
* If the key exists, the value is returned and the element is moved to the front.
*
* @param key The key to retrieve.
* @return The value associated with the key, or std::nullopt if the key does not exist.
*/
std::optional<Value> get(const Key & key)
{
auto it = cache_map_.find(key);
if (it == cache_map_.end()) {
return std::nullopt;
}
cache_list_.splice(cache_list_.begin(), cache_list_, it->second);
return it->second->second;
}

/**
* @brief Clear the cache.
*
* This removes all elements from the cache.
*/
void clear()
{
cache_list_.clear();
cache_map_.clear();
}

/**
* @brief Get the current size of the cache.
*
* @return The number of elements in the cache.
*/
[[nodiscard]] size_t size() const { return cache_map_.size(); }

/**
* @brief Check if the cache is empty.
*
* @return True if the cache is empty, false otherwise.
*/
[[nodiscard]] bool empty() const { return cache_map_.empty(); }
// NOLINTBEGIN(build/namespaces, whitespace/line_length)
// clang-format off

/**
* @brief Check if a key exists in the cache.
*
* @param key The key to check.
* @return True if the key exists, false otherwise.
*/
[[nodiscard]] bool contains(const Key & key) const
{
return cache_map_.find(key) != cache_map_.end();
}
};
#pragma message("#include <autoware_utils/system/lru_cache.hpp> is deprecated. Use #include <autoware_utils_system/lru_cache.hpp> instead.")
#include <autoware_utils_system/lru_cache.hpp>
namespace autoware_utils { using namespace autoware_utils_system; }

} // namespace autoware_utils
// clang-format on
// NOLINTEND

#endif // AUTOWARE_UTILS__SYSTEM__LRU_CACHE_HPP_
51 changes: 8 additions & 43 deletions autoware_utils/include/autoware_utils/system/stop_watch.hpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.
// Copyright 2025 The Autoware Contributors
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -15,49 +15,14 @@
#ifndef AUTOWARE_UTILS__SYSTEM__STOP_WATCH_HPP_
#define AUTOWARE_UTILS__SYSTEM__STOP_WATCH_HPP_

#include <chrono>
#include <string>
#include <unordered_map>
// NOLINTBEGIN(build/namespaces, whitespace/line_length)
// clang-format off

namespace autoware_utils
{
template <
class OutputUnit = std::chrono::seconds, class InternalUnit = std::chrono::microseconds,
class Clock = std::chrono::steady_clock>
class StopWatch
{
public:
StopWatch() { tic(default_name); }
#pragma message("#include <autoware_utils/system/stop_watch.hpp> is deprecated. Use #include <autoware_utils_system/stop_watch.hpp> instead.")
#include <autoware_utils_system/stop_watch.hpp>
namespace autoware_utils { using namespace autoware_utils_system; }

void tic(const std::string & name = default_name) { t_start_[name] = Clock::now(); }

void tic(const char * name) { tic(std::string(name)); }

double toc(const std::string & name, const bool reset = false)
{
const auto t_start = t_start_.at(name);
const auto t_end = Clock::now();
const auto duration = std::chrono::duration_cast<InternalUnit>(t_end - t_start).count();

if (reset) {
t_start_[name] = Clock::now();
}

const auto one_sec = std::chrono::duration_cast<InternalUnit>(OutputUnit(1)).count();

return static_cast<double>(duration) / one_sec;
}

double toc(const char * name, const bool reset = false) { return toc(std::string(name), reset); }

double toc(const bool reset = false) { return toc(default_name, reset); }

private:
using Time = std::chrono::time_point<Clock>;
static constexpr const char * default_name{"__auto__"};

std::unordered_map<std::string, Time> t_start_;
};
} // namespace autoware_utils
// clang-format on
// NOLINTEND

#endif // AUTOWARE_UTILS__SYSTEM__STOP_WATCH_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,7 @@
#ifndef AUTOWARE_UTILS__SYSTEM__TIME_KEEPER_HPP_
#define AUTOWARE_UTILS__SYSTEM__TIME_KEEPER_HPP_

#include "autoware_utils/system/stop_watch.hpp"

#include <autoware_utils_system/stop_watch.hpp>
#include <rclcpp/publisher.hpp>

#include <autoware_internal_debug_msgs/msg/processing_time_node.hpp>
Expand Down Expand Up @@ -173,7 +172,7 @@ class TimeKeeper
current_time_node_; //!< Shared pointer to the current time node
std::shared_ptr<ProcessingTimeNode> root_node_; //!< Shared pointer to the root time node
std::thread::id root_node_thread_id_; //!< ID of the thread that started the tracking
autoware_utils::StopWatch<
autoware_utils_system::StopWatch<
std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock>
stop_watch_; //!< StopWatch object for tracking the processing time

Expand Down
1 change: 1 addition & 0 deletions autoware_utils/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
<depend>autoware_utils_geometry</depend>
<depend>autoware_utils_math</depend>
<depend>autoware_utils_pcl</depend>
<depend>autoware_utils_system</depend>
<depend>autoware_utils_visualization</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>builtin_interfaces</depend>
Expand Down
16 changes: 16 additions & 0 deletions autoware_utils_system/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
cmake_minimum_required(VERSION 3.14)
project(autoware_utils_system)

find_package(autoware_cmake REQUIRED)
autoware_package()

ament_auto_add_library(${PROJECT_NAME} SHARED
"src/backtrace.cpp"
)

if(BUILD_TESTING)
file(GLOB_RECURSE test_files test/*.cpp)
ament_auto_add_gtest(test_${PROJECT_NAME} ${test_files})
endif()

ament_auto_package()
13 changes: 13 additions & 0 deletions autoware_utils_system/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
# autoware_utils_system

## Overview

The **autoware_utils** library is a comprehensive toolkit designed to facilitate the development of autonomous driving applications.
This package provides essential utilities for system.
It is extensively used in the Autoware project to handle common tasks such as performance monitoring and error handling.

## Design

- **`backtrace.hpp`**: Prints backtraces for debugging.
- **`lru_cache.hpp`**: Implements an LRU (Least Recently Used) cache.
- **`stop_watch.hpp`**: Measures elapsed time for profiling.
25 changes: 25 additions & 0 deletions autoware_utils_system/include/autoware_utils_system/backtrace.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
// Copyright 2023 Tier IV, 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 AUTOWARE_UTILS_SYSTEM__BACKTRACE_HPP_
#define AUTOWARE_UTILS_SYSTEM__BACKTRACE_HPP_

namespace autoware_utils_system
{

void print_backtrace();

} // namespace autoware_utils_system

#endif // AUTOWARE_UTILS_SYSTEM__BACKTRACE_HPP_
Loading