Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Mar 6, 2025
1 parent ee881ab commit ac43cce
Show file tree
Hide file tree
Showing 39 changed files with 87 additions and 74 deletions.
2 changes: 1 addition & 1 deletion planning/autoware_obstacle_cruise_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_interpolation</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_motion_utils</depend>
Expand All @@ -41,7 +42,6 @@
<depend>tf2_ros</depend>
<depend>tier4_metric_msgs</depend>
<depend>tier4_planning_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_obstacle_stop_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_factor_interface</depend>
Expand All @@ -43,7 +44,6 @@
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_planning_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
5 changes: 3 additions & 2 deletions planning/autoware_obstacle_stop_planner/src/debug_marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -194,8 +194,9 @@ void ObstacleStopPlannerDebugNode::publish()
if (stop_pose_ptr_) {
planning_factor_interface_->add(
std::numeric_limits<float>::quiet_NaN(), *stop_pose_ptr_,
autoware_internal_planning_msgs::msg::PlanningFactor::STOP, autoware_internal_planning_msgs::msg::SafetyFactorArray{},
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
0.0 /*shift distance*/, "");
}
planning_factor_interface_->publish();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,26 +18,26 @@
#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_planning_msgs/msg/path_point_with_lane_id.hpp>
#include <autoware_planning_msgs/msg/path_point.hpp>
#include <autoware_planning_msgs/msg/trajectory_point.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <autoware_internal_planning_msgs/msg/control_point.hpp>
#include <autoware_internal_planning_msgs/msg/path_point_with_lane_id.hpp>
#include <autoware_internal_planning_msgs/msg/planning_factor.hpp>
#include <autoware_internal_planning_msgs/msg/planning_factor_array.hpp>
#include <autoware_internal_planning_msgs/msg/safety_factor_array.hpp>
#include <autoware_planning_msgs/msg/path_point.hpp>
#include <autoware_planning_msgs/msg/trajectory_point.hpp>
#include <geometry_msgs/msg/pose.hpp>

#include <string>
#include <vector>

namespace autoware::planning_factor_interface
{

using geometry_msgs::msg::Pose;
using autoware_internal_planning_msgs::msg::ControlPoint;
using autoware_internal_planning_msgs::msg::PlanningFactor;
using autoware_internal_planning_msgs::msg::PlanningFactorArray;
using autoware_internal_planning_msgs::msg::SafetyFactorArray;
using geometry_msgs::msg::Pose;

class PlanningFactorInterface
{
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_planning_factor_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,11 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_utils</depend>
<depend>rclcpp</depend>
<depend>autoware_internal_planning_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_surround_obstacle_checker/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>
<buildtool_depend>eigen3_cmake_module</buildtool_depend>

<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_factor_interface</depend>
Expand All @@ -35,7 +36,6 @@
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_planning_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,9 @@
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_planning_msgs/msg/planning_factor_array.hpp>
#include <geometry_msgs/msg/polygon_stamped.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <autoware_internal_planning_msgs/msg/planning_factor_array.hpp>
#include <visualization_msgs/msg/marker.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

Expand All @@ -34,10 +34,10 @@ namespace autoware::surround_obstacle_checker
{

using autoware::vehicle_info_utils::VehicleInfo;
using geometry_msgs::msg::PolygonStamped;
using autoware_internal_planning_msgs::msg::ControlPoint;
using autoware_internal_planning_msgs::msg::PlanningFactor;
using autoware_internal_planning_msgs::msg::PlanningFactorArray;
using geometry_msgs::msg::PolygonStamped;
using visualization_msgs::msg::Marker;
using visualization_msgs::msg::MarkerArray;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,11 +57,11 @@ using autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInt
using autoware::planning_factor_interface::PlanningFactorInterface;
using autoware::rtc_interface::RTCInterface;
using autoware_internal_planning_msgs::msg::PathWithLaneId;
using autoware_internal_planning_msgs::msg::PlanningFactor;
using autoware_internal_planning_msgs::msg::SafetyFactorArray;
using autoware_utils::calc_offset_pose;
using autoware_utils::generate_uuid;
using tier4_planning_msgs::msg::AvoidanceDebugMsgArray;
using autoware_internal_planning_msgs::msg::PlanningFactor;
using autoware_internal_planning_msgs::msg::SafetyFactorArray;
using tier4_rtc_msgs::msg::State;
using unique_identifier_msgs::msg::UUID;
using visualization_msgs::msg::MarkerArray;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,11 +22,11 @@
#include <autoware_utils/geometry/geometry.hpp>
#include <autoware_utils/geometry/pose_deviation.hpp>

#include <autoware_internal_planning_msgs/msg/planning_factor_array.hpp>
#include <autoware_perception_msgs/msg/predicted_object.hpp>
#include <autoware_perception_msgs/msg/predicted_path.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/twist.hpp>
#include <autoware_internal_planning_msgs/msg/planning_factor_array.hpp>

#include <cmath>
#include <string>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_freespace_planning_algorithms</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_interpolation</depend>
<depend>autoware_lane_departure_checker</depend>
<depend>autoware_lanelet2_extension</depend>
Expand All @@ -64,7 +65,6 @@
<depend>rclcpp</depend>
<depend>tf2</depend>
<depend>tier4_planning_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
<depend>autoware_behavior_velocity_planner</depend>
<depend>autoware_behavior_velocity_planner_common</depend>
<depend>autoware_behavior_velocity_rtc_interface</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_perception_msgs</depend>
Expand All @@ -32,7 +33,6 @@
<depend>rclcpp</depend>
<depend>tf2</depend>
<depend>tier4_planning_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -103,9 +103,9 @@ void BlindSpotModule::reactRTCApprovalByDecision(
const auto stop_pose = path->points.at(decision.stop_line_idx).point.pose;
planning_factor_interface_->add(
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
autoware_internal_planning_msgs::msg::PlanningFactor::STOP, autoware_internal_planning_msgs::msg::SafetyFactorArray{},
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/,
"blind_spot(module is judging as UNSAFE)");
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
0.0 /*shift distance*/, "blind_spot(module is judging as UNSAFE)");
}
return;
}
Expand Down Expand Up @@ -137,9 +137,9 @@ void BlindSpotModule::reactRTCApprovalByDecision(
const auto stop_pose = path->points.at(decision.stop_line_idx).point.pose;
planning_factor_interface_->add(
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
autoware_internal_planning_msgs::msg::PlanningFactor::STOP, autoware_internal_planning_msgs::msg::SafetyFactorArray{},
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/,
"blind_spot(module is judging as SAFE and RTC is not approved)");
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
0.0 /*shift distance*/, "blind_spot(module is judging as SAFE and RTC is not approved)");
}
return;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
<depend>autoware_behavior_velocity_rtc_interface</depend>
<depend>autoware_grid_map_utils</depend>
<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_interpolation</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_motion_utils</depend>
Expand All @@ -45,7 +46,6 @@
<depend>rclcpp</depend>
<depend>sensor_msgs</depend>
<depend>visualization_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1366,8 +1366,8 @@ void CrosswalkModule::planStop(
planning_factor_interface_->add(
ego_path.points, planner_data_->current_odometry->pose, stop_factor->stop_pose,
stop_factor->stop_pose, autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0 /*velocity*/,
0.0 /*shift distance*/, "crosswalk_stop");
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/,
0.0 /*velocity*/, 0.0 /*shift distance*/, "crosswalk_stop");
}

bool CrosswalkModule::checkRestartSuppression(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -182,8 +182,9 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path)
{
planning_factor_interface_->add(
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
autoware_internal_planning_msgs::msg::PlanningFactor::STOP, autoware_internal_planning_msgs::msg::SafetyFactorArray{},
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
0.0 /*shift distance*/, "");

Check warning on line 187 in planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

DetectionAreaModule::modifyPathVelocity already has high cyclomatic complexity, and now it increases in Lines of Code from 101 to 102. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
}

return true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
<depend>autoware_behavior_velocity_planner_common</depend>
<depend>autoware_behavior_velocity_rtc_interface</depend>
<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_interpolation</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_motion_utils</depend>
Expand All @@ -41,7 +42,6 @@
<depend>rclcpp</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tier4_planning_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -158,8 +158,9 @@ bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path)
const auto & stop_pose = path->points.at(stopline_idx).point.pose;
planning_factor_interface_->add(
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
autoware_internal_planning_msgs::msg::PlanningFactor::STOP, autoware_internal_planning_msgs::msg::SafetyFactorArray{},
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "merge_from_private");
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
0.0 /*shift distance*/, "merge_from_private");

Check warning on line 163 in planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

MergeFromPrivateRoadModule::modifyPathVelocity already has high cyclomatic complexity, and now it increases in Lines of Code from 74 to 75. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

const double signed_arc_dist_to_stop_point = autoware::motion_utils::calcSignedArcLength(
path->points, current_pose.position, path->points.at(stopline_idx).point.pose.position);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -168,8 +168,9 @@ void NoDrivableLaneModule::handle_approaching_state(PathWithLaneId * path)
const auto & stop_pose = op_stop_pose.value();
planning_factor_interface_->add(
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
autoware_internal_planning_msgs::msg::PlanningFactor::STOP, autoware_internal_planning_msgs::msg::SafetyFactorArray{},
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,

Check warning on line 172 in planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp#L172

Added line #L172 was not covered by tests
0.0 /*shift distance*/, "");

const auto virtual_wall_pose = autoware::motion_utils::calcLongitudinalOffsetPose(
path->points, stop_pose.position, debug_data_.base_link2front);
Expand Down Expand Up @@ -218,8 +219,9 @@ void NoDrivableLaneModule::handle_inside_no_drivable_lane_state(PathWithLaneId *
const auto & stop_pose = autoware_utils::get_pose(path->points.at(0));
planning_factor_interface_->add(
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
autoware_internal_planning_msgs::msg::PlanningFactor::STOP, autoware_internal_planning_msgs::msg::SafetyFactorArray{},
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,

Check warning on line 223 in planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp#L223

Added line #L223 was not covered by tests
0.0 /*shift distance*/, "");

const auto & virtual_wall_pose = autoware::motion_utils::calcLongitudinalOffsetPose(
path->points, stop_pose.position, debug_data_.base_link2front);
Expand Down Expand Up @@ -258,8 +260,9 @@ void NoDrivableLaneModule::handle_stopped_state(PathWithLaneId * path)
const auto & stop_pose = ego_pos_on_path.pose;
planning_factor_interface_->add(
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
autoware_internal_planning_msgs::msg::PlanningFactor::STOP, autoware_internal_planning_msgs::msg::SafetyFactorArray{},
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,

Check warning on line 264 in planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp#L264

Added line #L264 was not covered by tests
0.0 /*shift distance*/, "");

const auto virtual_wall_pose = autoware::motion_utils::calcLongitudinalOffsetPose(
path->points, stop_pose.position, debug_data_.base_link2front);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
<depend>autoware_behavior_velocity_planner</depend>
<depend>autoware_behavior_velocity_planner_common</depend>
<depend>autoware_behavior_velocity_rtc_interface</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_interpolation</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_motion_utils</depend>
Expand All @@ -32,7 +33,6 @@
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>tier4_planning_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -769,8 +769,9 @@ bool RunOutModule::insertStopPoint(

planning_factor_interface_->add(
path.points, planner_data_->current_odometry->pose, stop_point.value(), stop_point.value(),
autoware_internal_planning_msgs::msg::PlanningFactor::STOP, autoware_internal_planning_msgs::msg::SafetyFactorArray{},
true /*is_driving_forward*/, 0.0 /*velocity*/, 0.0 /*shift_distance*/, "run_out_stop");
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/,
0.0 /*velocity*/, 0.0 /*shift_distance*/, "run_out_stop");

return true;
}
Expand Down Expand Up @@ -884,8 +885,8 @@ void RunOutModule::insertApproachingVelocity(
planning_factor_interface_->add(
output_path.points, planner_data_->current_odometry->pose, stop_point.value(),
stop_point.value(), autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0 /*velocity*/,
0.0 /*shift_distance*/, "run_out_approaching_velocity");
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/,
0.0 /*velocity*/, 0.0 /*shift_distance*/, "run_out_approaching_velocity");

// debug
debug_ptr_->pushStopPose(autoware_utils::calc_offset_pose(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,8 +68,9 @@ bool StopLineModule::modifyPathVelocity(PathWithLaneId * path)
planning_factor_interface_->add(
path->points, trajectory->compute(*stop_point).point.pose,
planner_data_->current_odometry->pose, planner_data_->current_odometry->pose,
autoware_internal_planning_msgs::msg::PlanningFactor::STOP, autoware_internal_planning_msgs::msg::SafetyFactorArray{},
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "stopline");
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
0.0 /*shift distance*/, "stopline");

updateStateAndStoppedTime(
&state_, &stopped_time_, clock_->now(), *stop_point - ego_s, planner_data_->isVehicleStopped());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
<depend>autoware_behavior_velocity_planner</depend>
<depend>autoware_behavior_velocity_planner_common</depend>
<depend>autoware_behavior_velocity_rtc_interface</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_perception_msgs</depend>
Expand All @@ -37,7 +38,6 @@
<depend>tf2_eigen</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tier4_planning_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -297,8 +297,9 @@ autoware_internal_planning_msgs::msg::PathWithLaneId TrafficLightModule::insertS
planning_factor_interface_->add(
modified_path.points, planner_data_->current_odometry->pose,
target_point_with_lane_id.point.pose, target_point_with_lane_id.point.pose,
autoware_internal_planning_msgs::msg::PlanningFactor::STOP, autoware_internal_planning_msgs::msg::SafetyFactorArray{},
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
0.0 /*shift distance*/, "");

return modified_path;
}
Expand Down
Loading

0 comments on commit ac43cce

Please sign in to comment.