diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp
index 59f6f20937f41..ace145bc5505f 100644
--- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp
+++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp
@@ -46,7 +46,6 @@ DetectionAreaModule::DetectionAreaModule(
   planner_param_(planner_param),
   debug_data_()
 {
-  velocity_factor_.init(PlanningBehavior::USER_DEFINED_DETECTION_AREA);
 }
 
 bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path)
@@ -180,9 +179,10 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path)
 
   // Create StopReason
   {
-    velocity_factor_.set(
-      path->points, planner_data_->current_odometry->pose, stop_point->second,
-      VelocityFactor::UNKNOWN);
+    planning_factor_interface_->add(
+      path->points, planner_data_->current_odometry->pose, stop_point->second, stop_point->second,
+      tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{},
+      true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
   }
 
   return true;
diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp
index bcb8b365f6205..82003f8f3881c 100644
--- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp
+++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp
@@ -50,7 +50,6 @@ NoStoppingAreaModule::NoStoppingAreaModule(
   planner_param_(planner_param),
   debug_data_()
 {
-  velocity_factor_.init(PlanningBehavior::NO_STOPPING_AREA);
   state_machine_.setState(StateMachine::State::GO);
   state_machine_.setMarginTime(planner_param_.state_clear_time);
 }
@@ -144,9 +143,11 @@ bool NoStoppingAreaModule::modifyPathVelocity(PathWithLaneId * path)
 
     // Create StopReason
     {
-      velocity_factor_.set(
-        path->points, planner_data_->current_odometry->pose, stop_point->second,
-        VelocityFactor::UNKNOWN);
+      planning_factor_interface_->add(
+        path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
+        tier4_planning_msgs::msg::PlanningFactor::STOP,
+        tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
+        0.0 /*shift distance*/, "");
     }
 
   } else if (state_machine_.getState() == StateMachine::State::GO) {
diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp
index 9ba7b0bccf1b9..a5779cfc0712a 100644
--- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp
+++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp
@@ -48,8 +48,6 @@ VirtualTrafficLightModule::VirtualTrafficLightModule(
   lane_(lane),
   planner_param_(planner_param)
 {
-  velocity_factor_.init(PlanningBehavior::VIRTUAL_TRAFFIC_LIGHT);
-
   // Get map data
   const auto instrument = reg_elem_.getVirtualTrafficLight();
   const auto instrument_bottom_line = toAutowarePoints(instrument);
@@ -420,9 +418,10 @@ void VirtualTrafficLightModule::insertStopVelocityAtStopLine(
   }
 
   // Set StopReason
-  velocity_factor_.set(
-    path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN,
-    command_.type);
+  planning_factor_interface_->add(
+    path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
+    tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{},
+    true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
 
   // Set data for visualization
   module_data_.stop_head_pose_at_stop_line =
@@ -453,8 +452,10 @@ void VirtualTrafficLightModule::insertStopVelocityAtEndLine(
   }
 
   // Set StopReason
-  velocity_factor_.set(
-    path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN);
+  planning_factor_interface_->add(
+    path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
+    tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{},
+    true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
 
   // Set data for visualization
   module_data_.stop_head_pose_at_end_line =
diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp
index 9e7a1192d9869..0661267b3d361 100644
--- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp
+++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp
@@ -113,10 +113,6 @@ class VirtualTrafficLightModule : public SceneModuleInterface
 
   void updateInfrastructureCommand();
 
-  void setVelocityFactor(
-    const geometry_msgs::msg::Pose & stop_pose,
-    autoware_adapi_v1_msgs::msg::VelocityFactor * velocity_factor);
-
   std::optional<size_t> getPathIndexOfFirstEndLine();
 
   bool isBeforeStartLine(const size_t end_line_idx);