diff --git a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp b/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp index e27fc9b6cfa81..6ea142ed66a1b 100644 --- a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp @@ -174,9 +174,6 @@ void VelocitySteeringFactorsPanel::onSteeringFactors(const SteeringFactorArray:: case SteeringFactor::APPROACHING: label->setText("APPROACHING"); break; - case SteeringFactor::TRYING: - label->setText("TRYING"); - break; case SteeringFactor::TURNING: label->setText("TURNING"); break; diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 9fd397bb8a8b1..12715520e1146 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -490,16 +490,10 @@ void BehaviorPathPlannerNode::publish_steering_factor( const auto [intersection_pose, intersection_distance] = planner_data->turn_signal_decider.getIntersectionPoseAndDistance(); - const uint16_t steering_factor_state = std::invoke([&intersection_flag]() { - if (intersection_flag) { - return SteeringFactor::TURNING; - } - return SteeringFactor::TRYING; - }); steering_factor_interface_ptr_->updateSteeringFactor( {intersection_pose, intersection_pose}, {intersection_distance, intersection_distance}, - PlanningBehavior::INTERSECTION, steering_factor_direction, steering_factor_state, ""); + PlanningBehavior::INTERSECTION, steering_factor_direction, SteeringFactor::TURNING, ""); } else { steering_factor_interface_ptr_->clearSteeringFactors(); } diff --git a/system/default_ad_api/src/planning.cpp b/system/default_ad_api/src/planning.cpp index 17491482a18fe..ed2dcee92eb2b 100644 --- a/system/default_ad_api/src/planning.cpp +++ b/system/default_ad_api/src/planning.cpp @@ -63,82 +63,6 @@ T merge_factors(const rclcpp::Time stamp, const std::vector(now(), velocity_factors_); auto steering = merge_factors(now(), steering_factors_); - // Set velocity factor type for compatibility. - for (auto & factor : velocity.factors) { - factor.type = convert_velocity_behavior(factor.behavior); - } - - // Set steering factor type for compatibility. - for (auto & factor : steering.factors) { - factor.type = convert_steering_behavior(factor.behavior); - } - // Set the distance if it is nan. if (trajectory_ && kinematic_state_) { for (auto & factor : velocity.factors) {