diff --git a/op_local_planner/launch/op_common_params.launch b/op_local_planner/launch/op_common_params.launch
index eae84276..a1550f1c 100644
--- a/op_local_planner/launch/op_common_params.launch
+++ b/op_local_planner/launch/op_common_params.launch
@@ -29,7 +29,7 @@
-
+
@@ -92,6 +92,7 @@
+
diff --git a/op_local_planner/nodes/op_behavior_selector/op_behavior_selector_core.cpp b/op_local_planner/nodes/op_behavior_selector/op_behavior_selector_core.cpp
index d73a3ef8..5a7bd678 100644
--- a/op_local_planner/nodes/op_behavior_selector/op_behavior_selector_core.cpp
+++ b/op_local_planner/nodes/op_behavior_selector/op_behavior_selector_core.cpp
@@ -135,7 +135,7 @@ void BehaviorGen::UpdatePlanningParams(ros::NodeHandle& _nh)
_nh.getParam("/op_common_params/horizontalSafetyDistance", m_PlanningParams.horizontalSafetyDistancel);
_nh.getParam("/op_common_params/verticalSafetyDistance", m_PlanningParams.verticalSafetyDistance);
-
+ _nh.getParam("/op_common_params/enableFinalLocalPathUpdate", m_PlanningParams.enableFinalLocalPathUpdate);
_nh.getParam("/op_common_params/enableLaneChange", m_PlanningParams.enableLaneChange);
_nh.getParam("/op_common_params/front_length", m_CarInfo.front_length);