Package Summary
Tags | No category tags. |
Version | 0.43.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-04-03 |
Dev Status | UNMAINTAINED |
CI status | No Continuous Integration |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Takamasa Horibe
- Takayuki Murooka
- Mamoru Sobue
Authors
autoware_universe_utils
Purpose
This package contains many common functions used by other packages, so please refer to them as needed.
For developers
autoware_universe_utils.hpp
header file was removed because the source files that directly/indirectly include this file took a long time for preprocessing.
autoware::universe_utils
systems
autoware::universe_utils::TimeKeeper
Constructor
template <typename... Reporters>
explicit TimeKeeper(Reporters... reporters);
- Initializes the
TimeKeeper
with a list of reporters.
Methods
-
void add_reporter(std::ostream * os);
- Adds a reporter to output processing times to an
ostream
. -
os
: Pointer to theostream
object.
- Adds a reporter to output processing times to an
-
void add_reporter(rclcpp::Publisher<ProcessingTimeDetail>::SharedPtr publisher);
- Adds a reporter to publish processing times to an
rclcpp
publisher. -
publisher
: Shared pointer to therclcpp
publisher.
- Adds a reporter to publish processing times to an
-
void add_reporter(rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher);
- Adds a reporter to publish processing times to an
rclcpp
publisher withstd_msgs::msg::String
. -
publisher
: Shared pointer to therclcpp
publisher.
- Adds a reporter to publish processing times to an
-
void start_track(const std::string & func_name);
- Starts tracking the processing time of a function.
-
func_name
: Name of the function to be tracked.
-
void end_track(const std::string & func_name);
- Ends tracking the processing time of a function.
-
func_name
: Name of the function to end tracking.
-
void comment(const std::string & comment);
- Adds a comment to the current function being tracked.
-
comment
: Comment to be added.
Note
- It’s possible to start and end time measurements using
start_track
andend_track
as shown below:
time_keeper.start_track("example_function");
// Your function code here
time_keeper.end_track("example_function");
- For safety and to ensure proper tracking, it is recommended to use
ScopedTimeTrack
.
Example
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>
#include <chrono>
#include <iostream>
#include <memory>
#include <thread>
class ExampleNode : public rclcpp::Node
{
public:
ExampleNode() : Node("time_keeper_example")
{
publisher_ =
create_publisher<autoware::universe_utils::ProcessingTimeDetail>("processing_time", 1);
time_keeper_ = std::make_shared<autoware::universe_utils::TimeKeeper>(publisher_, &std::cerr);
// You can also add a reporter later by add_reporter.
// time_keeper_->add_reporter(publisher_);
// time_keeper_->add_reporter(&std::cerr);
timer_ =
create_wall_timer(std::chrono::seconds(1), std::bind(&ExampleNode::func_a, this));
}
private:
std::shared_ptr<autoware::universe_utils::TimeKeeper> time_keeper_;
rclcpp::Publisher<autoware::universe_utils::ProcessingTimeDetail>::SharedPtr publisher_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_str_;
rclcpp::TimerBase::SharedPtr timer_;
void func_a()
{
// Start constructing ProcessingTimeTree (because func_a is the root function)
autoware::universe_utils::ScopedTimeTrack st("func_a", *time_keeper_);
std::this_thread::sleep_for(std::chrono::milliseconds(1));
time_keeper_->comment("This is a comment for func_a");
func_b();
// End constructing ProcessingTimeTree. After this, the tree will be reported (publishing
// message and outputting to std::cerr)
}
void func_b()
{
autoware::universe_utils::ScopedTimeTrack st("func_b", *time_keeper_);
std::this_thread::sleep_for(std::chrono::milliseconds(2));
time_keeper_->comment("This is a comment for func_b");
func_c();
}
void func_c()
{
autoware::universe_utils::ScopedTimeTrack st("func_c", *time_keeper_);
std::this_thread::sleep_for(std::chrono::milliseconds(3));
time_keeper_->comment("This is a comment for func_c");
}
};
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<ExampleNode>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
- Output (console)
==========================
func_a (6.243ms) : This is a comment for func_a
└── func_b (5.116ms) : This is a comment for func_b
└── func_c (3.055ms) : This is a comment for func_c
- Output (
ros2 topic echo /processing_time
)
---
nodes:
- id: 1
name: func_a
processing_time: 6.366
parent_id: 0
comment: This is a comment for func_a
- id: 2
name: func_b
processing_time: 5.237
parent_id: 1
comment: This is a comment for func_b
- id: 3
name: func_c
processing_time: 3.156
parent_id: 2
comment: This is a comment for func_c
autoware::universe_utils::ScopedTimeTrack
Description
Class for automatically tracking the processing time of a function within a scope.
Constructor
ScopedTimeTrack(const std::string & func_name, TimeKeeper & time_keeper);
-
func_name
: Name of the function to be tracked. -
time_keeper
: Reference to theTimeKeeper
object.
Destructor
~ScopedTimeTrack();
- Destroys the
ScopedTimeTrack
object, ending the tracking of the function.
Changelog for package autoware_universe_utils
0.43.0 (2025-03-21)
- Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
- chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
- fix(autoware_universe_utils): fix procedure to check if point is
on edge
(#10260)
- fix procedure to check if point is on edge
* add test cases ---------
- Contributors: Hayato Mizushima, Mitsuhiro Sakamoto, Yutaka Kondo
0.42.0 (2025-03-03)
- Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
- feat(autoware_vehicle_info_utils): replace autoware_universe_utils with autoware_utils (#10167)
- feat!: replace tier4_planning_msgs/PathWithLaneId with autoware_internal_planning_msgs/PathWithLaneId (#10023)
- test(autoware_universe_utils): make opencv_fast_atan2 test reproducible (#9728)
- feat(universe_utils): add Polygon Clipping implementation to do boolean operation on Polygons (XOR, OR, AND) (#8728) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>>
- Contributors: Fumiya Watanabe, Giovanni Muhammad Raditya, Max Schmeller, Ryohsuke Mitsudome
0.41.2 (2025-02-19)
- chore: bump version to 0.41.1 (#10088)
- Contributors: Ryohsuke Mitsudome
0.41.1 (2025-02-10)
0.41.0 (2025-01-29)
- Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
- refactor(autoware_universe_utils): add missing 's' in the class of diagnostics_interface (#9777)
- feat(behavior_path_planner): use autoware internal stamped
messages
(#9750)
- feat(behavior_path_planner): use autoware internal stamped messages
* fix universe_utils ---------
- feat!: move diagnostics_module from localization_util to
unverse_utils
(#9714)
- feat!: move diagnostics_module from localization_util to unverse_utils
- remove diagnostics module from localization_util
- style(pre-commit): autofix
- minor fix in pose_initializer
- add test
- style(pre-commit): autofix
- remove unnecessary declaration
- module -> interface
- remove unnecessary equal expression
- revert the remove of template function
- style(pre-commit): autofix
- use overload instead
* include what you use -- test_diagnostics_interface.cpp ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- fix(autoware_universe_utils): fix bug in test (#9710)
- Contributors: Fumiya Watanabe, Ryuta Kambe, Takayuki Murooka, kminoda
0.40.0 (2024-12-12)
- Merge branch 'main' into release-0.40.0
- Revert "chore(package.xml): bump version to 0.39.0 (#9587)" This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5.
- fix: fix ticket links in CHANGELOG.rst (#9588)
- chore(package.xml): bump version to 0.39.0
(#9587)
- chore(package.xml): bump version to 0.39.0
- fix: fix ticket links in CHANGELOG.rst
* fix: remove unnecessary diff ---------Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>
- fix: fix ticket links in CHANGELOG.rst (#9588)
- fix(cpplint): include what you use - common (#9564)
- feat(universe_utils): add extra info to time keeper warning (#9484) add extra info to time keeper warning
- refactor(evaluators, autoware_universe_utils): rename Stat class
to Accumulator and move it to autoware_universe_utils
(#9459)
- add Accumulator class to autoware_universe_utils
- use Accumulator on all evaluators.
- pre-commit
- found and fixed a bug. add more tests.
- pre-commit
* Update common/autoware_universe_utils/include/autoware/universe_utils/math/accumulator.hpp Co-authored-by: Kosuke Takeuchi <<kosuke.tnp@gmail.com>> ---------Co-authored-by: Kosuke Takeuchi <<kosuke.tnp@gmail.com>>
- 0.39.0
- update changelog
- Merge commit '6a1ddbd08bd' into release-0.39.0
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- fix(autoware_utils): address self-intersecting polygons in random_concave_generator and handle empty inners() during triangulation (#8995) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>>
- chore(package.xml): bump version to 0.38.0
(#9266)
(#9284)
- unify package.xml version to 0.37.0
- remove system_monitor/CHANGELOG.rst
- add changelog
* 0.38.0
- Contributors: Esteve Fernandez, Fumiya Watanabe, Giovanni Muhammad Raditya, Kem (TiankuiXian), M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, danielsanchezaran
0.39.0 (2024-11-25)
- Merge commit '6a1ddbd08bd' into release-0.39.0
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- fix(autoware_utils): address self-intersecting polygons in random_concave_generator and handle empty inners() during triangulation (#8995) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>>
- chore(package.xml): bump version to 0.38.0
(#9266)
(#9284)
- unify package.xml version to 0.37.0
- remove system_monitor/CHANGELOG.rst
- add changelog
* 0.38.0
- Contributors: Esteve Fernandez, Giovanni Muhammad Raditya, Yutaka Kondo
0.38.0 (2024-11-08)
- unify package.xml version to 0.37.0
- feat(autoware_pointcloud_preprocessor): distortion corrector node
update azimuth and distance
(#8380)
- feat: add option for updating distance and azimuth value
- chore: clean code
- chore: remove space
- chore: add documentation
- chore: fix docs
- feat: conversion formula implementation for degree, still need to change to rad
- chore: fix tests for AzimuthConversionExists function
- feat: add fastatan to utils
- feat: remove seperate sin, cos and use sin_and_cos function
- chore: fix readme
- chore: fix some grammar errors
- chore: fix spell error
- chore: set debug mode to false
- chore: set update_azimuth_and_distance default value to false
- chore: update readme
- chore: remove cout
- chore: add opencv license
- chore: fix grammar error
- style(pre-commit): autofix
- chore: add runtime error when azimuth conversion failed
- chore: change default pointcloud
- chore: change function name
- chore: move variables to structure
- chore: add random seed
- chore: rewrite get conversion function
- chore: fix opencv fast atan2 function
- chore: fix schema description
* Update sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp Co-authored-by: Max Schmeller <<6088931+mojomex@users.noreply.github.com>> * Update sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp Co-authored-by: Max Schmeller <<6088931+mojomex@users.noreply.github.com>>
- chore: move code to function for readability
- chore: simplify code
- chore: fix sentence, angle conversion
- chore: add more invalid condition
- chore: fix the string name to enum
- chore: remove runtime error
- chore: use optional for AngleConversion structure
- chore: fix bug and clean code
- chore: refactor the logic of calculating conversion
- chore: refactor function in unit test
- chore: RCLCPP_WARN_STREAM logging when failed to get angle conversion
- chore: improve normalize angle algorithm
- chore: improve multiple_of_90_degrees logic
- chore: add opencv license
- style(pre-commit): autofix
- chore: clean code
- chore: fix sentence
- style(pre-commit): autofix
- chore: add 0 0 0 points in test case
- chore: fix spell error
* Update common/autoware_universe_utils/NOTICE Co-authored-by: Max Schmeller <<6088931+mojomex@users.noreply.github.com>> * Update sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp Co-authored-by: Max Schmeller <<6088931+mojomex@users.noreply.github.com>> * Update sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp Co-authored-by: Max Schmeller <<6088931+mojomex@users.noreply.github.com>>
- chore: use constexpr for threshold
- chore: fix the path of license
- chore: explanation for failures
- chore: use throttle
- chore: fix empty pointcloud function
- refactor: change camel to snake case
* Update sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector_node.hpp Co-authored-by: Max Schmeller <<6088931+mojomex@users.noreply.github.com>> * Update sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector_node.hpp Co-authored-by: Max Schmeller <<6088931+mojomex@users.noreply.github.com>>
- style(pre-commit): autofix
* Update sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp Co-authored-by: Max Schmeller <<6088931+mojomex@users.noreply.github.com>>
- refactor: refactor virtual function in base class
- chore: fix test naming error
- chore: fix clang error
- chore: fix error
- chore: fix clangd
- chore: add runtime error if the setting is wrong
- chore: clean code
* Update sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp Co-authored-by: Max Schmeller <<6088931+mojomex@users.noreply.github.com>>
- style(pre-commit): autofix
- chore: fix unit test for runtime error
* Update sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md Co-authored-by: Kenzo Lobos Tsunekawa <<kenzo.lobos@tier4.jp>>
- chore: fix offset_rad_threshold
- chore: change pointer to reference
- chore: snake_case for unit test
- chore: fix refactor process twist and imu
- chore: fix abs and return type of matrix to tf2
- chore: fix grammar error
- chore: fix readme description
* chore: remove runtime error ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: Max Schmeller <<6088931+mojomex@users.noreply.github.com>> Co-authored-by: Kenzo Lobos Tsunekawa <<kenzo.lobos@tier4.jp>>
- fix(universe_utils): avoid test timeout (#8993) reduce number of polygons to be generated
- fix(autoware_universe_utils): fix unmatchedSuppression (#8986) fix:unmatchedSuppression
- refactor(universe_utils): eliminate dependence on Boost.Geometry
(#8965)
- add alt::Polygon2d -> Polygon2d conversion function
- migrate to alt geometry
- invert orientation of linked list
- suppress cppcheck unusedFunction error
* fix parameter to avoid confusion ---------
- feat(autoware_universe_utils): reduce dependence on Boost.Geometry
(#8592)
- add find_farthest()
- add simplify()
- add envelope()
- (WIP) add buffer()
- add Polygon2d class
- change input type of envelope()
- disable convexity check until correct() supports non-convex polygons
- add is_clockwise()
- make correct() support non-convex polygons
- fix test case
* Revert "(WIP) add buffer()" This reverts commit 123b0ba85ede5e558431a4336038c14023d1bef1. ---------
- refactor(universe_utils): remove raw pointers from the triangulation function (#8893)
- fix(autoware_pointcloud_preprocessor): static TF listener as Filter option (#8678)
- feat(universe_utils): add Triangulation (ear clipping)
implementation for 2D concave polygon with/without holes
(#8609)
- added random_concave_polygon and triangulation
- disable some test with GJK
- pre-commit fix
- fully fixed convexHull issue and styling fix
- fix conflict
- cleaning up the code
- cleanup the code
- cleanup the code
- fix spelling
- last cleanup
- more spellcheck fix
* more spellcheck fixes ---------Co-authored-by: Maxime CLEMENT <<maxime.clement@tier4.jp>>
- refactor(autoware_universe_utils): refactor Boost.Geometry
alternatives
(#8594)
- move alternatives to separate files
- style(pre-commit): autofix
* include missing headers ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- fix(autoware_universe_utils): fix unusedFunction (#8723) fix:unusedFunction
- feat(universe_utils): add SAT implementation for 2D convex polygon collision check (#8239)
- feat(autoware_universe_utils): add thread_id check to time_keeper (#8628) add thread_id check
- fix(autoware_universe_utils): fix unusedFunction (#8521) fix: unusedFunction
- feat(autoware_universe_utils): add LRU Cache (#8456)
- fix(autoware_universe_utils): fix memory leak of time_keeper (#8425) fix bug of time_keeper
- feat(autoware_universe_utils): reduce dependence on Boost.Geometry
(#7778)
- add within function
- return nullopt as is
- add disjoint function
- add polygon-and-polygon version of intersect function
- use intersect for disjoint
- add test case for disjoint
- checking intersection of edges is unnecessary
- return nullopt when no intersection point found
- add distance function
- add coveredBy function
- add point-polygon variant of distance function
- add isAbove function
- add divideBySegment function
- add convexHull function
- add correct function
- add area function
- change point type to tf2::Vector3
- simplify correct function
- push geometry types to namespace
- match the behavior of Boost.Geometry
- add test cases for benchmarking
- add headers for convex_hull()
- remove polygon-polygon intersect & disjoint function
- add intersects function
- add touches function
- add disjoint function
- minor fix
- change name Polygon to CvxPolygon
- change name CvxPolygon to ConvexPolygon
- rename intersect function and restore the original
- change function names to snake_case
- early return
- change point type from tf2::Vector3 to custom struct
- style(pre-commit): autofix
- use alt::Vector2d to represent point
- convert from boost before time measurement
- add header for std::move
- avoid using long
- convert from boost before time measurement
- add point-segment variant of touches function
- improve performance of point-polygon touches()
- improve performance of area()
- add note for class naming
- improve performance of covered_by()
- simplify within()
- improve performance of covered_by()
- improve performance of within()
- use operator[] instead of at()
- print point when covered_by() test failed
- avoid using hypot()
- improve performace of convex_hull()
- remove divide_by_segment() function
- fix test cases
- improve performance of touches()
- add test case for touches()
- improve performance of touches()
- change type alias PointList to Points2d
- add & fix vector size assertions
* define epsilon respectively ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: Satoshi OTA <<44889564+satoshi-ota@users.noreply.github.com>>
- fix(autoware_universe_utils): fix constParameterReference
(#8145)
- fix:constParameterReference
- fix:clang format
- fix:constParameterReference
* fix:clang format ---------
- perf(autoware_pointcloud_preprocessor): lazy & managed TF
listeners
(#8174)
- perf(autoware_pointcloud_preprocessor): lazy & managed TF listeners
- fix(autoware_pointcloud_preprocessor): param names & reverse frames transform logic
- fix(autoware_ground_segmentation): add missing TF listener
- feat(autoware_ground_segmentation): change to static TF buffer
- refactor(autoware_pointcloud_preprocessor): move StaticTransformListener to universe utils
- perf(autoware_universe_utils): skip redundant transform
- fix(autoware_universe_utils): change checks order
* doc(autoware_universe_utils): add docstring ---------
- refactor(autoware_universe_utils): changed the API to be more
intuitive and added documentation
(#7443)
- refactor(tier4_autoware_utils): Changed the API to be more intuitive and added documentation.
- use raw shared ptr in PollingPolicy::NEWEST
- update
- fix
* Update evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp Co-authored-by: danielsanchezaran <<daniel.sanchez@tier4.jp>> ---------Co-authored-by: danielsanchezaran <<daniel.sanchez@tier4.jp>>
- feat(universe_utils): add GJK implementation for 2D convex polygon collision check (#7853)
- feat(autoware_universe_utils): add comment function to
time_keeper
(#7991)
- update readme
- refactoring
- remove string reporter
- fix readme.md
- feat(autoware_universe_utils): add comment function to time_keeper
- remove comment from scoped time track
* modify readme ---------
- chore(autoware_universe_utils): update document
(#7907)
- update readme
- refactoring
- remove string reporter
- fix readme.md
- change node name of example
* update readme ---------
- fix(autoware_universe_utils): fix constParameterReference
(#7882)
- fix: constParameterReference
* fix: constParameterReference ---------
- feat(autoware_universe_utils): add TimeKeeper to track function's processing time (#7754)
- refactor(universe_utils/motion_utils)!: add autoware namespace (#7594)
- feat(autoware_universe_utils)!: rename from tier4_autoware_utils (#7538) Co-authored-by: kosuke55 <<kosuke.tnp@gmail.com>>
- Contributors: Amadeusz Szymko, Giovanni Muhammad Raditya, Kosuke Takeuchi, Maxime CLEMENT, Mitsuhiro Sakamoto, Nagi70, Takayuki Murooka, Yi-Hsiang Fang (Vivid), Yukinari Hisaki, Yutaka Kondo, kobayu858