diff --git a/nav2_costmap_2d/plugins/range_sensor_layer.cpp b/nav2_costmap_2d/plugins/range_sensor_layer.cpp index ff71fa8edf..3d0f728bfb 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 ad1fb15d3a..619613c678 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 @@ class TestCollisionChecker : public nav2_util::LifecycleNode 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); }