diff --git a/control/autoware_shift_decider/CMakeLists.txt b/control/autoware_shift_decider/CMakeLists.txt
index 269b0fcc33690..7d26ce72188de 100644
--- a/control/autoware_shift_decider/CMakeLists.txt
+++ b/control/autoware_shift_decider/CMakeLists.txt
@@ -4,10 +4,18 @@ project(autoware_shift_decider)
 find_package(autoware_cmake REQUIRED)
 autoware_package()
 
+generate_parameter_library(shift_decider_parameters
+  param/shift_decider_parameters.yaml
+)
+
 ament_auto_add_library(${PROJECT_NAME}_node SHARED
   src/${PROJECT_NAME}.cpp
 )
 
+target_link_libraries(${PROJECT_NAME}_node
+  shift_decider_parameters
+)
+
 rclcpp_components_register_node(${PROJECT_NAME}_node
   PLUGIN "autoware::shift_decider::ShiftDecider"
   EXECUTABLE ${PROJECT_NAME}
diff --git a/control/autoware_shift_decider/include/autoware/shift_decider/autoware_shift_decider.hpp b/control/autoware_shift_decider/include/autoware/shift_decider/autoware_shift_decider.hpp
index c7ce822d1ac18..74990aa55a992 100644
--- a/control/autoware_shift_decider/include/autoware/shift_decider/autoware_shift_decider.hpp
+++ b/control/autoware_shift_decider/include/autoware/shift_decider/autoware_shift_decider.hpp
@@ -16,6 +16,7 @@
 #define AUTOWARE__SHIFT_DECIDER__AUTOWARE_SHIFT_DECIDER_HPP_
 
 #include "autoware/universe_utils/ros/polling_subscriber.hpp"
+#include "shift_decider_parameters.hpp"
 
 #include <rclcpp/rclcpp.hpp>
 
@@ -58,7 +59,8 @@ class ShiftDecider : public rclcpp::Node
   autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr current_gear_ptr_;
   uint8_t prev_shift_command = autoware_vehicle_msgs::msg::GearCommand::PARK;
 
-  bool park_on_goal_;
+  std::shared_ptr<::shift_decider::ParamListener> param_listener_;
+  ::shift_decider::Params param_;
 };
 }  // namespace autoware::shift_decider
 
diff --git a/control/autoware_shift_decider/package.xml b/control/autoware_shift_decider/package.xml
index fb7811e094dc2..27e814aac8401 100644
--- a/control/autoware_shift_decider/package.xml
+++ b/control/autoware_shift_decider/package.xml
@@ -17,6 +17,7 @@
   <depend>autoware_system_msgs</depend>
   <depend>autoware_universe_utils</depend>
   <depend>autoware_vehicle_msgs</depend>
+  <depend>generate_parameter_library</depend>
   <depend>rclcpp</depend>
   <depend>rclcpp_components</depend>
 
diff --git a/control/autoware_shift_decider/param/shift_decider_parameters.yaml b/control/autoware_shift_decider/param/shift_decider_parameters.yaml
new file mode 100644
index 0000000000000..294421d79cd6e
--- /dev/null
+++ b/control/autoware_shift_decider/param/shift_decider_parameters.yaml
@@ -0,0 +1,4 @@
+shift_decider:
+  park_on_goal:
+    type: bool
+    description: Whether to put the gear in park when vehicle reaches the goal.
diff --git a/control/autoware_shift_decider/src/autoware_shift_decider.cpp b/control/autoware_shift_decider/src/autoware_shift_decider.cpp
index 846eaabee4b88..c9c3b5cc6ad6d 100644
--- a/control/autoware_shift_decider/src/autoware_shift_decider.cpp
+++ b/control/autoware_shift_decider/src/autoware_shift_decider.cpp
@@ -31,7 +31,9 @@ ShiftDecider::ShiftDecider(const rclcpp::NodeOptions & node_options)
   rclcpp::QoS durable_qos(queue_size);
   durable_qos.transient_local();
 
-  park_on_goal_ = declare_parameter<bool>("park_on_goal");
+  param_listener_ =
+    std::make_shared<::shift_decider::ParamListener>(this->get_node_parameters_interface());
+  param_ = param_listener_->get_params();
 
   pub_shift_cmd_ =
     create_publisher<autoware_vehicle_msgs::msg::GearCommand>("output/gear_cmd", durable_qos);
@@ -71,7 +73,7 @@ void ShiftDecider::updateCurrentShiftCmd()
     if (
       (autoware_state_->state == AutowareState::ARRIVED_GOAL ||
        autoware_state_->state == AutowareState::WAITING_FOR_ROUTE) &&
-      park_on_goal_) {
+      param_.park_on_goal) {
       shift_cmd_.command = GearCommand::PARK;
     } else {
       shift_cmd_.command = current_gear_ptr_->report;