From 416b1536df8b330c53a5b48fc25a4a53218a6b73 Mon Sep 17 00:00:00 2001 From: stevemacenski Date: Thu, 16 Jun 2022 12:56:35 -0700 Subject: [PATCH] adding plugin type for static in local + removing unused print --- .../include/nav2_behaviors/timed_behavior.hpp | 13 ------------- nav2_bringup/params/nav2_params.yaml | 1 + 2 files changed, 1 insertion(+), 13 deletions(-) diff --git a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp index d696607feb..0c41b13f49 100644 --- a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp +++ b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp @@ -196,19 +196,6 @@ class TimedBehavior : public nav2_core::Behavior return; } - // Log a message every second - { - auto node = node_.lock(); - if (!node) { - throw std::runtime_error{"Failed to lock node"}; - } - - auto timer = node->create_wall_timer( - 1s, - [&]() - {RCLCPP_INFO(logger_, "%s running...", behavior_name_.c_str());}); - } - auto start_time = steady_clock_.now(); // Initialize the ActionT result diff --git a/nav2_bringup/params/nav2_params.yaml b/nav2_bringup/params/nav2_params.yaml index 51163b3775..7180548b82 100644 --- a/nav2_bringup/params/nav2_params.yaml +++ b/nav2_bringup/params/nav2_params.yaml @@ -214,6 +214,7 @@ local_costmap: obstacle_max_range: 2.5 obstacle_min_range: 0.0 static_layer: + plugin: "nav2_costmap_2d::StaticLayer" map_subscribe_transient_local: True always_send_full_costmap: True