diff --git a/nav2_costmap_2d/plugins/range_sensor_layer.cpp b/nav2_costmap_2d/plugins/range_sensor_layer.cpp
index ff71fa8edf1ce1aa103994e824c1fa8c817356d9..3d0f728bfb7d37d7e44cc25a48ed6eef199fd099 100644
--- a/nav2_costmap_2d/plugins/range_sensor_layer.cpp
+++ b/nav2_costmap_2d/plugins/range_sensor_layer.cpp
@@ -77,7 +77,7 @@ void RangeSensorLayer::onInitialize()
   declareParameter("phi", rclcpp::ParameterValue(1.2));
   node->get_parameter(name_ + "." + "phi", phi_v_);
   declareParameter("inflate_cone", rclcpp::ParameterValue(1.0));
-  node->get_parameter(name_ + "." + "phi", phi_v_);
+  node->get_parameter(name_ + "." + "inflate_cone", inflate_cone_);
   declareParameter("no_readings_timeout", rclcpp::ParameterValue(0.0));
   node->get_parameter(name_ + "." + "no_readings_timeout", no_readings_timeout_);
   declareParameter("clear_threshold", rclcpp::ParameterValue(0.2));
diff --git a/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp b/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp
index ad1fb15d3a03c8eb1beee592a872d5f6c3fa7892..619613c6785836f77f2586566fb765bf72d4e51a 100644
--- a/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp
+++ b/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp
@@ -183,7 +183,7 @@ public:
     setPose(x, y, theta);
     publishFootprint();
     publishCostmap();
-    rclcpp::sleep_for(std::chrono::milliseconds(50));
+    rclcpp::sleep_for(std::chrono::milliseconds(1000));
     return collision_checker_->isCollisionFree(pose);
   }