diff --git a/nav2_costmap_2d/src/observation_buffer.cpp b/nav2_costmap_2d/src/observation_buffer.cpp
index 2dbfe63aa80272f2e9880cabc6da694c3e9345ce..c1d1a44fd25551e4dcee28979ea4ce9e18ac7e65 100644
--- a/nav2_costmap_2d/src/observation_buffer.cpp
+++ b/nav2_costmap_2d/src/observation_buffer.cpp
@@ -52,8 +52,9 @@ ObservationBuffer::ObservationBuffer(
   double min_obstacle_height, double max_obstacle_height, double obstacle_range,
   double raytrace_range, tf2_ros::Buffer & tf2_buffer, std::string global_frame,
   std::string sensor_frame, double tf_tolerance)
-: tf2_buffer_(tf2_buffer), observation_keep_time_(observation_keep_time, 0),
-  expected_update_rate_(expected_update_rate, 0), nh_(nh),
+: tf2_buffer_(tf2_buffer),
+  observation_keep_time_(rclcpp::Duration::from_seconds(observation_keep_time)),
+  expected_update_rate_(rclcpp::Duration::from_seconds(expected_update_rate)), nh_(nh),
   last_updated_(nh->now()), global_frame_(global_frame), sensor_frame_(sensor_frame),
   topic_name_(topic_name),
   min_obstacle_height_(min_obstacle_height), max_obstacle_height_(max_obstacle_height),