Skip to content

Commit 1693bfa

Browse files
committed
fail
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 20e0340 commit 1693bfa

File tree

3 files changed

+5
-3
lines changed

3 files changed

+5
-3
lines changed

planning/autoware_path_optimizer/include/autoware/path_optimizer/mpt_optimizer.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -110,7 +110,8 @@ class MPTOptimizer
110110
const TrajectoryParam & traj_param, const std::shared_ptr<DebugData> debug_data_ptr,
111111
const std::shared_ptr<autoware_utils::TimeKeeper> time_keeper_);
112112

113-
std::vector<TrajectoryPoint> optimizeTrajectory(const PlannerData & planner_data);
113+
std::vector<TrajectoryPoint> optimizeTrajectory(
114+
const PlannerData & planner_data, const bool empty);
114115
std::optional<std::vector<TrajectoryPoint>> getPrevOptimizedTrajectoryPoints() const;
115116

116117
void initialize(const bool enable_debug_info, const TrajectoryParam & traj_param);

planning/autoware_path_optimizer/src/mpt_optimizer.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -472,7 +472,8 @@ void MPTOptimizer::onParam(const std::vector<rclcpp::Parameter> & parameters)
472472
debug_data_ptr_->mpt_visualize_sampling_num = mpt_param_.mpt_visualize_sampling_num;
473473
}
474474

475-
std::vector<TrajectoryPoint> MPTOptimizer::optimizeTrajectory(const PlannerData & planner_data)
475+
std::vector<TrajectoryPoint> MPTOptimizer::optimizeTrajectory(
476+
const PlannerData & planner_data, [[maybe_unused]] const bool empty)
476477
{
477478
autoware_utils::ScopedTimeTrack st(__func__, *time_keeper_);
478479

planning/autoware_path_optimizer/src/node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -363,7 +363,7 @@ std::vector<TrajectoryPoint> PathOptimizer::optimizeTrajectory(const PlannerData
363363

364364
// 2. make trajectory kinematically-feasible and collision-free (= inside the drivable area)
365365
// with model predictive trajectory
366-
const auto mpt_traj = mpt_optimizer_ptr_->optimizeTrajectory(planner_data);
366+
const auto mpt_traj = mpt_optimizer_ptr_->optimizeTrajectory(planner_data, false);
367367

368368
return mpt_traj;
369369
}

0 commit comments

Comments
 (0)