Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 0 additions & 13 deletions nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
1 change: 1 addition & 0 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down