Skip to content
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
7 changes: 6 additions & 1 deletion planning/autoware_planning_data_analyzer/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
src/or_scene_evaluator.cpp
src/metrics/deviation_metrics.cpp
src/metrics/history_comfort.cpp
src/metrics/drivable_area_compliance.cpp
src/metrics/trajectory_metrics.cpp
src/utils/bag_utils.cpp
src/utils/json_utils.cpp
Expand All @@ -27,7 +28,11 @@ rclcpp_components_register_node(${PROJECT_NAME}
if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)

ament_add_gtest(test_metrics test/metrics/test_deviation_metrics.cpp)
ament_add_gtest(
test_metrics
test/metrics/test_deviation_metrics.cpp
test/metrics/test_drivable_area_compliance.cpp
)
target_link_libraries(test_metrics ${PROJECT_NAME})

ament_add_gtest(test_offline_evaluation
Expand Down
Original file line number Diff line number Diff line change
@@ -1,21 +1,38 @@
<launch>
<arg name="bag_path" description="Path to rosbag file or directory"/>
<arg name="config_file" default="$(find-pkg-share autoware_planning_data_analyzer)/config/planning_data_analyzer.param.yaml" description="Path to parameter file"/>
<arg name="vehicle_model" default="" description="Vehicle model name"/>
<arg name="output_dir" description="Output directory for evaluation results (overrides config file if specified)"/>
<arg name="trajectory_topic" default="/planning/trajectory" description="Trajectory topic to evaluate"/>
<arg name="open_loop_metric_variant" default="" description="Variant label for open-loop metric topics"/>
<arg name="gt_source_mode" default="kinematic_state" description="GT source mode: kinematic_state or gt_trajectory"/>
<arg name="gt_trajectory_topic" default="/planning/ground_truth_trajectory" description="GT trajectory topic for gt_trajectory mode"/>
<arg name="gt_sync_tolerance_ms" default="200.0" description="Sync tolerance (ms) for GT trajectory alignment"/>

<node pkg="autoware_planning_data_analyzer" exec="autoware_planning_data_analyzer_node" name="autoware_planning_data_analyzer" output="screen">
<param from="$(var config_file)"/>
<param name="input_bag_path" value="$(var bag_path)"/>
<param name="output_dir" value="$(var output_dir)"/>
<param name="trajectory_topic" value="$(var trajectory_topic)"/>
<param name="open_loop.metric_variant" value="$(var open_loop_metric_variant)"/>
<param name="open_loop.gt_source_mode" value="$(var gt_source_mode)"/>
<param name="open_loop.gt_trajectory_topic" value="$(var gt_trajectory_topic)"/>
<param name="open_loop.gt_sync_tolerance_ms" value="$(var gt_sync_tolerance_ms)"/>
</node>
<group if="$(eval '&quot;$(var vehicle_model)&quot; != &quot;&quot;')">
<node pkg="autoware_planning_data_analyzer" exec="autoware_planning_data_analyzer_node" name="autoware_planning_data_analyzer" output="screen">
<param from="$(var config_file)"/>
<param from="$(find-pkg-share $(var vehicle_model)_description)/config/vehicle_info.param.yaml"/>
<param name="input_bag_path" value="$(var bag_path)"/>
<param name="output_dir" value="$(var output_dir)"/>
<param name="trajectory_topic" value="$(var trajectory_topic)"/>
<param name="open_loop.metric_variant" value="$(var open_loop_metric_variant)"/>
<param name="open_loop.gt_source_mode" value="$(var gt_source_mode)"/>
<param name="open_loop.gt_trajectory_topic" value="$(var gt_trajectory_topic)"/>
<param name="open_loop.gt_sync_tolerance_ms" value="$(var gt_sync_tolerance_ms)"/>
</node>
</group>

<group if="$(eval '&quot;$(var vehicle_model)&quot; == &quot;&quot;')">
<node pkg="autoware_planning_data_analyzer" exec="autoware_planning_data_analyzer_node" name="autoware_planning_data_analyzer" output="screen">
<param from="$(var config_file)"/>
<param name="input_bag_path" value="$(var bag_path)"/>
<param name="output_dir" value="$(var output_dir)"/>
<param name="trajectory_topic" value="$(var trajectory_topic)"/>
<param name="open_loop.metric_variant" value="$(var open_loop_metric_variant)"/>
<param name="open_loop.gt_source_mode" value="$(var gt_source_mode)"/>
<param name="open_loop.gt_trajectory_topic" value="$(var gt_trajectory_topic)"/>
<param name="open_loop.gt_sync_tolerance_ms" value="$(var gt_sync_tolerance_ms)"/>
</node>
</group>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,16 @@ AutowarePlanningDataAnalyzerNode::AutowarePlanningDataAnalyzerNode(
: Node("autoware_planning_data_analyzer", node_options),
route_handler_{std::make_shared<autoware::route_handler::RouteHandler>()}
{
try {
vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo();
} catch (const std::exception & e) {
RCLCPP_WARN(
get_logger(),
"Vehicle info parameters are unavailable. Drivable area compliance will be marked "
"unavailable: %s",
e.what());
vehicle_info_ = autoware::vehicle_info_utils::VehicleInfo{};
}
setup_evaluation_bag_writer();

// Open bag file
Expand Down Expand Up @@ -468,7 +478,8 @@ void AutowarePlanningDataAnalyzerNode::run_evaluation()
const auto evaluation_horizons =
get_or_declare_parameter<std::vector<double>>(*this, "open_loop.evaluation_horizons");
OpenLoopEvaluator evaluator(
get_logger(), route_handler_, gt_mode, gt_sync_tolerance_ms_, history_comfort_params_);
get_logger(), route_handler_, gt_mode, gt_sync_tolerance_ms_, history_comfort_params_,
vehicle_info_);
evaluator.set_json_output_dir(output_dir_path.string());
evaluator.set_metric_variant(open_loop_metric_variant);
evaluator.set_evaluation_horizons(evaluation_horizons);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,7 @@ class AutowarePlanningDataAnalyzerNode : public rclcpp::Node
std::string gt_trajectory_topic_name_;
double gt_sync_tolerance_ms_ = 200.0;
metrics::HistoryComfortParameters history_comfort_params_;
autoware::vehicle_info_utils::VehicleInfo vehicle_info_;
std::string objects_topic_name_;
std::string tf_topic_name_;
std::string acceleration_topic_name_;
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,192 @@
// Copyright 2026 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 "drivable_area_compliance.hpp"

#include <autoware_utils_geometry/boost_geometry.hpp>
#include <autoware_utils_geometry/geometry.hpp>

#include <boost/geometry.hpp>

#include <lanelet2_core/geometry/Lanelet.h>

#include <cstddef>
#include <optional>
#include <vector>

namespace autoware::planning_data_analyzer::metrics
{

namespace
{

bool is_vehicle_info_valid(const autoware::vehicle_info_utils::VehicleInfo & vehicle_info)
{
return vehicle_info.vehicle_length_m > 0.0 && vehicle_info.vehicle_width_m > 0.0;
}

using autoware_utils_geometry::LinearRing2d;
using autoware_utils_geometry::MultiPolygon2d;
using autoware_utils_geometry::Point2d;
using autoware_utils_geometry::Polygon2d;

std::vector<LinearRing2d> create_vehicle_footprints(
const autoware_planning_msgs::msg::Trajectory & trajectory,
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info)
{
const auto base_footprint = vehicle_info.createFootprint(0.0);

std::vector<LinearRing2d> vehicle_footprints;
vehicle_footprints.reserve(trajectory.points.size());
for (const auto & point : trajectory.points) {
vehicle_footprints.push_back(
autoware_utils_geometry::transform_vector(
base_footprint, autoware_utils_geometry::pose2transform(point.pose)));
}

return vehicle_footprints;
}

LinearRing2d create_hull_from_footprints(const std::vector<LinearRing2d> & footprints)
{
boost::geometry::model::multi_point<Point2d> combined;
for (const auto & footprint : footprints) {
for (const auto & point : footprint) {
combined.push_back(point);
}
}

LinearRing2d hull;
boost::geometry::convex_hull(combined, hull);
boost::geometry::correct(hull);
return hull;
}

lanelet::ConstLanelets collect_candidate_lanelets(
const lanelet::ConstLanelets & drivable_lanelets,
const std::vector<LinearRing2d> & vehicle_footprints)
{
const auto footprint_hull = create_hull_from_footprints(vehicle_footprints);

lanelet::ConstLanelets candidate_lanelets;
for (const auto & lanelet : drivable_lanelets) {
if (!boost::geometry::disjoint(lanelet.polygon2d().basicPolygon(), footprint_hull)) {
candidate_lanelets.push_back(lanelet);
}
}

return candidate_lanelets;
}

Polygon2d to_polygon_2d(const lanelet::BasicPolygon2d & polygon)
{
Polygon2d converted;
for (const auto & point : polygon) {
converted.outer().push_back(Point2d(point.x(), point.y()));
}
boost::geometry::correct(converted);
return converted;
}

std::optional<MultiPolygon2d> fuse_lanelet_polygons(
const lanelet::ConstLanelets & candidate_lanelets)
{
if (candidate_lanelets.empty()) {
return std::nullopt;
}

MultiPolygon2d lanelet_unions;
MultiPolygon2d result;

for (const auto & lanelet : candidate_lanelets) {
const auto polygon = to_polygon_2d(lanelet.polygon2d().basicPolygon());
boost::geometry::union_(lanelet_unions, polygon, result);
lanelet_unions = result;
result.clear();
}

if (lanelet_unions.empty()) {
return std::nullopt;
}

for (auto & polygon : lanelet_unions) {
boost::geometry::correct(polygon);
}

return lanelet_unions;
}

bool is_footprint_inside_any_polygon(
const LinearRing2d & vehicle_footprint, const MultiPolygon2d & fused_polygons)
{
return std::any_of(
fused_polygons.begin(), fused_polygons.end(), [&vehicle_footprint](const auto & polygon) {
return boost::geometry::within(vehicle_footprint, polygon);
});
}

} // namespace

DrivableAreaComplianceResult calculate_drivable_area_compliance(
const autoware_planning_msgs::msg::Trajectory & trajectory,
const lanelet::ConstLanelets & drivable_lanelets,
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info)
{
DrivableAreaComplianceResult result;
if (trajectory.points.empty()) {
result.reason = "unavailable_empty_trajectory";
return result;
}
if (drivable_lanelets.empty()) {
result.reason = "unavailable_no_drivable_lanelets";
return result;
}
if (!is_vehicle_info_valid(vehicle_info)) {
result.reason = "unavailable_invalid_vehicle_info";
return result;
}

const auto vehicle_footprints = create_vehicle_footprints(trajectory, vehicle_info);
if (vehicle_footprints.empty() || vehicle_footprints.front().empty()) {
result.reason = "unavailable_invalid_footprint";
return result;
}

const auto candidate_lanelets = collect_candidate_lanelets(drivable_lanelets, vehicle_footprints);
if (candidate_lanelets.empty()) {
result.reason = "unavailable_no_candidate_lanelets";
return result;
}

const auto fused_lanelet_polygons = fuse_lanelet_polygons(candidate_lanelets);
if (!fused_lanelet_polygons) {
result.reason = "unavailable_invalid_drivable_area_polygon";
return result;
}

result.available = true;
result.reason = "compliant";

for (const auto & footprint : vehicle_footprints) {
if (!is_footprint_inside_any_polygon(footprint, *fused_lanelet_polygons)) {
result.reason = "non_compliant_footprint_outside_drivable_area";
return result;
}
}

result.score = 1.0;
return result;
}

} // namespace autoware::planning_data_analyzer::metrics
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
// Copyright 2026 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 METRICS__DRIVABLE_AREA_COMPLIANCE_HPP_
#define METRICS__DRIVABLE_AREA_COMPLIANCE_HPP_

#include <autoware_vehicle_info_utils/vehicle_info.hpp>

#include <autoware_planning_msgs/msg/trajectory.hpp>

#include <lanelet2_core/primitives/Lanelet.h>

#include <string>

namespace autoware::planning_data_analyzer::metrics
{

struct DrivableAreaComplianceResult
{
double score{0.0};
bool available{false};
std::string reason{"unavailable"};
};

DrivableAreaComplianceResult calculate_drivable_area_compliance(
const autoware_planning_msgs::msg::Trajectory & trajectory,
const lanelet::ConstLanelets & drivable_lanelets,
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info);

} // namespace autoware::planning_data_analyzer::metrics

#endif // METRICS__DRIVABLE_AREA_COMPLIANCE_HPP_
Loading
Loading