Skip to content

Commit bfbe80e

Browse files
authored
fix(autoware_behavior_path_static_obstacle_avoidance_module): fix duplicateCondition warnings (#7582)
Signed-off-by: Ryuta Kambe <ryuta.kambe@tier4.jp>
1 parent 67c76b3 commit bfbe80e

File tree

1 file changed

+13
-23
lines changed
  • planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src

1 file changed

+13
-23
lines changed

planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp

+13-23
Original file line numberDiff line numberDiff line change
@@ -573,55 +573,45 @@ MarkerArray createDebugMarkerArray(
573573
addObjects(data.other_objects, ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE);
574574
}
575575

576-
// shift line pre-process
577576
if (parameters->enable_shift_line_marker) {
577+
// shift line pre-process
578578
addAvoidLine(debug.step1_registered_shift_line, "step1_registered_shift_line", 0.2, 0.2, 1.0);
579579
addAvoidLine(debug.step1_current_shift_line, "step1_current_shift_line", 0.2, 0.4, 0.8, 0.3);
580580
addAvoidLine(debug.step1_merged_shift_line, "step1_merged_shift_line", 0.2, 0.6, 0.6, 0.3);
581581
addAvoidLine(debug.step1_filled_shift_line, "step1_filled_shift_line", 0.2, 0.8, 0.4, 0.3);
582582
addAvoidLine(debug.step1_return_shift_line, "step1_return_shift_line", 0.2, 1.0, 0.2, 0.3);
583-
}
584583

585-
// merge process
586-
if (parameters->enable_shift_line_marker) {
584+
// merge process
587585
addAvoidLine(debug.step2_merged_shift_line, "step2_merged_shift_line", 0.2, 1.0, 0.0, 0.3);
588-
}
589586

590-
// trimming process
591-
if (parameters->enable_shift_line_marker) {
587+
// trimming process
592588
addAvoidLine(debug.step3_grad_filtered_1st, "step3_grad_filtered_1st", 0.2, 0.8, 0.0, 0.3);
593589
addAvoidLine(debug.step3_grad_filtered_2nd, "step3_grad_filtered_2nd", 0.4, 0.6, 0.0, 0.3);
594590
addAvoidLine(debug.step3_grad_filtered_3rd, "step3_grad_filtered_3rd", 0.6, 0.4, 0.0, 0.3);
595-
}
596591

597-
// registering process
598-
if (parameters->enable_shift_line_marker) {
592+
// registering process
599593
addShiftLine(shifter.getShiftLines(), "step4_old_shift_line", 1.0, 1.0, 0.0, 0.3);
600594
addAvoidLine(data.new_shift_line, "step4_new_shift_line", 1.0, 0.0, 0.0, 0.3);
601-
}
602-
603-
// safety check
604-
if (parameters->enable_safety_check_marker) {
605-
add(showSafetyCheckInfo(debug.collision_check, "object_debug_info"));
606-
add(showPredictedPath(debug.collision_check, "ego_predicted_path"));
607-
add(showPolygon(debug.collision_check, "ego_and_target_polygon_relation"));
608-
}
609595

610-
// shift length
611-
if (parameters->enable_shift_line_marker) {
596+
// shift length
612597
addShiftLength(debug.pos_shift, "merged_length_pos", 0.0, 0.7, 0.5);
613598
addShiftLength(debug.neg_shift, "merged_length_neg", 0.0, 0.5, 0.7);
614599
addShiftLength(debug.total_shift, "merged_length_total", 0.99, 0.4, 0.2);
615-
}
616600

617-
// shift grad
618-
if (parameters->enable_shift_line_marker) {
601+
// shift grad
619602
addShiftGrad(debug.pos_shift_grad, debug.pos_shift, "merged_grad_pos", 0.0, 0.7, 0.5);
620603
addShiftGrad(debug.neg_shift_grad, debug.neg_shift, "merged_grad_neg", 0.0, 0.5, 0.7);
621604
addShiftGrad(debug.total_forward_grad, debug.total_shift, "grad_forward", 0.99, 0.4, 0.2);
622605
addShiftGrad(debug.total_backward_grad, debug.total_shift, "grad_backward", 0.4, 0.2, 0.9);
623606
}
624607

608+
// safety check
609+
if (parameters->enable_safety_check_marker) {
610+
add(showSafetyCheckInfo(debug.collision_check, "object_debug_info"));
611+
add(showPredictedPath(debug.collision_check, "ego_predicted_path"));
612+
add(showPolygon(debug.collision_check, "ego_and_target_polygon_relation"));
613+
}
614+
625615
// detection area
626616
if (parameters->enable_detection_area_marker) {
627617
size_t i = 0;

0 commit comments

Comments
 (0)