Package Summary
Tags | No category tags. |
Version | 0.44.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-04-25 |
Dev Status | UNKNOWN |
CI status | No Continuous Integration |
Released | UNRELEASED |
Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Maxime CLEMENT
- Kyoichi Sugahara
- Temkei Kem
Authors
- Maxime CLEMENT
Planning Evaluator
Purpose
This package provides nodes that generate various metrics to evaluate the quality of planning.
Metrics can be published in real time and saved to a JSON file when the node is shut down:
-
metrics_for_publish
:- Metrics listed in
metrics_for_publish
are calculated and published to the topic.
- Metrics listed in
-
metrics_for_output
:- Metrics listed in
metrics_for_output
are saved to a JSON file when the node shuts down (ifoutput_metrics
is set totrue
). - These metrics include statistics derived from
metrics_for_publish
and additional information such as parameters and descriptions.
- Metrics listed in
Metrics
All possible metrics are defined in the Metric
enumeration located in:
include/autoware/planning_evaluator/metrics/metric.hpp
include/autoware/planning_evaluator/metrics/output_metric.hpp
These files also provide string conversions and human-readable descriptions for use in output files.
Metric Classifications
By Data Type
-
Statistics-based Metrics:
- Calculated using
autoware_utils::Accumulator
, which tracks minimum, maximum, mean, and count values. - Sub-metrics:
/mean
,/min
,/max
, and/count
.
- Calculated using
-
Value-based Metrics:
- Metrics with a single value.
- Sub-metrics:
/value
. - Some metrics with older implementations use the statistics-based format of
/mean
,/min
,/max
, but all values are the same.
-
Count-based Metrics:
- Count occurrences of specific events over a time period.
- Sub-metrics:
/count
, or/count_in_duration
.
By Purpose
- Trajectory Metrics
- Trajectory Deviation Metrics
- Trajectory Stability Metrics
- Trajectory Obstacle Metrics
- Modified Goal Metrics
- Planning Factor Metrics
- Steering Metrics
- Blinker Metrics
- Other Information
Detailed Metrics
Trajectory Metrics
Evaluates the current trajectory T(0)
itself.
Metrics are calculated and published when a trajectory is received.
Implemented metrics
-
curvature
: Statistics of curvature at each trajectory point.- Sub-metrics to publish:
/mean
,/min
,/max
. - Sub-metrics to output: The same as above but take the published data as data point instead of each trajectory point.
- Sub-metrics to publish:
-
point_interval
: Statistics of distances between consecutive trajectory points.- Sub-metrics to publish:
/mean
,/min
,/max
. - Sub-metrics to output: The same as above but take the published data as data point instead of each trajectory point.
- Sub-metrics to publish:
-
relative_angle
: Statistics of angles between consecutive trajectory points.- Parameters:
trajectory.min_point_dist_m
(minimum distance between points). - Sub-metrics to publish:
/mean
,/min
,/max
. - Sub-metrics to output: The same as above but take the published data as data point instead of each trajectory point.
- Parameters:
-
resampled_relative_angle
: Similar torelative_angle
, but considers a point at a fixed distance (e.g., half the vehicle length) for angle calculation from the current point as the next point to calculate the relative angle, instead of using the immediately adjacent point. -
length
: Total trajectory length.- Sub-metrics: Value-based metric, but using the statistics-based format of
/mean
,/min
,/max
with the same value. - Sub-metrics to output:
/mean
,/min
,/max
for the published data.
- Sub-metrics: Value-based metric, but using the statistics-based format of
-
duration
: Expected driving time to travel the trajectory.- Sub-metrics: Value-based metric, but using the statistics-based format of
/mean
,/min
,/max
with the same value. - Sub-metrics to output:
/mean
,/min
,/max
for the published data.
- Sub-metrics: Value-based metric, but using the statistics-based format of
-
velocity
: Statistics of velocity at each trajectory point.- Sub-metrics to publish:
/mean
,/min
,/max
. - Sub-metrics to output: The same as above but take the published data as data point instead of each trajectory point.
- Sub-metrics to publish:
-
acceleration
: Statistics of acceleration at each trajectory point.- Sub-metrics to publish:
/mean
,/min
,/max
. - Sub-metrics to output: The same as above but take the published data as data point instead of each trajectory point.
- Sub-metrics to publish:
-
jerk
: Statistics of jerk at each trajectory point.- Sub-metrics to publish:
/mean
,/min
,/max
. - Sub-metrics to output: The same as above but take the published data as data point instead of each trajectory point.
- Sub-metrics to publish:
Trajectory Deviation Metrics
Evaluates the trajectory deviation by comparing the trajectory T(0)
and the reference trajectory.
Metrics are calculated and publish only when the node receives a trajectory.
The following information are used to calculate metrics:
- the trajectory
T(0)
. - the reference trajectory assumed to be used as the reference to plan
T(0)
.
Implemented metrics
-
lateral_deviation
: Statistics of the lateral deviation between trajectory points and the closest reference trajectory points.- Sub-metrics to publish:
/mean
,/min
,/max
. - Sub-metrics to output: The same as above but take the published data as data point instead of each trajectory point.
- Sub-metrics to publish:
-
yaw_deviation
: Statistics of the yaw deviation between trajectory points and the closest reference trajectory points.- Sub-metrics to publish:
/mean
,/min
,/max
. - Sub-metrics to output: The same as above but take the published data as data point instead of each trajectory point.
- Sub-metrics to publish:
-
velocity_deviation
: Statistics of the velocity deviation between trajectory points and the closest reference trajectory points.- Sub-metrics to publish:
/mean
,/min
,/max
. - Sub-metrics to output: The same as above but take the published data as data point instead of each trajectory point.
- Sub-metrics to publish:
Trajectory Stability Metrics
Evaluates the trajectory stability by comparing the trajectory T(0)
and previous trajectory T(-1)
.
Metrics are calculated and publish only when the node receives a trajectory.
The following information are used to calculate metrics:
- the trajectory
T(0)
itself. - the previous trajectory
T(-1)
. - the current ego odometry.
Implemented metrics
stability
: Statistics of the lateral deviation between T(0)
and T(-1)
within a lookahead duration and distance.
- Parameters:
trajectory.lookahead.max_time_s
,trajectory.lookahead.max_dist_m
. - Sub-metrics to publish:
/mean
,/min
,/max
. -
Sub-metrics to output: The same as above but take the published data as data point instead of each trajectory point.
-
stability_frechet
: Frechet distance betweenT(0)
andT(-1)
within a lookahead duration and distance.- Parameters: Same as
stability
. - Sub-metrics to publish:
/mean
,/min
,/max
. - Sub-metrics to output: The same as above but take the published data as data point instead of each trajectory point.
- Parameters: Same as
-
lateral_trajectory_displacement_local
: Absolute lateral displacement betweenT(0)
andT(-1)
at the ego position.- Sub-metrics to publish: Value-based metric, but using the statistics-based format.
- Sub-metrics to output:
/mean
,/min
,/max
for the published data.
-
lateral_trajectory_displacement_lookahead
: Statistics of absolute lateral displacement betweenT(0)
andT(-1)
within a lookahead duration. - Parameters:
trajectory.evaluation_time_s
. - Sub-metrics to publish:
/mean
,/min
,/max
. - Sub-metrics to output: The same as above but take the published data as data point instead of each trajectory point.
Trajectory Obstacle Metrics
Evaluate the safety of T(0)
with respect to obstacles.
Metrics are calculated and publish only when the node receives a trajectory.
The following information are used to calculate metrics:
- the trajectory
T(0)
. - the set of objects in the environment.
Implemented metrics
-
obstacle_distance
: Statistics of the distance between the centroid of each object and the closest trajectory point.- Sub-metrics to publish:
/mean
,/min
,/max
. - Sub-metrics to output: The same as above but take the published data as data point instead of each trajectory point.
- Sub-metrics to publish:
-
obstacle_ttc
: Statistics of the time-to-collision (TTC) for those objects near the trajectory.- Parameters:
obstacle.dist_thr_m
(distance threshold to consider the object as close to the trajectory). - Sub-metrics to publish:
/mean
,/min
,/max
. - Sub-metrics to output: The same as above but take the published data as data point instead of each trajectory point.
- Parameters:
Modified Goal Metrics
Evaluate deviations between the modified goal and the ego position.
Metrics are calculated and publish only when the node receives a modified goal message.
Implemented metrics
-
modified_goal_longitudinal_deviation
: Statistics of the longitudinal deviation between the modified goal and the current ego position.- Sub-metrics to publish: Value-based metric, but using the statics-based format.
- Sub-metrics to output:
/mean
,/min
,/max
for the published data.
-
modified_goal_lateral_deviation
: Statistics of the lateral deviation between the modified goal and the current ego position.- Sub-metrics to publish: Value-based metric, but using the statics-based format.
- Sub-metrics to output:
/mean
,/min
,/max
for the published data.
-
modified_goal_yaw_deviation
: Statistics of the yaw deviation between the modified goal and the current ego position.- Sub-metrics to publish: Value-based metric, but using the statics-based format.
- Sub-metrics to output:
/mean
,/min
,/max
for the published data.
Planning Factor Metrics
Evaluates the behavior of each planning module by checking planning factors.
Metrics are calculated and publish only when the node receives that planning factors published by each module.
The modules listed in the module_list
in the parameter file are evaluated.
Implemented metrics
-
stop_decision
: Evaluate stop decisions for each module.- Parameters:
-
stop_decision.time_count_threshold_s
: time threshold to count a stop decision as a new one. -
stop_decision.dist_count_threshold_m
: distance threshold to count a stop decision as a new one. -
stop_decision.topic_prefix
: topic prefix for planning factors -
stop_decision.module_list
: list of modules’ names to check, the{topic_prefix}/{module_name}
should be a valid topic.
-
- Sub-metrics to publish:
-
/{module_name}/keep_duration
(value-based): the time current stop decision keeps. -
/{module_name}/distance_to_stop
(value-based): the distance to the stop line. -
/{module_name}/count
(count-based): the stop decision index, in other words, the number of stop decisions made by the module.
-
- Sub-metrics to output:
-
/{module_name}/keep_duration/mean
,/{module_name}/keep_duration/min
,/{module_name}/keep_duration/max
: the statistics of the published keep_duration. -
/{module_name}/count
: the total number of stop decisions.
-
- Parameters:
-
abnormal_stop_decision
: Evaluate abnormal stop decisions for each module.- A stop decision is considered as abnormal if the ego cannot stop with the current velocity and the maximum deceleration limit.
- Parameters:
-
stop_decision.abnormal_deceleration_threshold_mps2
: maximum deceleration limit to consider the stop decision as abnormal. - Other parameters are shared with
stop_decision
.
-
- Sub-metrics to publish: The same as
stop_decision
. - Sub-metrics to output: The same as
stop_decision
.
Blinker Metrics
Evaluates the blinker status of the vehicle.
Metrics are calculated and publish only when the node receives a turn indicators report message.
Implemented metrics
-
blinker_change_count
: Count blinker status changes.- A change is counted when the blinker status transitions from off/left to right, or from off/right to left.
- Parameters:
-
blinker_change_count.window_duration_s
: duration to count the changes for publishing.
-
- Sub-metrics to publish:
/count_in_duration
. - Sub-metrics to output:
-
/count_in_duration/min
,/count_in_duration/max
,/count_in_duration/mean
: the statistics of the published keep_duration. -
/count
: total number of changes.
-
Steering Metrics
Evaluates the steering status of the vehicle.
Metrics are calculated and publish only when the node receives a steering report message.
Implemented metrics
-
steer_change_count
: Count steering rate changes.- A change is counted when the steering rate changes from positive/0 to negative or from negative/0 to positive.
- Parameters:
-
steer_change_count.window_duration_s
: duration to count the changes for publishing. -
steer_change_count.steer_rate_margin
: margin to consider the steer rate as 0.
-
- Sub-metrics to publish:
/count_in_duration
. - Sub-metrics to output:
-
/count_in_duration/min
,/count_in_duration/max
,/count_in_duration/mean
: the statistics of the published keep_duration. -
/count
: total number of changes.
-
Other Information
Additional useful information related to planning:
Implemented metrics
-
kinematic_state
: Current kinematic state of the vehicle- Sub-metrics to publish:
-
/velocity
: current ego velocity. -
/acceleration
: current ego acceleration. -
/jerk
: current ego jerk.
-
- Sub-metrics to publish:
-
ego_lane_info
: Lanelet information.- Sub-metrics to publish:
-
/lanelet_id
: ID of the lanelet where the ego is located. -
/s
: Arc length of ego position in the lanelet. -
/t
: Lateral offset of ego position in the lanelet.
-
- Sub-metrics to publish:
Inputs / Outputs
Inputs
Name | Type | Description |
---|---|---|
~/input/trajectory |
autoware_planning_msgs::msg::Trajectory |
Main trajectory to evaluate |
~/input/reference_trajectory |
autoware_planning_msgs::msg::Trajectory |
Reference trajectory to use for deviation metrics |
~/input/objects |
autoware_perception_msgs::msg::PredictedObjects |
Obstacles |
~/input/modified_goal |
autoware_planning_msgs::msg::PoseWithUuidStamped |
Modified goal |
~/input/odometry |
nav_msgs::msg::Odometry |
Current odometry of the vehicle |
~/input/route |
autoware_planning_msgs::msg::LaneletRoute |
Route information |
~/input/vector_map |
autoware_map_msgs::msg::LaneletMapBin |
Vector map information |
~/input/acceleration |
geometry_msgs::msg::AccelWithCovarianceStamped |
Current acceleration of the vehicle |
~/input/steering_status |
autoware_vehicle_msgs::msg::SteeringReport |
Current steering of the vehicle |
~/input/turn_indicators_status |
autoware_vehicle_msgs::msg::TurnIndicatorsReport |
Current blinker status of the vehicle |
{topic_prefix}/{module_name} |
autoware_internal_planning_msgs::msg::PlanningFactorArray |
Planning factors of each module to evaluate |
Outputs
Each publishing-based metric is published on the same topic.
Name | Type | Description |
---|---|---|
~/metrics |
tier4_metric_msgs::msg::MetricArray |
MetricArray with all published metrics |
~/debug/processing_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
Node processing time in milliseconds |
- If
output_metrics = true
, the evaluation node writes the output-based metrics measured during its lifetime to<ros2_logging_directory>/autoware_metrics/<node_name>-<time_stamp>.json
when shut down.
Parameters
{{ json_to_markdown(“evaluator/autoware_planning_evaluator/schema/autoware_planning_evaluator.schema.json”) }}
Assumptions / Known limits
There is a strong assumption that when receiving a trajectory T(0)
,
it has been generated using the last received reference trajectory and objects.
This can be wrong if a new reference trajectory or objects are published while T(0)
is being calculated.
Precision is currently limited by the resolution of the trajectories. It is possible to interpolate the trajectory and reference trajectory to increase precision but would make computation significantly more expensive.
Future extensions / Unimplemented parts
- Use
Route
orPath
messages as reference trajectory. - RSS metrics (done in another node https://tier4.atlassian.net/browse/AJD-263).
-
motion_evaluator_node
.- Node which constructs a trajectory over time from the real motion of ego.
- Only a proof of concept is currently implemented.
- Take into account the shape, not only the centroid of the object for the obstacle metrics.
Changelog for package autoware_planning_evaluator
0.44.0 (2025-04-18)
- Merge remote-tracking branch 'origin/main' into humble
- chore(autoware_planning_evaluator): record goal_stop_deviation
only when ego stop
(#10429)
- record modified_goal related output_metric only when the ego stop close to goal
- change vel thr
* pre-commit ---------
- feat(autoware_planning_evaluator): refactor planning_evaluator
for new metrics
(#10368)
- tmp save.
- tmp save.
- WIP add accumulator-based metrics.
- pre-commit
- add unit test.
- pre-commit
- fix cppcheck
- update readme.
- pre-commit
- polish readme.
- pre-commit
- change count to size_t
- update config.
- publish count.
- fix stop decision bug
- update parameters.
* fix typo ---------Co-authored-by: t4-adc <<grp-rd-1-adc-admin@tier4.jp>>
- Contributors: Kem (TiankuiXian), Ryohsuke Mitsudome
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)
- feat(control_evaluator): add a new stop_deviation metric
(#10246)
- add metric of stop_deviation
- fix bug
- remove unused include.
- add unit test and schema
- pre-commit
* update planning_evaluator schema ---------Co-authored-by: t4-adc <<grp-rd-1-adc-admin@tier4.jp>>
- Contributors: Hayato Mizushima, Kem (TiankuiXian), Yutaka Kondo
0.42.0 (2025-03-03)
- Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
- feat(autoware_utils): replace autoware_universe_utils with autoware_utils (#10191)
- feat(autoware_planning_evaluator): add resampled_relative_angle
metrics
(#10020)
- feat(autoware_planning_evaluator): add new large_relative_angle metrics
- fix copyright and vehicle_length_m
- style(pre-commit): autofix
- del: resample trajectory
- del: traj points check
- rename msg and speed optimization
- style(pre-commit): autofix
- add unit_test and fix resample_relative_angle
- style(pre-commit): autofix
- include tuple to test
- target two point, update unit test value
- fix abs
* fix for loop bag and primitive type ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- Contributors: Fumiya Watanabe, Kazunori-Nakajima, 心刚
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
- feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (#9859) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files evaluator/autoware_planning_evaluator
- fix(planning_evaluator): update lateral_trajectory_displacement
to absolute value
(#9696)
- fix(planning_evaluator): update lateral_trajectory_displacement to absolute value
* style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- fix(autoware_planning_evaluator): rename lateral deviation metrics
(#9801)
- refactor(planning_evaluator): rename and add lateral trajectory displacement metrics
* fix typo ---------
- feat(planning_evaluator): add evaluation feature of trajectory
lateral displacement
(#9718)
- feat(planning_evaluator): add evaluation feature of trajectory lateral displacement
- feat(metrics_calculator): implement lookahead trajectory calculation and remove deprecated method
* fix(planning_evaluator): rename lateral_trajectory_displacement to trajectory_lateral_displacement for consistency ---------
- fix(autoware_planning_evaluator): fix bugprone-exception-escape (#9730) fix: bugprone-exception-escape
- feat(planning_evaluator): add lateral trajectory displacement
metrics
(#9674)
- feat(planning_evaluator): add nearest pose deviation msg
- update comment contents
- update variable name
* Revert "update variable name" This reverts commit ee427222fcbd2a18ffbc20fecca3ad557f527e37.
- move lateral_trajectory_displacement position
* prev.dist -> prev_lateral_deviation ---------
- Contributors: Fumiya Watanabe, Kazunori-Nakajima, Kyoichi Sugahara, Vishal Chauhan, kobayu858
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 - evaluator (#9566)
- feat(planning_evaluator): add a trigger to choice whether to output
metrics to log folder
(#9476)
- tmp save
- planning_evaluator build ok, test it.
- add descriptions to output.
- pre-commit.
- add parm to launch file.
- move output_metrics from config to launch file.
* fix unit test bug. ---------
- 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>>
- feat(planning_evaluator): add processing time pub (#9334)
- 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(evaluator): missing dependency in evaluator components (#9074)
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- feat(tier4_metric_msgs): apply tier4_metric_msgs for
scenario_simulator_v2_adapter, control_evaluator,
planning_evaluator, autonomous_emergency_braking,
obstacle_cruise_planner, motion_velocity_planner,
processing_time_checker
(#9180)
- first commit
- fix building errs.
- change diagnostic messages to metric messages for publishing decision.
- fix bug about motion_velocity_planner
- change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner.
- tmp save for planning_evaluator
- change the topic to which metrics published to.
- fix typo.
- remove unnesessary publishing of metrics.
- mke planning_evaluator publish msg of MetricArray instead of Diags.
- update aeb with metric type for decision.
- fix some bug
- remove autoware_evaluator_utils package.
- remove diagnostic_msgs dependency of planning_evaluator
- use metric_msgs for autoware_processing_time_checker.
- rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs.
- pre-commit and fix typo
- publish metrics even if there is no metric in the MetricArray.
- modify the metric name of processing_time.
- update unit test for test_planning/control_evaluator
* manual pre-commit ---------
- 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, Kazunori-Nakajima, Kem (TiankuiXian), M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, ぐるぐる
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)
- feat(tier4_metric_msgs): apply tier4_metric_msgs for
scenario_simulator_v2_adapter, control_evaluator,
planning_evaluator, autonomous_emergency_braking,
obstacle_cruise_planner, motion_velocity_planner,
processing_time_checker
(#9180)
- first commit
- fix building errs.
- change diagnostic messages to metric messages for publishing decision.
- fix bug about motion_velocity_planner
- change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner.
- tmp save for planning_evaluator
- change the topic to which metrics published to.
- fix typo.
- remove unnesessary publishing of metrics.
- mke planning_evaluator publish msg of MetricArray instead of Diags.
- update aeb with metric type for decision.
- fix some bug
- remove autoware_evaluator_utils package.
- remove diagnostic_msgs dependency of planning_evaluator
- use metric_msgs for autoware_processing_time_checker.
- rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs.
- pre-commit and fix typo
- publish metrics even if there is no metric in the MetricArray.
- modify the metric name of processing_time.
- update unit test for test_planning/control_evaluator
* manual pre-commit ---------
- 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, Kem (TiankuiXian), Yutaka Kondo
0.38.0 (2024-11-08)
- unify package.xml version to 0.37.0
- refactor(autoware_planning_evaluator): devops node dojo (#8746)
- feat(motion_velocity_planner,planning_evaluator): add stop,
slow_down diags
(#8503)
- tmp save.
- publish diagnostics.
- move clearDiagnostics func to head
- change to snake_names.
- remove a change of launch.xml
- pre-commit run -a
- publish diagnostics on node side.
- move empty checking out of 'get_diagnostics'.
- remove get_diagnostics; change reason str.
- remove unused condition.
* Update planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp Co-authored-by: Kosuke Takeuchi <<kosuke.tnp@gmail.com>> * Update planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp Co-authored-by: Kosuke Takeuchi <<kosuke.tnp@gmail.com>> ---------Co-authored-by: Kosuke Takeuchi <<kosuke.tnp@gmail.com>>
- fix(autoware_planning_evaluator): fix unreadVariable
(#8352)
- fix:unreadVariable
* fix:unreadVariable ---------
- feat(evalautor): rename evaluator diag topics
(#8152)
- feat(evalautor): rename evaluator diag topics
* perception ---------
- 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(cruise_planner,planning_evaluator): add cruise and slow down
diags
(#7960)
- add cruise and slow down diags to cruise planner
- add cruise types
* adjust planning eval ---------
- feat(planning_evaluator,control_evaluator, evaluator utils): add
diagnostics subscriber to planning eval
(#7849)
- add utils and diagnostics subscription to planning_evaluator
- add diagnostics eval
* fix input diag in launch ---------Co-authored-by: kosuke55 <<kosuke.tnp@gmail.com>>
- feat(planning_evaluator): add planning evaluator polling sub
(#7827)
- WIP add polling subs
- WIP
- update functions
- remove semicolon
* use last data for modified goal ---------
- feat(planning_evaluator): add lanelet info to the planning evaluator (#7781) add lanelet info to the planning evaluator
- refactor(universe_utils/motion_utils)!: add autoware namespace (#7594)
- refactor(motion_utils)!: add autoware prefix and include dir (#7539) refactor(motion_utils): add autoware prefix and include dir
- feat(autoware_universe_utils)!: rename from tier4_autoware_utils (#7538) Co-authored-by: kosuke55 <<kosuke.tnp@gmail.com>>
- feat(planning_evaluator): rename to
include/autoware/{package_name}
(#7518)
- fix
* fix
- Contributors: Kosuke Takeuchi, Takayuki Murooka, Tiankui Xian, Yukinari Hisaki, Yutaka Kondo, danielsanchezaran, kobayu858, odra
0.26.0 (2024-04-03)
Wiki Tutorials
Package Dependencies
System Dependencies
Name |
---|
eigen |
nlohmann-json-dev |
Dependant Packages
Name | Deps |
---|---|
tier4_planning_launch |
Launch files
- launch/motion_evaluator.launch.xml
-
- output_metrics [default: false]
- input/twist [default: /localization/twist]
- launch/planning_evaluator.launch.xml
-
- output_metrics [default: false]
- input/odometry [default: /localization/kinematic_state]
- input/acceleration [default: /localization/acceleration]
- input/trajectory [default: /planning/scenario_planning/trajectory]
- input/reference_trajectory [default: /planning/scenario_planning/lane_driving/motion_planning/path_optimizer/trajectory]
- input/objects [default: /perception/object_recognition/objects]
- input/modified_goal [default: /planning/scenario_planning/modified_goal]
- input/map_topic [default: /map/vector_map]
- input/route_topic [default: /planning/mission_planning/route]
- input/turn_indicators_status [default: /vehicle/status/turn_indicators_status]
- input/steering_status [default: /vehicle/status/steering_status]