Skip to content

Commit a42c37b

Browse files
PanConChicharronsaka1-s
authored andcommitted
fix(autoware_path_optimizer): hotfix for wrong logic triggering MRM on start in 3 seconds (#1916)
fix Signed-off-by: Arjun Jagdish Ram <arjun.ram@tier4.jp>
1 parent 8cccb48 commit a42c37b

File tree

1 file changed

+1
-1
lines changed
  • planning/autoware_path_optimizer/src

1 file changed

+1
-1
lines changed

planning/autoware_path_optimizer/src/node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -390,7 +390,7 @@ std::vector<TrajectoryPoint> PathOptimizer::optimizeTrajectory(const PlannerData
390390
// with model predictive trajectory
391391
const auto mpt_traj = mpt_optimizer_ptr_->optimizeTrajectory(planner_data);
392392

393-
const bool optimized_traj_failed = static_cast<bool>(mpt_traj);
393+
const bool optimized_traj_failed = !static_cast<bool>(mpt_traj);
394394

395395
conditional_timer_->update(optimized_traj_failed);
396396

0 commit comments

Comments
 (0)