Skip to content

Commit

Permalink
fail
Browse files Browse the repository at this point in the history
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
  • Loading branch information
takayuki5168 committed Mar 10, 2025
1 parent 2b88d03 commit 27d183d
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,8 @@ class MPTOptimizer
const TrajectoryParam & traj_param, const std::shared_ptr<DebugData> debug_data_ptr,
const std::shared_ptr<autoware_utils::TimeKeeper> time_keeper_);

std::vector<TrajectoryPoint> optimizeTrajectory(const PlannerData & planner_data);
std::vector<TrajectoryPoint> optimizeTrajectory(
const PlannerData & planner_data, const bool empty);
std::optional<std::vector<TrajectoryPoint>> getPrevOptimizedTrajectoryPoints() const;

void initialize(const bool enable_debug_info, const TrajectoryParam & traj_param);
Expand Down
3 changes: 2 additions & 1 deletion planning/autoware_path_optimizer/src/mpt_optimizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -472,7 +472,8 @@ void MPTOptimizer::onParam(const std::vector<rclcpp::Parameter> & parameters)
debug_data_ptr_->mpt_visualize_sampling_num = mpt_param_.mpt_visualize_sampling_num;
}

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

Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_path_optimizer/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -363,7 +363,7 @@ std::vector<TrajectoryPoint> PathOptimizer::optimizeTrajectory(const PlannerData

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

return mpt_traj;
}
Expand Down

0 comments on commit 27d183d

Please sign in to comment.