Skip to content

Commit

Permalink
refactor(evaluators, autoware_universe_utils): rename Stat class to A…
Browse files Browse the repository at this point in the history
…ccumulator and move it to autoware_universe_utils (#9459)

* add Accumulator class to autoware_universe_utils

Signed-off-by: xtk8532704 <[email protected]>

* use Accumulator on all evaluators.

Signed-off-by: xtk8532704 <[email protected]>

* pre-commit

Signed-off-by: xtk8532704 <[email protected]>

* found and fixed a bug. add more tests.

Signed-off-by: xtk8532704 <[email protected]>

* pre-commit

Signed-off-by: xtk8532704 <[email protected]>

* Update common/autoware_universe_utils/include/autoware/universe_utils/math/accumulator.hpp

Co-authored-by: Kosuke Takeuchi <[email protected]>
Signed-off-by: xtk8532704 <[email protected]>

---------

Signed-off-by: xtk8532704 <[email protected]>
Co-authored-by: Kosuke Takeuchi <[email protected]>
  • Loading branch information
xtk8532704 and kosuke55 authored Nov 27, 2024
1 parent f23916f commit 12a86f6
Show file tree
Hide file tree
Showing 39 changed files with 215 additions and 416 deletions.
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.
// Copyright 2021-2024 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.
Expand All @@ -15,17 +15,17 @@
#include <iostream>
#include <limits>

#ifndef AUTOWARE__PLANNING_EVALUATOR__STAT_HPP_
#define AUTOWARE__PLANNING_EVALUATOR__STAT_HPP_
#ifndef AUTOWARE__UNIVERSE_UTILS__MATH__ACCUMULATOR_HPP_
#define AUTOWARE__UNIVERSE_UTILS__MATH__ACCUMULATOR_HPP_

namespace planning_diagnostics
namespace autoware::universe_utils
{
/**
* @brief class to incrementally build statistics
* @brief class to accumulate statistical data, supporting min, max and mean.
* @typedef T type of the values (default to double)
*/
template <typename T = double>
class Stat
class Accumulator
{
public:
/**
Expand Down Expand Up @@ -65,11 +65,11 @@ class Stat
unsigned int count() const { return count_; }

template <typename U>
friend std::ostream & operator<<(std::ostream & os, const Stat<U> & stat);
friend std::ostream & operator<<(std::ostream & os, const Accumulator<U> & accumulator);

private:
T min_ = std::numeric_limits<T>::max();
T max_ = std::numeric_limits<T>::min();
T max_ = std::numeric_limits<T>::lowest();
long double mean_ = 0.0;
unsigned int count_ = 0;
};
Expand All @@ -78,16 +78,16 @@ class Stat
* @brief overload << operator for easy print to output stream
*/
template <typename T>
std::ostream & operator<<(std::ostream & os, const Stat<T> & stat)
std::ostream & operator<<(std::ostream & os, const Accumulator<T> & accumulator)
{
if (stat.count() == 0) {
if (accumulator.count() == 0) {
os << "None None None";
} else {
os << stat.min() << " " << stat.max() << " " << stat.mean();
os << accumulator.min() << " " << accumulator.max() << " " << accumulator.mean();
}
return os;
}

} // namespace planning_diagnostics
} // namespace autoware::universe_utils

#endif // AUTOWARE__PLANNING_EVALUATOR__STAT_HPP_
#endif // AUTOWARE__UNIVERSE_UTILS__MATH__ACCUMULATOR_HPP_
64 changes: 64 additions & 0 deletions common/autoware_universe_utils/test/src/math/test_accumulator.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
// Copyright 2024 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.

#include "autoware/universe_utils/math/accumulator.hpp"

#include <gtest/gtest.h>

TEST(accumulator, empty)
{
autoware::universe_utils::Accumulator<double> acc;

EXPECT_DOUBLE_EQ(acc.mean(), 0.0);
EXPECT_DOUBLE_EQ(acc.min(), std::numeric_limits<double>::max());
EXPECT_DOUBLE_EQ(acc.max(), std::numeric_limits<double>::lowest());
EXPECT_EQ(acc.count(), 0);
}

TEST(accumulator, addValues)
{
autoware::universe_utils::Accumulator<double> acc;
acc.add(100.0);

EXPECT_DOUBLE_EQ(acc.mean(), 100.0);
EXPECT_DOUBLE_EQ(acc.min(), 100.0);
EXPECT_DOUBLE_EQ(acc.max(), 100.0);
EXPECT_EQ(acc.count(), 1);
}

TEST(accumulator, positiveValues)
{
autoware::universe_utils::Accumulator<double> acc;
acc.add(10.0);
acc.add(40.0);
acc.add(10.0);

EXPECT_DOUBLE_EQ(acc.mean(), 20.0);
EXPECT_DOUBLE_EQ(acc.min(), 10.0);
EXPECT_DOUBLE_EQ(acc.max(), 40.0);
EXPECT_EQ(acc.count(), 3);
}

TEST(accumulator, negativeValues)
{
autoware::universe_utils::Accumulator<double> acc;
acc.add(-10.0);
acc.add(-40.0);
acc.add(-10.0);

EXPECT_DOUBLE_EQ(acc.mean(), -20.0);
EXPECT_DOUBLE_EQ(acc.min(), -40.0);
EXPECT_DOUBLE_EQ(acc.max(), -10.0);
EXPECT_EQ(acc.count(), 3);
}
4 changes: 2 additions & 2 deletions evaluator/autoware_planning_evaluator/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ which is also responsible for calculating metrics.

### Stat

Each metric is calculated using a `Stat` instance which contains
Each metric is calculated using a `autoware::universe_utils::Accumulator` instance which contains
the minimum, maximum, and mean values calculated for the metric
as well as the number of values measured.

Expand All @@ -35,7 +35,7 @@ The `MetricsCalculator` is responsible for calculating metric statistics
through calls to function:

```C++
Stat<double> MetricsCalculator::calculate(const Metric metric, const Trajectory & traj) const;
Accumulator<double> MetricsCalculator::calculate(const Metric metric, const Trajectory & traj) const;
```
Adding a new metric `M` requires the following steps:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef AUTOWARE__PLANNING_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_
#define AUTOWARE__PLANNING_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_

#include "autoware/planning_evaluator/stat.hpp"
#include "autoware/universe_utils/math/accumulator.hpp"

#include "autoware_planning_msgs/msg/trajectory.hpp"
#include "autoware_planning_msgs/msg/trajectory_point.hpp"
Expand All @@ -24,6 +24,7 @@ namespace planning_diagnostics
{
namespace metrics
{
using autoware::universe_utils::Accumulator;
using autoware_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::TrajectoryPoint;
using geometry_msgs::msg::Point;
Expand All @@ -35,47 +36,47 @@ using geometry_msgs::msg::Pose;
* @param [in] traj input trajectory
* @return calculated statistics
*/
Stat<double> calcLateralDeviation(const Trajectory & ref, const Trajectory & traj);
Accumulator<double> calcLateralDeviation(const Trajectory & ref, const Trajectory & traj);

/**
* @brief calculate yaw deviation of the given trajectory from the reference trajectory
* @param [in] ref reference trajectory
* @param [in] traj input trajectory
* @return calculated statistics
*/
Stat<double> calcYawDeviation(const Trajectory & ref, const Trajectory & traj);
Accumulator<double> calcYawDeviation(const Trajectory & ref, const Trajectory & traj);

/**
* @brief calculate velocity deviation of the given trajectory from the reference trajectory
* @param [in] ref reference trajectory
* @param [in] traj input trajectory
* @return calculated statistics
*/
Stat<double> calcVelocityDeviation(const Trajectory & ref, const Trajectory & traj);
Accumulator<double> calcVelocityDeviation(const Trajectory & ref, const Trajectory & traj);

/**
* @brief calculate longitudinal deviation of the given ego pose from the modified goal pose
* @param [in] base_pose base pose
* @param [in] target_point target point
* @return calculated statistics
*/
Stat<double> calcLongitudinalDeviation(const Pose & base_pose, const Point & target_point);
Accumulator<double> calcLongitudinalDeviation(const Pose & base_pose, const Point & target_point);

/**
* @brief calculate lateral deviation of the given ego pose from the modified goal pose
* @param [in] base_pose base pose
* @param [in] target_point target point
* @return calculated statistics
*/
Stat<double> calcLateralDeviation(const Pose & base_pose, const Point & target_point);
Accumulator<double> calcLateralDeviation(const Pose & base_pose, const Point & target_point);

/**
* @brief calculate yaw deviation of the given ego pose from the modified goal pose
* @param [in] base_pose base pose
* @param [in] target_pose target pose
* @return calculated statistics
*/
Stat<double> calcYawDeviation(const Pose & base_pose, const Pose & target_pose);
Accumulator<double> calcYawDeviation(const Pose & base_pose, const Pose & target_pose);

} // namespace metrics
} // namespace planning_diagnostics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,6 @@
#ifndef AUTOWARE__PLANNING_EVALUATOR__METRICS__METRICS_UTILS_HPP_
#define AUTOWARE__PLANNING_EVALUATOR__METRICS__METRICS_UTILS_HPP_

#include "autoware/planning_evaluator/stat.hpp"

#include "autoware_planning_msgs/msg/trajectory.hpp"
#include "autoware_planning_msgs/msg/trajectory_point.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef AUTOWARE__PLANNING_EVALUATOR__METRICS__OBSTACLE_METRICS_HPP_
#define AUTOWARE__PLANNING_EVALUATOR__METRICS__OBSTACLE_METRICS_HPP_

#include "autoware/planning_evaluator/stat.hpp"
#include "autoware/universe_utils/math/accumulator.hpp"

#include "autoware_perception_msgs/msg/predicted_objects.hpp"
#include "autoware_planning_msgs/msg/trajectory.hpp"
Expand All @@ -24,6 +24,7 @@ namespace planning_diagnostics
{
namespace metrics
{
using autoware::universe_utils::Accumulator;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_planning_msgs::msg::Trajectory;

Expand All @@ -33,7 +34,8 @@ using autoware_planning_msgs::msg::Trajectory;
* @param [in] traj trajectory
* @return calculated statistics
*/
Stat<double> calcDistanceToObstacle(const PredictedObjects & obstacles, const Trajectory & traj);
Accumulator<double> calcDistanceToObstacle(
const PredictedObjects & obstacles, const Trajectory & traj);

/**
* @brief calculate the time to collision of the trajectory with the given obstacles
Expand All @@ -42,7 +44,7 @@ Stat<double> calcDistanceToObstacle(const PredictedObjects & obstacles, const Tr
* @param [in] traj trajectory
* @return calculated statistics
*/
Stat<double> calcTimeToCollision(
Accumulator<double> calcTimeToCollision(
const PredictedObjects & obstacles, const Trajectory & traj, const double distance_threshold);

} // namespace metrics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,15 @@
#ifndef AUTOWARE__PLANNING_EVALUATOR__METRICS__STABILITY_METRICS_HPP_
#define AUTOWARE__PLANNING_EVALUATOR__METRICS__STABILITY_METRICS_HPP_

#include "autoware/planning_evaluator/stat.hpp"
#include "autoware/universe_utils/math/accumulator.hpp"

#include "autoware_planning_msgs/msg/trajectory.hpp"

namespace planning_diagnostics
{
namespace metrics
{
using autoware::universe_utils::Accumulator;
using autoware_planning_msgs::msg::Trajectory;

/**
Expand All @@ -31,15 +32,15 @@ using autoware_planning_msgs::msg::Trajectory;
* @param [in] traj2 second trajectory
* @return calculated statistics
*/
Stat<double> calcFrechetDistance(const Trajectory & traj1, const Trajectory & traj2);
Accumulator<double> calcFrechetDistance(const Trajectory & traj1, const Trajectory & traj2);

/**
* @brief calculate the lateral distance between two trajectories
* @param [in] traj1 first trajectory
* @param [in] traj2 second trajectory
* @return calculated statistics
*/
Stat<double> calcLateralDistance(const Trajectory & traj1, const Trajectory & traj2);
Accumulator<double> calcLateralDistance(const Trajectory & traj1, const Trajectory & traj2);

} // namespace metrics
} // namespace planning_diagnostics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef AUTOWARE__PLANNING_EVALUATOR__METRICS__TRAJECTORY_METRICS_HPP_
#define AUTOWARE__PLANNING_EVALUATOR__METRICS__TRAJECTORY_METRICS_HPP_

#include "autoware/planning_evaluator/stat.hpp"
#include "autoware/universe_utils/math/accumulator.hpp"

#include "autoware_planning_msgs/msg/trajectory.hpp"
#include "autoware_planning_msgs/msg/trajectory_point.hpp"
Expand All @@ -24,6 +24,7 @@ namespace planning_diagnostics
{
namespace metrics
{
using autoware::universe_utils::Accumulator;
using autoware_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::TrajectoryPoint;

Expand All @@ -33,56 +34,57 @@ using autoware_planning_msgs::msg::TrajectoryPoint;
* @param [in] min_dist_threshold minimum distance between successive points
* @return calculated statistics
*/
Stat<double> calcTrajectoryRelativeAngle(const Trajectory & traj, const double min_dist_threshold);
Accumulator<double> calcTrajectoryRelativeAngle(
const Trajectory & traj, const double min_dist_threshold);

/**
* @brief calculate metric for the distance between trajectory points
* @param [in] traj input trajectory
* @return calculated statistics
*/
Stat<double> calcTrajectoryInterval(const Trajectory & traj);
Accumulator<double> calcTrajectoryInterval(const Trajectory & traj);

/**
* @brief calculate curvature metric
* @param [in] traj input trajectory
* @return calculated statistics
*/
Stat<double> calcTrajectoryCurvature(const Trajectory & traj);
Accumulator<double> calcTrajectoryCurvature(const Trajectory & traj);

/**
* @brief calculate length of the trajectory [m]
* @param [in] traj input trajectory
* @return calculated statistics
*/
Stat<double> calcTrajectoryLength(const Trajectory & traj);
Accumulator<double> calcTrajectoryLength(const Trajectory & traj);

/**
* @brief calculate duration of the trajectory [s]
* @param [in] traj input trajectory
* @return calculated statistics
*/
Stat<double> calcTrajectoryDuration(const Trajectory & traj);
Accumulator<double> calcTrajectoryDuration(const Trajectory & traj);

/**
* @brief calculate velocity metrics for the trajectory
* @param [in] traj input trajectory
* @return calculated statistics
*/
Stat<double> calcTrajectoryVelocity(const Trajectory & traj);
Accumulator<double> calcTrajectoryVelocity(const Trajectory & traj);

/**
* @brief calculate acceleration metrics for the trajectory
* @param [in] traj input trajectory
* @return calculated statistics
*/
Stat<double> calcTrajectoryAcceleration(const Trajectory & traj);
Accumulator<double> calcTrajectoryAcceleration(const Trajectory & traj);

/**
* @brief calculate jerk metrics for the trajectory
* @param [in] traj input trajectory
* @return calculated statistics
*/
Stat<double> calcTrajectoryJerk(const Trajectory & traj);
Accumulator<double> calcTrajectoryJerk(const Trajectory & traj);

} // namespace metrics
} // namespace planning_diagnostics
Expand Down
Loading

0 comments on commit 12a86f6

Please sign in to comment.