diff --git a/nav2_controller/src/progress_checker.cpp b/nav2_controller/src/progress_checker.cpp
index def27aaca521830ee4918fc3a2d1eb8d681fab1d..68fe96de50ccccc17af1fed28153f6184393c6c6 100644
--- a/nav2_controller/src/progress_checker.cpp
+++ b/nav2_controller/src/progress_checker.cpp
@@ -33,7 +33,7 @@ ProgressChecker::ProgressChecker(const rclcpp_lifecycle::LifecycleNode::SharedPt
     nh_, "movement_time_allowance", rclcpp::ParameterValue(10.0));
   // Scale is set to 0 by default, so if it was not set otherwise, set to 0
   nh_->get_parameter_or("required_movement_radius", radius_, 0.5);
-  double time_allowance_param;
+  double time_allowance_param = 0.0;
   nh_->get_parameter_or("movement_time_allowance", time_allowance_param, 10.0);
   time_allowance_ = rclcpp::Duration::from_seconds(time_allowance_param);
 }
diff --git a/nav2_dwb_controller/dwb_core/src/publisher.cpp b/nav2_dwb_controller/dwb_core/src/publisher.cpp
index f4e562ff29f753668fbdd57b8e647067b4dee7d0..0a3c8479123e1c169b3ad35114df565665b9222f 100644
--- a/nav2_dwb_controller/dwb_core/src/publisher.cpp
+++ b/nav2_dwb_controller/dwb_core/src/publisher.cpp
@@ -97,7 +97,7 @@ DWBPublisher::on_configure()
   marker_pub_ = node_->create_publisher<visualization_msgs::msg::MarkerArray>("marker", 1);
   cost_grid_pc_pub_ = node_->create_publisher<sensor_msgs::msg::PointCloud>("cost_cloud", 1);
 
-  double marker_lifetime;
+  double marker_lifetime = 0.0;
   node_->get_parameter(plugin_name_ + ".marker_lifetime", marker_lifetime);
   marker_lifetime_ = rclcpp::Duration::from_seconds(marker_lifetime);
 
diff --git a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/parameters.hpp b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/parameters.hpp
index a8fad52165e46b32b036e37fc104a1a35a6ae18d..a7a2f010ee87155fa477b1d7ba421ad13c211787 100644
--- a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/parameters.hpp
+++ b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/parameters.hpp
@@ -72,7 +72,7 @@ param_t searchAndGetParam(
   //   nh->param(resolved_name, value, default_value);
   //   return value;
   // }
-  param_t value;
+  param_t value = 0;
   nav2_util::declare_parameter_if_not_declared(
     nh, param_name,
     rclcpp::ParameterValue(default_value));
@@ -147,7 +147,7 @@ void moveParameter(
   const nav2_util::LifecycleNode::SharedPtr & nh, std::string old_name,
   std::string current_name, param_t default_value, bool should_delete = true)
 {
-  param_t value;
+  param_t value = 0;
   if (nh->get_parameter(current_name, value)) {
     if (should_delete) {nh->undeclare_parameter(old_name);}
     return;