Skip to content

Tracking error layer#5605

Open
silanus23 wants to merge 35 commits intoros-navigation:mainfrom
silanus23:tracking_error_layer
Open

Tracking error layer#5605
silanus23 wants to merge 35 commits intoros-navigation:mainfrom
silanus23:tracking_error_layer

Conversation

@silanus23
Copy link
Contributor

@silanus23 silanus23 commented Oct 13, 2025


Basic Info

Info Please fill out this column
Ticket(s) this addresses #5037
Primary OS tested on Ubuntu
Robotic platform tested on nav2 bringup
Does this PR contain AI generated software? util tests
Was this PR description generated by AI software? Nope

Description of contribution in a few bullet points

I have added a layer that can draw a corridor around path with obstacles. In addition I added a geometry util that can draw smoother lines.

Description of documentation updates required from your changes

A costmap layer and it's params

Description of how this change was tested

Wrote a unit test and I have seen visually it is working


Future work that may be required in bullet points

Tests definitely need a see throgh.

Note:

I had to copy paste and carry changes to a new branch. Like I did on the prev 2 PR. This going to make me move with less burden. Commits look lesser and rushy but they ain't.

For Maintainers:

  • Check that any new parameters added are updated in docs.nav2.org
  • Check that any significant change is added to the migration guide
  • Check that any new features OR changes to existing behaviors are reflected in the tuning guide
  • Check that any new functions have Doxygen added
  • Check that any new features have test coverage
  • Check that any new plugins is added to the plugins page
  • If BT Node, Additionally: add to BT's XML index of nodes for groot, BT package's readme table, and BT library lists
  • Should this be backported to current distributions? If so, tag with backport-*.

Copy link
Member

@SteveMacenski SteveMacenski left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'd recommend spending some time to think about how we can most optimally compute this since this is going to be a little heavy so its worth some performance considerations.

Off the cuff:

  • We don't really need to store an internal representation of the layer at all, so this could derive from the Layer rather than CostmapLayer since we shouldn't really need the internal costmap structure.
  • We default assume all points are lethal unless proven otherwise in the for each loop in the update window.
  • Given the path, we shift the path left/right by the left/right tolerances by the base frame. If we enclose the start of the path and the end of the path segment, we should end up with a polygon.
  • Using some polygon math, we can ID if a point is inside of that polygon or not. If inside, we set ignore. If outside, we set as lethal. We'd need to make sure this works with concave polygons since there's no promise that this is convex.

Also maybe ways that can improve the method you have now and/or convolved the path by some radius left/right?

We probably want this to mark more than just 1 cell around the boundary as lethal so that small quantization errors don't allow the system to break out. At least 3 cells thick, but also I was thinking perhaps it would be sensible to just default mark everything as occupied unless within the bounds of tracking. But maybe a "thick" line is fine actually if that gives us some computational gains :-)

this, std::placeholders::_1));

path_sub_ = node->create_subscription<nav_msgs::msg::Path>(
"/plan",
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Remove forward slash in both subscriptions

tracking_feedback_sub_ = node->create_subscription<nav2_msgs::msg::TrackingFeedback>(
"/tracking_feedback",
std::bind(&TrackingErrorLayer::trackingCallback, this, std::placeholders::_1),
rclcpp::QoS(10).reliable()
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

For all QoS: Use the established Nav2 policies in nav2_ros_common

std::bind(&TrackingErrorLayer::trackingCallback, this, std::placeholders::_1),
rclcpp::QoS(10).reliable()
);
tf_buffer_ = std::make_shared<tf2_ros::Buffer>(node->get_clock());
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You should have this already from base classes to this class. You shouldn't need to manually create another (which is very heavy)

Comment on lines +74 to +75
std::mutex path_mutex_;
std::mutex tracking_error_mutex_;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think you can get away with a single data mutex

return result;
}

TrackingErrorLayer::~TrackingErrorLayer()
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Move destructor right after the constructor

Comment on lines +354 to +359
void TrackingErrorLayer::reset() {}
void TrackingErrorLayer::activate() {enabled_ = true;}
void TrackingErrorLayer::deactivate() {enabled_ = false;}

void TrackingErrorLayer::onFootprintChanged() {}
void TrackingErrorLayer::cleanup() {}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Dont override if not implementing

Comment on lines +355 to +356
void TrackingErrorLayer::activate() {enabled_ = true;}
void TrackingErrorLayer::deactivate() {enabled_ = false;}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

These two should create / destroy the subscriptions

dyn_params_handler_.reset();
}

void TrackingErrorLayer::reset() {}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This should reset data and other states. Please check out other layers for example

@silanus23
Copy link
Contributor Author

silanus23 commented Dec 5, 2025

@SteveMacenski I deleted bresenham line drawer to make it faster. I think I fixed your review points. I think adding constraints as seperate obstacles is a better choice, cause if a user tries to use this on a bigger local costmap it can become a huge computation. Also with rasterization, sharp turns could create problems. Current version creates big distinct blocks (like watchtowers) one after another. This can be parameterized and improved later. Not looking good but would do the job I think.

@SteveMacenski
Copy link
Member

Related to your other PR, I'm passing off the first review stage to @mini-1235 and I'll come in afterwards

@SteveMacenski
Copy link
Member

@SteveMacenski I deleted bresenham line drawer to make it faster. I think I fixed your review points. I think adding constraints as seperate obstacles is a better choice, cause if a user tries to use this on a bigger local costmap it can become a huge computation. Also with rasterization, sharp turns could create problems. Current version creates big distinct blocks (like watchtowers) one after another. This can be parameterized and improved later. Not looking good but would do the job I think.

Can you show an image of this behavior for example?

Copy link
Member

@SteveMacenski SteveMacenski left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK I can't help myself, here's a few notes. I didn't look at the main get path segments / wall functions, but I looked at the layer boilerplate

<class type="nav2_costmap_2d::VoxelLayer" base_class_type="nav2_costmap_2d::Layer">
<description>Similar to obstacle costmap, but uses 3D voxel grid to store data.</description>
</class>
<class type="nav2_costmap_2d::TrackingErrorLayer" base_class_type="nav2_costmap_2d::Layer">
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe rename to BoundedTrackingErrorLayer since its adding bounds

namespace nav2_costmap_2d
{

TrackingErrorLayer::TrackingErrorLayer() {}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You can just set this to TrackingErrorLayer() = default; in the header file instead

Comment on lines +75 to +81
void TrackingErrorLayer::trackingCallback(
const nav2_msgs::msg::TrackingFeedback::SharedPtr msg)
{
std::lock_guard<std::mutex> lock(data_mutex_);
last_tracking_feedback_ = *msg;
}

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It would be good to check on timestamps to make sure these are sufficiently current


// Create subscriptions when layer is activated
path_sub_ = node->create_subscription<nav_msgs::msg::Path>(
"/plan",
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Remove forward slashes here and in the tracking feedback to let this work with namespaces

Copy link
Contributor Author

@silanus23 silanus23 Dec 5, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I have tried without "/" but didn't work. It wasn't subscribing to those topics. Am I doing anything else wrong about this?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ah. I know why. The costmap namespaces things on its topic. I think maybe instead you should make these parameters + add those parameters to the yaml file where there you set it.

Just make sure to use this function to parse the parameter https://github.com/ros-navigation/navigation2/blob/main/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp#L180. Grep the obstacle / static layer for use examples

Comment on lines +340 to +341
last_path_.poses.clear();
last_path_.header = std_msgs::msg::Header();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
last_path_.poses.clear();
last_path_.header = std_msgs::msg::Header();
last_path_ = nav_msgs::msg::Path();

@silanus23 silanus23 marked this pull request as ready for review December 8, 2025 15:53
Copilot AI review requested due to automatic review settings December 8, 2025 15:53
@silanus23
Copy link
Contributor Author

silanus23 commented Dec 8, 2025

image

@SteveMacenski currently looks like this. with bresenham function it was a smooth straight line.
About naming I though trackingbounds layer was better and shorter but if you want I can make it boundedtrackingerror. I couldn't find tf function you mentioned about path transforming. Can you help me about that? Or maybe I misunderstood you.

Copy link
Contributor

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

This PR introduces a new TrackingBoundsLayer costmap plugin that creates a corridor around the robot's path with obstacles, helping to constrain navigation within path boundaries. The implementation adds a new costmap layer, configuration parameters, and comprehensive unit tests.

Key Changes

  • Added TrackingBoundsLayer plugin that subscribes to path and tracking feedback topics to dynamically create corridor boundaries
  • Implemented wall point generation algorithm that calculates perpendicular boundaries around path segments
  • Added unit tests covering initialization, path segment extraction, wall point generation, and edge cases

Reviewed changes

Copilot reviewed 8 out of 8 changed files in this pull request and generated 19 comments.

Show a summary per file
File Description
nav2_util/include/nav2_util/geometry_utils.hpp Adds utility include for geometry operations
nav2_costmap_2d/include/nav2_costmap_2d/tracking_bounds_layer.hpp Defines the TrackingBoundsLayer class interface with lifecycle methods and member variables
nav2_costmap_2d/plugins/tracking_bounds_layer.cpp Implements the tracking bounds layer logic including callbacks, path segmentation, and costmap updates
nav2_costmap_2d/test/unit/tracking_bounds_layer_test.cpp Provides comprehensive unit tests for the new layer functionality
nav2_costmap_2d/test/unit/CMakeLists.txt Adds test target for tracking_bounds_layer_test
nav2_costmap_2d/CMakeLists.txt Integrates tracking_bounds_layer.cpp into the layers library
nav2_costmap_2d/costmap_plugins.xml Registers the TrackingBoundsLayer as a plugin
nav2_bringup/params/nav2_params.yaml Configures the tracking_bounds_layer in the local costmap with default parameters

Comment on lines +73 to +86
void TrackingBoundsLayer::pathCallback(const nav_msgs::msg::Path::SharedPtr msg)
{
std::lock_guard<std::mutex> lock(data_mutex_);
auto now = node_.lock()->now();
auto msg_time = rclcpp::Time(msg->header.stamp);
auto age = (now - msg_time).seconds();

if (age > 1.0) {
RCLCPP_WARN_THROTTLE(
node_.lock()->get_logger(),
*node_.lock()->get_clock(),
5000,
"Path is %.2f seconds old", age);
return;
Copy link

Copilot AI Dec 8, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Multiple calls to node_.lock() without checking if the lock is successful. If the node has been destroyed, this could lead to a crash. Store the locked node in a local variable and check it once at the beginning of the function.

Example fix:

void TrackingBoundsLayer::pathCallback(const nav_msgs::msg::Path::SharedPtr msg)
{
  std::lock_guard<std::mutex> lock(data_mutex_);
  auto node = node_.lock();
  if (!node) {
    return;
  }
  auto now = node->now();
  // ... rest of the function using 'node' instead of node_.lock()

Copilot uses AI. Check for mistakes.
enabled: True
look_ahead: 5.0
step: 5
corridor_width: 2.0
Copy link

Copilot AI Dec 8, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

[nitpick] The tracking_bounds_layer configuration is missing the tracking_feedback_topic and path_topic parameters. While these have defaults in the code ("tracking_feedback" and "plan"), they should be explicitly documented in the configuration file for clarity, especially since this is a new plugin. Add:

tracking_bounds_layer:
  plugin: "nav2_costmap_2d::TrackingBoundsLayer"
  enabled: True
  look_ahead: 5.0
  step: 5
  corridor_width: 2.0
  tracking_feedback_topic: "tracking_feedback"
  path_topic: "plan"
Suggested change
corridor_width: 2.0
corridor_width: 2.0
tracking_feedback_topic: "tracking_feedback"
path_topic: "plan"

Copilot uses AI. Check for mistakes.
@SteveMacenski
Copy link
Member

@SteveMacenski currently looks like this. with bresenham function it was a smooth straight line.

This doesn't look very dense / complete (?). I see large gaps there.

About naming I though trackingbounds layer was better and shorter but if you want I can make it boundedtrackingerror. I couldn't find tf function you mentioned about path transforming. Can you help me about that? Or maybe I misunderstood you.

Please update the name - I think the "Error" bit is an important clarification. You are correct on the TF thing - Maurice convinced me that my internal AI was hallucinating about it. That seems like something we should add to Nav2 utils.

@SteveMacenski
Copy link
Member

SteveMacenski commented Dec 9, 2025

Can you provide some updated picture + compute times? I think the density is worth it, but maybe there are other methods we could consider and/or optimize if the performance isn't high enough

@silanus23
Copy link
Contributor Author

silanus23 commented Dec 9, 2025

Screenshot from 2025-12-09 18-40-46 Screenshot from 2025-12-09 18-40-40

I can make lines thicker. About computation I can try to bring numbers but I gotta say my pc is extremely bad (gpu burnt and 5 y.o.) and didn't felt any diffirence.

@SteveMacenski
Copy link
Member

SteveMacenski commented Dec 9, 2025

Can we make the line at least 2 pixels thick? 1 pixel, as before, could cause issues if the search window is larger than 1 cell length (like smac, which is $\sqrt{2}$, so in some cases it could skip over a good chunk of a cell at an angle that would bypass that check when the 2 lethal cells added are not edge-connected but corner-connected)

@silanus23
Copy link
Contributor Author

Should I parameterize it?

@SteveMacenski
Copy link
Member

I think that might be good. Default at 2 though I think would be good.

@mergify
Copy link
Contributor

mergify bot commented Dec 12, 2025

This pull request is in conflict. Could you fix it @silanus23?

@silanus23
Copy link
Contributor Author

silanus23 commented Dec 12, 2025

@SteveMacenski I will solve conflict and open a doc. About computational weight I can bring actually numbers with perf but this can take too long in addition theoretically corridor logic (especially better in bigger local costmap bounds) and bresenham line function (specifically made for this usage) is the most performative choice I think. I still can bring out the numbers if you want.

@SteveMacenski
Copy link
Member

@mini-1235 is taking over the first set of reviews on this feature - please direct to him for now :-)

@silanus23 silanus23 force-pushed the tracking_error_layer branch from 52b0dba to 308b361 Compare December 13, 2025 21:06
@codecov
Copy link

codecov bot commented Dec 15, 2025

Codecov Report

❌ Patch coverage is 76.85185% with 50 lines in your changes missing coverage. Please review.

Files with missing lines Patch % Lines
...ostmap_2d/plugins/bounded_tracking_error_layer.cpp 74.74% 50 Missing ⚠️
Files with missing lines Coverage Δ
...e/nav2_costmap_2d/bounded_tracking_error_layer.hpp 100.00% <100.00%> (ø)
nav2_util/include/nav2_util/geometry_utils.hpp 97.72% <100.00%> (+0.50%) ⬆️
...ostmap_2d/plugins/bounded_tracking_error_layer.cpp 74.74% <74.74%> (ø)

... and 6 files with indirect coverage changes

🚀 New features to boost your workflow:
  • ❄️ Test Analytics: Detect flaky tests, report on failures, and find test suite problems.

@mini-1235
Copy link
Collaborator

Screenshot from 2025-12-09 18-40-46 Screenshot from 2025-12-09 18-40-40
I can make lines thicker. About computation I can try to bring numbers but I gotta say my pc is extremely bad (gpu burnt and 5 y.o.) and didn't felt any diffirence.

Hi @silanus23, regarding the visualization, I don't think it is very clear at the moment. It would also be helpful to get some metrics to see whether we are on the right track, especially to ensure this works well on weaker CPUs

@silanus23
Copy link
Contributor Author

silanus23 commented Dec 22, 2025

Hi @mini-1235 I am aware that a PC's cpu is enough to compensate diffirences so you are right about asking for metrics. I just wanted to point out no overflows and in complexity wise current one was the best I could find. I will try to bring out metrics . In addition Currently lines are parameterized and double thickness of those and the thickness is parameterized.

As a last note: I might be away for a short period soon, but I will jump back into this and all other pending PRs as soon as I return. :-)

@silanus23 silanus23 force-pushed the tracking_error_layer branch from fe89b10 to 3fd5bca Compare January 30, 2026 15:02
@silanus23
Copy link
Contributor Author

silanus23 commented Jan 30, 2026

Screenshot from 2026-01-30 08-42-48
  • After initial tests I've seen some optimizations needed and started to use existing functions instead bresenham.
  • I will put new performance reports of current as soon as I can.
  • After some tests on tb4 I have seen that creating lethal obstacles can stop path planner from finding shortest path and make obstacle avoidance problematic. I observed corridor was making robot stuck (couldn't see these problems on tb3 due to smaller env.). Current version is healthier and the only way to harmonize with path planner imo.

Signed-off-by: silanus23 <berkantali23@outlook.com>
Signed-off-by: silanus23 <berkantali23@outlook.com>
@SteveMacenski
Copy link
Member

That video look really nice! I didn't look through the code, but mostly my questions would be around performance to make sure its as light weight as it should be // the technique used. But for the general visible output, that's perfect: a wall of some non-trivial thickness to stop the robot from going around outside of bounds

Copy link
Collaborator

@mini-1235 mini-1235 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@silanus23 Could you explain the screenshot or the perf data? I am having a bit of trouble interpreting it on my end. Maybe you can also measure the CPU usage before and after enabling this layer + how long the heavy functions take to execute.

As a side note, I will be away starting next week to get some rest, so I might be a bit slower to respond here. I will still try to find some time to bring this to a complete state in my free time :)

this, std::placeholders::_1));
}

void BoundedTrackingErrorLayer::goalCallback(const geometry_msgs::msg::PoseStamped::SharedPtr msg)
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think you can use the last pose in the pathCallback to determine if the goal has changed

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Agreed!

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@silanus23 This is still valid

if (!enabled_.load()) {
return;
}
*min_x = std::min(*min_x, robot_x - look_ahead_);
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does this really work for global_costmap?

Copy link
Contributor Author

@silanus23 silanus23 Mar 9, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sorry I couldn't understand you in here. My aim is to creating a corridor for only a limited path segment ahead of the robot so in case of drawing circles it won't interfere with path installation or other things. Am I wrong about this? Is code shouldn't be providing this? Can you help me?

for (size_t i = 0; i < segment.poses.size(); ++i) {
const auto & pose = segment.poses[i];
geometry_msgs::msg::PoseStamped transformed_pose;
double timeout = (i == 0) ? 0.1 : 0.0;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You can get the transform_tolerance parameter like we did in other layers

@silanus23
Copy link
Contributor Author

silanus23 commented Mar 5, 2026

@mini-1235
I see the problem about perf now. Here are more refined outputs:
image

image

above 2 are about costmap layer's specific usage
image

Here is my complete usage with layer (I know nav2 shouldn't be taking this much in a laptop cpu)

image

This one is complete cpu usage without layer

pecified in parameter 'current_progress_checker'. Server will use only plugin loaded progress_checker . This warning will appear once.
[component_container_isolated-10] [WARN] [1772746583.044897198] [controller_server]: No path handler was specified in parameter 'current_path_handler'. Server will use only plugin loaded PathHandler . This warning will appear once.
[parameter_bridge-2] [INFO] [1772746583.098024514] [bridge_ros_gz]: Passing message from ROS geometry_msgs/msg/TwistStamped to Gazebo gz.msgs.Twist (showing msg only once per type)
[component_container_isolated-10] [INFO] [1772746583.137850830] [global_costmap.global_costmap]: getPathSegment took 28 microseconds
[component_container_isolated-10] [INFO] [1772746583.137987852] [global_costmap.global_costmap]: getWallPolygons took 21 microseconds
[component_container_isolated-10] [INFO] [1772746583.138156998] [global_costmap.global_costmap]: updateCosts took 357 microseconds (total time including transforms and polygon filling)
[component_container_isolated-10] [INFO] [1772746584.051703667] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746584.095130350] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746585.072078459] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746585.145145906] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746586.103135477] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746586.145117686] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746587.122532921] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746587.145123078] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746588.137911933] [global_costmap.global_costmap]: updateCosts took 122 microseconds (total time including transforms and polygon filling)
[component_container_isolated-10] [INFO] [1772746588.152476757] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746588.195117165] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746589.181945532] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746589.245130666] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746590.212234246] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746590.245143485] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746591.232525622] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746591.295132917] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746592.252451416] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746592.295122090] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746593.137825221] [global_costmap.global_costmap]: updateCosts took 76 microseconds (total time including transforms and polygon filling)
[component_container_isolated-10] [INFO] [1772746593.273142862] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746593.295140451] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746594.138171445] [global_costmap.global_costmap]: getPathSegment took 17 microseconds
[component_container_isolated-10] [INFO] [1772746594.138295128] [global_costmap.global_costmap]: getWallPolygons took 14 microseconds
[component_container_isolated-10] [INFO] [1772746594.292573883] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746594.345122363] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746595.311608509] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746595.345162375] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746596.342078507] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746596.395123244] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746597.352470730] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746597.395124340] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746598.381489563] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746598.445164084] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746599.137791272] [global_costmap.global_costmap]: updateCosts took 85 microseconds (total time including transforms and polygon filling)
[component_container_isolated-10] [INFO] [1772746599.402750130] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746599.445145243] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1772746600.431834320] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1772746600.495151616] [controller_server]: Passing new path to controller.

These ones are outputs when I put loggers

My summary:
CPU Usage Before/After:
The layer itself uses negligible CPU (<0.1%). The heavy functions you're concerned about (mutex locks and FastDDS messaging) are not caused by this layer—they're part of the general ROS2/Nav2 infrastructure overhead.
Execution Time:
(microsecond range based on the 0.00054% per-symbol cost).
Conclusion:
The 24-25% mutex locking overhead is from ROS2's internal communication, not code.

I am working on your reviews locally but I think we should continue to take goal change from other channels cause when change hit path it's a bit late I think. I am trying to delete layer's effect ASAP so path can react quicker and better. Previously when I tested I sensed a bit stuttering when taken from path.

As a last not:
Have a good rest :).

this, std::placeholders::_1));
}

void BoundedTrackingErrorLayer::goalCallback(const geometry_msgs::msg::PoseStamped::SharedPtr msg)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Agreed!

Comment on lines +163 to +192
if (!last_path_.poses.empty() && msg->poses.size() >= 2) {
size_t old_size = last_path_.poses.size();
size_t new_size = msg->poses.size();

if (old_size != new_size) {
path_discontinuity = true;
RCLCPP_DEBUG(
node->get_logger(),
"Path size changed from %zu to %zu, clearing corridor", old_size, new_size);
} else if (old_size >= 2) {
double threshold = corridor_width_ * 0.5;

// Compare midpoint and endpoint positions between old and new paths
// to detect significant path changes even when size remains the same
size_t old_mid_idx = old_size / 2;
size_t new_mid_idx = new_size / 2;
double mid_dx = msg->poses[new_mid_idx].pose.position.x -
last_path_.poses[old_mid_idx].pose.position.x;
double mid_dy = msg->poses[new_mid_idx].pose.position.y -
last_path_.poses[old_mid_idx].pose.position.y;
double mid_dist = std::hypot(mid_dx, mid_dy);

double end_dx = msg->poses.back().pose.position.x -
last_path_.poses.back().pose.position.x;
double end_dy = msg->poses.back().pose.position.y -
last_path_.poses.back().pose.position.y;
double end_dist = std::hypot(end_dx, end_dy);

if (mid_dist > threshold || end_dist > threshold) {
path_discontinuity = true;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is all of this really necessary? This seems overkill. Why not just change when the path is different using the geomery_msgs isPathUpdated method? Or just check if the goal has changed?

What's the benefit this draws so I understand - I'm sure there's something if you went through this effort

Comment on lines +542 to +547
{
std::lock_guard<std::mutex> lock(data_mutex_);
last_path_ = nav_msgs::msg::Path();
last_tracking_feedback_ = nav2_msgs::msg::TrackingFeedback();
last_goal_ = geometry_msgs::msg::PoseStamped();
}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'd just turn this into a function resetState that deactivate / reset uses. Right now reset() actually doesn't clear out all the stuff.

return;
}

std::lock_guard<std::mutex> lock(data_mutex_);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We could simply make these few values atomics so we don't have to mutex lock internally for callback states.

@SteveMacenski
Copy link
Member

@mini-1235 how does this compare to your work in terms of the wall generating method?

@silanus23
Copy link
Contributor Author

silanus23 commented Mar 6, 2026

@SteveMacenski gonna switch to isPathUpdated. In addition what do you think about the cpu usage? Is it bearable or should I try to lower it?

@SteveMacenski
Copy link
Member

I assume those gdb times are pre-optimized, yeah? Can you add timers in the costmap update in costmap ros layer updates and give the timer update metrics (and hell - the others too just for comparison). I'd just print all the times for update/costs and have the log include the layer's name. Include the keepout zone for that comparison. The TB4 demo would include that all.

…ctivate

Signed-off-by: silanus23 <berkantali23@outlook.com>
Signed-off-by: silanus23 <berkantali23@outlook.com>
@silanus23
Copy link
Contributor Author

silanus23 commented Mar 9, 2026

[component_container_isolated-10] [INFO] [1773036699.044470906] [global_costmap.global_costmap]: keepout_filter updateBounds time: 0.000007 s
[component_container_isolated-10] [INFO] [1773036699.044538581] [global_costmap.global_costmap]: static_layer updateCosts time: 0.000040 s
[component_container_isolated-10] [INFO] [1773036699.044608631] [global_costmap.global_costmap]: obstacle_layer updateCosts time: 0.000057 s
[component_container_isolated-10] [INFO] [1773036699.044698934] [nav2_costmap_2d]: bounded_tracking_error_layer updateCosts time: 0.000076 s
[component_container_isolated-10] [INFO] [1773036699.044974173] [global_costmap.global_costmap]: inflation_layer updateCosts time: 0.000262 s
[component_container_isolated-10] [INFO] [1773036699.045861629] [global_costmap.global_costmap]: keepout_filter updateCosts time: 0.000831 s
[component_container_isolated-10] [INFO] [1773036699.086099632] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773036699.127165936] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773036699.189893097] [local_costmap.local_costmap]: voxel_layer updateBounds time: 0.000404 s
[component_container_isolated-10] [INFO] [1773036699.189945128] [local_costmap.local_costmap]: inflation_layer updateBounds time: 0.000001 s
[component_container_isolated-10] [INFO] [1773036699.189988987] [local_costmap.local_costmap]: keepout_filter updateBounds time: 0.000027 s
[component_container_isolated-10] [INFO] [1773036699.190017063] [local_costmap.local_costmap]: voxel_layer updateCosts time: 0.000011 s
[component_container_isolated-10] [INFO] [1773036699.190040459] [local_costmap.local_costmap]: inflation_layer updateCosts time: 0.000012 s
[component_container_isolated-10] [INFO] [1773036699.190175949] [local_costmap.local_costmap]: keepout_filter updateCosts time: 0.000122 s
[component_container_isolated-10] [INFO] [1773036699.389942134] [local_costmap.local_costmap]: voxel_layer updateBounds time: 0.000445 s
[component_container_isolated-10] [INFO] [1773036699.390025802] [local_costmap.local_costmap]: inflation_layer updateBounds time: 0.000003 s
[component_container_isolated-10] [INFO] [1773036699.390143552] [local_costmap.local_costmap]: keepout_filter updateBounds time: 0.000031 s
[component_container_isolated-10] [INFO] [1773036699.390232179] [local_costmap.local_costmap]: voxel_layer updateCosts time: 0.000011 s
[component_container_isolated-10] [INFO] [1773036699.390258718] [local_costmap.local_costmap]: inflation_layer updateCosts time: 0.000011 s
[component_container_isolated-10] [INFO] [1773036699.390373535] [local_costmap.local_costmap]: keepout_filter updateCosts time: 0.000103 s
[component_container_isolated-10] [INFO] [1773036699.589757137] [local_costmap.local_costmap]: voxel_layer updateBounds time: 0.000284 s
[component_container_isolated-10] [INFO] [1773036699.589797295] [local_costmap.local_costmap]: inflation_layer updateBounds time: 0.000001 s
[component_container_isolated-10] [INFO] [1773036699.589820342] [local_costmap.local_costmap]: keepout_filter updateBounds time: 0.000009 s
[component_container_isolated-10] [INFO] [1773036699.589841713] [local_costmap.local_costmap]: voxel_layer updateCosts time: 0.000008 s
[component_container_isolated-10] [INFO] [1773036699.589862176] [local_costmap.local_costmap]: inflation_layer updateCosts time: 0.000011 s
[component_container_isolated-10] [INFO] [1773036699.589966587] [local_costmap.local_costmap]: keepout_filter updateCosts time: 0.000094 s
[component_container_isolated-10] [INFO] [1773036699.789810364] [local_costmap.local_costmap]: voxel_layer updateBounds time: 0.000316 s
[component_container_isolated-10] [INFO] [1773036699.789849474] [local_costmap.local_costmap]: inflation_layer updateBounds time: 0.000001 s
[component_container_isolated-10] [INFO] [1773036699.789876642] [local_costmap.local_costmap]: keepout_filter updateBounds time: 0.000014 s
[component_container_isolated-10] [INFO] [1773036699.789899969] [local_costmap.local_costmap]: voxel_layer updateCosts time: 0.000009 s
[component_container_isolated-10] [INFO] [1773036699.789922317] [local_costmap.local_costmap]: inflation_layer updateCosts time: 0.000010 s
[component_container_isolated-10] [INFO] [1773036699.790028474] [local_costmap.local_costmap]: keepout_filter updateCosts time: 0.000094 s
[component_container_isolated-10] [INFO] [1773036699.989913457] [local_costmap.local_costmap]: voxel_layer updateBounds time: 0.000406 s
[component_container_isolated-10] [INFO] [1773036699.989973519] [local_costmap.local_costmap]: inflation_layer updateBounds time: 0.000001 s
[component_container_isolated-10] [INFO] [1773036699.990028274] [local_costmap.local_costmap]: keepout_filter updateBounds time: 0.000038 s
[component_container_isolated-10] [INFO] [1773036699.990064660] [local_costmap.local_costmap]: voxel_layer updateCosts time: 0.000015 s
[component_container_isolated-10] [INFO] [1773036699.990123815] [local_costmap.local_costmap]: inflation_layer updateCosts time: 0.000015 s
[component_container_isolated-10] [INFO] [1773036699.990265520] [local_costmap.local_costmap]: keepout_filter updateCosts time: 0.000123 s
[component_container_isolated-10] [INFO] [1773036700.044374994] [global_costmap.global_costmap]: obstacle_layer updateBounds time: 0.000112 s
[component_container_isolated-10] [INFO] [1773036700.044481500] [nav2_costmap_2d]: bounded_tracking_error_layer updateBounds time: 0.000001 s
[component_container_isolated-10] [INFO] [1773036700.044494211] [global_costmap.global_costmap]: inflation_layer updateBounds time: 0.000002 s
[component_container_isolated-10] [INFO] [1773036700.044521938] [global_costmap.global_costmap]: keepout_filter updateBounds time: 0.000008 s
[component_container_isolated-10] [INFO] [1773036700.044594431] [global_costmap.global_costmap]: static_layer updateCosts time: 0.000040 s
[component_container_isolated-10] [INFO] [1773036700.044670836] [global_costmap.global_costmap]: obstacle_layer updateCosts time: 0.000062 s
[component_container_isolated-10] [INFO] [1773036700.044772453] [nav2_costmap_2d]: bounded_tracking_error_layer updateCosts time: 0.000086 s
[component_container_isolated-10] [INFO] [1773036700.045049090] [global_costmap.global_costmap]: inflation_layer updateCosts time: 0.000262 s
[component_container_isolated-10] [INFO] [1773036700.045790301] [global_costmap.global_costmap]: keepout_filter updateCosts time: 0.000670 s
[component_container_isolated-10] [INFO] [1773036700.116707806] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773036700.177314492] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773036700.199811055] [local_costmap.local_costmap]: voxel_layer updateBounds time: 0.000500 s
[component_container_isolated-10] [INFO] [1773036700.202059553] [local_costmap.local_costmap]: inflation_layer updateBounds time: 0.000002 s
[component_container_isolated-10] [INFO] [1773036700.202168363] [local_costmap.local_costmap]: keepout_filter updateBounds time: 0.000020 s
[component_container_isolated-10] [INFO] [1773036700.202844554] [local_costmap.local_costmap]: voxel_layer updateCosts time: 0.000139 s
[component_container_isolated-10] [INFO] [1773036700.202926476] [local_costmap.local_costmap]: inflation_layer updateCosts time: 0.000021 s
[component_container_isolated-10] [INFO] [1773036700.203105196] [local_costmap.local_costmap]: keepout_filter updateCosts time: 0.000156 s
[component_container_isolated-10] [INFO] [1773036700.390036419] [local_costmap.local_costmap]: voxel_layer updateBounds time: 0.000540 s
[component_container_isolated-10] [INFO] [1773036700.390139921] [local_costmap.local_costmap]: inflation_layer updateBounds time: 0.000002 s
[component_container_isolated-10] [INFO] [1773036700.390278274] [local_costmap.local_costmap]: keepout_filter updateBounds time: 0.000044 s
[component_container_isolated-10] [INFO] [1773036700.390336940] [local_costmap.local_costmap]: voxel_layer updateCosts time: 0.000025 s
[component_container_isolated-10] [INFO] [1773036700.390380730] [local_costmap.local_costmap]: inflation_layer updateCosts time: 0.000022 s
[component_container_isolated-10] [INFO] [1773036700.390611481] [local_costmap.local_costmap]: keepout_filter updateCosts time: 0.000212 s
[component_container_isolated-10] [INFO] [1773036700.589806458] [local_costmap.local_costmap]: voxel_layer updateBounds time: 0.000321 s
[component_container_isolated-10] [INFO] [1773036700.589849130] [local_costmap.local_costmap]: inflation_layer updateBounds time: 0.000001 s
[component_container_isolated-10] [INFO] [1773036700.589881885] [local_costmap.local_costmap]: keepout_filter updateBounds time: 0.000018 s
[component_container_isolated-10] [INFO] [1773036700.589912405] [local_costmap.local_costmap]: voxel_layer updateCosts time: 0.000010 s
[component_container_isolated-10] [INFO] [1773036700.589934754] [local_costmap.local_costmap]: inflation_layer updateCosts time: 0.000011 s
[component_container_isolated-10] [INFO] [1773036700.590043425] [local_costmap.local_costmap]: keepout_filter updateCosts time: 0.000096 s
[component_container_isolated-10] [INFO] [1773036700.789844822] [local_costmap.local_costmap]: voxel_layer updateBounds time: 0.000357 s
[component_container_isolated-10] [INFO] [1773036700.789895386] [local_costmap.local_costmap]: inflation_layer updateBounds time: 0.000002 s
[component_container_isolated-10] [INFO] [1773036700.789921506] [local_costmap.local_costmap]: keepout_filter updateBounds time: 0.000012 s
[component_container_isolated-10] [INFO] [1773036700.789947487] [local_costmap.local_costmap]: voxel_layer updateCosts time: 0.000010 s
[component_container_isolated-10] [INFO] [1773036700.789971372] [local_costmap.local_costmap]: inflation_layer updateCosts time: 0.000011 s
[component_container_isolated-10] [INFO] [1773036700.790096316] [local_costmap.local_costmap]: keepout_filter updateCosts time: 0.000113 s
[component_container_isolated-10] [INFO] [1773036700.990041304] [local_costmap.local_costmap]: voxel_layer updateBounds time: 0.000490 s
[component_container_isolated-10] [INFO] [1773036700.990147321] [local_costmap.local_costmap]: inflation_layer updateBounds time: 0.000002 s
[component_container_isolated-10] [INFO] [1773036700.990204101] [local_costmap.local_costmap]: keepout_filter updateBounds time: 0.000032 s
[component_container_isolated-10] [INFO] [1773036700.990257529] [local_costmap.local_costmap]: voxel_layer updateCosts time: 0.000025 s
[component_container_isolated-10] [INFO] [1773036700.990306626] [local_costmap.local_costmap]: inflation_layer updateCosts time: 0.000024 s
[component_container_isolated-10] [INFO] [1773036700.990553440] [local_costmap.local_costmap]: keepout_filter updateCosts time: 0.000223 s
[component_container_isolated-10] [INFO] [1773036701.044909523] [global_costmap.global_costmap]: obstacle_layer updateBounds time: 0.000118 s
[component_container_isolated-10] [INFO] [1773036701.045016797] [nav2_costmap_2d]: bounded_tracking_error_layer updateBounds time: 0.000000 s
[component_container_isolated-10] [INFO] [1773036701.045028740] [global_costmap.global_costmap]: inflation_layer updateBounds time: 0.000001 s
[component_container_isolated-10] [INFO] [1773036701.045054441] [global_costmap.global_costmap]: keepout_filter updateBounds time: 0.000008 s
[component_container_isolated-10] [INFO] [1773036701.045150331] [global_costmap.global_costmap]: static_layer updateCosts time: 0.000047 s
[component_container_isolated-10] [INFO] [1773036701.045238958] [global_costmap.global_costmap]: obstacle_layer updateCosts time: 0.000072 s
[component_container_isolated-10] [INFO] [1773036701.046922241] [nav2_costmap_2d]: bounded_tracking_error_layer updateCosts time: 0.000089 s
[component_container_isolated-10] [INFO] [1773036701.047142167] [global_costmap.global_costmap]: inflation_layer updateCosts time: 0.000197 s
[component_container_isolated-10] [INFO] [1773036701.048001966] [global_costmap.global_costmap]: keepout_filter updateCosts time: 0.000821 s
[component_container_isolated-10] [INFO] [1773036701.145069719] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773036701.177005363] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773036701.189816244] [local_costmap.local_costmap]: voxel_layer updateBounds time: 0.000333 s
[component_container_isolated-10] [INFO] [1773036701.189872047] [local_costmap.local_costmap]: inflation_layer updateBounds time: 0.000001 s
[component_container_isolated-10] [INFO] [1773036701.189904033] [local_costmap.local_costmap]: keepout_filter updateBounds time: 0.000017 s
[component_container_isolated-10] [INFO] [1773036701.189935461] [local_costmap.local_costmap]: voxel_layer updateCosts time: 0.000013 s
[component_container_isolated-10] [INFO] [1773036701.189964515] [local_costmap.local_costmap]: inflation_layer updateCosts time: 0.000015 s

Sorry. Lint probably slipped last second I will fix it at
first chance

…ling

Signed-off-by: silanus23 <berkantali23@outlook.com>
@SteveMacenski
Copy link
Member


[component_container_isolated-10] [INFO] [1773036701.045238958] [global_costmap.global_costmap]: obstacle_layer updateCosts time: 0.000072 s
[component_container_isolated-10] [INFO] [1773036701.046922241] [nav2_costmap_2d]: bounded_tracking_error_layer updateCosts time: 0.000089 s

It is unexpected to me that this is heavier than the obstacle layer, which should be processing alot more data (~1000 beams at 20hz). Anywhere we can improve the performance and/or rethink the underlying algorithm to be more light weight (or is my expectation unrealistic)?

Where's the compute time in this layer specifically? I'm thinking maybe its using transformPoseInTargetFrame. Instead, if you get the transform once, you can apply it yourself to the path points (which is a simple matrix multiplication) since the path poses and the global frame at a particular timestamp is the same for all poses.

I just looked at the implementation in detail: master_grid.setConvexPolygonCost(left_wall_polygon, corridor_cost_); --> clever 😉 Its worth seeing what the computational impact of this is though, this could be conceptually where the compute time is (not sure). I wouldn't assume that's a particularly efficient method.

@silanus23
Copy link
Contributor Author

silanus23 commented Mar 10, 2026

[component_container_isolated-10] [INFO] [1773124862.173205838] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000101 ms
[component_container_isolated-10] [INFO] [1773124862.173292754] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.015770 ms
[component_container_isolated-10] [INFO] [1773124862.173322822] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.019186 ms
[component_container_isolated-10] [INFO] [1773124862.326289724] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773124862.366847455] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773124862.373258076] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000150 ms
[component_container_isolated-10] [INFO] [1773124862.373321697] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.010219 ms
[component_container_isolated-10] [INFO] [1773124862.373358678] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.018926 ms
[component_container_isolated-10] [INFO] [1773124862.419023947] [controller_server]: scoreArcLength timing - Duration: 681 μs | Batch: 2000, Path segs: 65
[component_container_isolated-10] [INFO] [1773124862.419062811] [controller_server]: PathAlignCritic::score() timing - Duration: 856 μs | Batch: 2000, Path segs: 65
[rviz2-9] Start navigation
[rviz2-9] [INFO] [1773124862.482435277] [rviz_navigation_dialog_action_client]: NavigateToPose will be called using the BT Navigator's default behavior tree.
[component_container_isolated-10] [INFO] [1773124862.485892489] [bt_navigator]: Received goal preemption request
[component_container_isolated-10] [INFO] [1773124862.486336508] [bt_navigator]: Begin navigating from current location (10.18, 10.87) to (19.45, 13.94)
[component_container_isolated-10] [INFO] [1773124862.572997425] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000090 ms
[component_container_isolated-10] [INFO] [1773124862.573040477] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.007474 ms
[component_container_isolated-10] [INFO] [1773124862.573055125] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.008616 ms
[component_container_isolated-10] [INFO] [1773124862.773011059] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000090 ms
[component_container_isolated-10] [INFO] [1773124862.773053661] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.007444 ms
[component_container_isolated-10] [INFO] [1773124862.773067727] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.008776 ms
[component_container_isolated-10] [INFO] [1773124862.863177370] [global_costmap.global_costmap]: [ObstacleLayer] updateBounds: 0.089852 ms
[component_container_isolated-10] [INFO] [1773124862.863223589] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateBounds: 0.000121 ms
[component_container_isolated-10] [INFO] [1773124862.863232155] [global_costmap.global_costmap]: [InflationLayer] updateBounds: 0.000200 ms
[component_container_isolated-10] [INFO] [1773124862.863322999] [global_costmap.global_costmap]: [ObstacleLayer] updateCosts: 0.042602 ms
[component_container_isolated-10] [INFO] [1773124862.863345342] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateCosts: 0.015209 ms (total)
[component_container_isolated-10] [INFO] [1773124862.863691373] [global_costmap.global_costmap]: [InflationLayer] updateCosts: 0.340170 ms
[component_container_isolated-10] [INFO] [1773124862.973489662] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000220 ms
[component_container_isolated-10] [INFO] [1773124862.973606346] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.020429 ms
[component_container_isolated-10] [INFO] [1773124862.973646583] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.023835 ms
[component_container_isolated-10] [INFO] [1773124863.173113648] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000180 ms
[component_container_isolated-10] [INFO] [1773124863.173162702] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.007925 ms
[component_container_isolated-10] [INFO] [1773124863.173177500] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.009007 ms
[component_container_isolated-10] [INFO] [1773124863.345705292] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773124863.366807171] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773124863.373187303] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000120 ms
[component_container_isolated-10] [INFO] [1773124863.373255534] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.016261 ms
[component_container_isolated-10] [INFO] [1773124863.373293577] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.025208 ms
[component_container_isolated-10] [INFO] [1773124863.573036329] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000121 ms
[component_container_isolated-10] [INFO] [1773124863.573099169] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.010360 ms
[component_container_isolated-10] [INFO] [1773124863.573118556] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.011352 ms
[component_container_isolated-10] [INFO] [1773124863.773066942] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000090 ms
[component_container_isolated-10] [INFO] [1773124863.773137467] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.010760 ms
[component_container_isolated-10] [INFO] [1773124863.773159268] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.012263 ms
[component_container_isolated-10] [INFO] [1773124863.863238341] [global_costmap.global_costmap]: [ObstacleLayer] updateBounds: 0.133936 ms
[component_container_isolated-10] [INFO] [1773124863.863295640] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateBounds: 0.000150 ms
[component_container_isolated-10] [INFO] [1773124863.863307563] [global_costmap.global_costmap]: [InflationLayer] updateBounds: 0.000461 ms
[component_container_isolated-10] [INFO] [1773124863.863469242] [global_costmap.global_costmap]: [ObstacleLayer] updateCosts: 0.074412 ms
[component_container_isolated-10] [INFO] [1773124863.863530139] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateCosts: 0.049986 ms (total)
[component_container_isolated-10] [INFO] [1773124863.864416725] [global_costmap.global_costmap]: [InflationLayer] updateCosts: 0.869573 ms
[component_container_isolated-10] [INFO] [1773124863.973017111] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000050 ms
[component_container_isolated-10] [INFO] [1773124863.973060764] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.007785 ms
[component_container_isolated-10] [INFO] [1773124863.973076975] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.010600 ms
[component_container_isolated-10] [INFO] [1773124864.173347774] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000300 ms
[component_container_isolated-10] [INFO] [1773124864.173456502] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.023104 ms
[component_container_isolated-10] [INFO] [1773124864.173500546] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.025869 ms
[component_container_isolated-10] [INFO] [1773124864.365882828] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773124864.373294423] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000171 ms
[component_container_isolated-10] [INFO] [1773124864.373376219] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.021812 ms
[component_container_isolated-10] [INFO] [1773124864.373417047] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.028565 ms
[component_container_isolated-10] [INFO] [1773124864.416814617] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773124864.573066067] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000140 ms
[component_container_isolated-10] [INFO] [1773124864.573122064] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.008777 ms
[component_container_isolated-10] [INFO] [1773124864.573138134] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.010630 ms
[component_container_isolated-10] [INFO] [1773124864.773357174] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000211 ms
[component_container_isolated-10] [INFO] [1773124864.773441686] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.017523 ms
[component_container_isolated-10] [INFO] [1773124864.773474799] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.021812 ms
[component_container_isolated-10] [INFO] [1773124864.863283653] [global_costmap.global_costmap]: [ObstacleLayer] updateBounds: 0.147733 ms
[component_container_isolated-10] [INFO] [1773124864.864587346] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateBounds: 0.000180 ms
[component_container_isolated-10] [INFO] [1773124864.864619458] [global_costmap.global_costmap]: [InflationLayer] updateBounds: 0.000280 ms
[component_container_isolated-10] [INFO] [1773124864.864809952] [global_costmap.global_costmap]: [ObstacleLayer] updateCosts: 0.112566 ms
[component_container_isolated-10] [INFO] [1773124864.864853425] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateCosts: 0.027563 ms (total)
[component_container_isolated-10] [INFO] [1773124864.865807911] [global_costmap.global_costmap]: [InflationLayer] updateCosts: 0.939597 ms
[component_container_isolated-10] [INFO] [1773124864.973193511] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000100 ms
[component_container_isolated-10] [INFO] [1773124864.973275939] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.019498 ms
[component_container_isolated-10] [INFO] [1773124864.973317238] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.025309 ms
[component_container_isolated-10] [INFO] [1773124865.173202676] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000100 ms
[component_container_isolated-10] [INFO] [1773124865.173284723] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.019728 ms
[component_container_isolated-10] [INFO] [1773124865.173326834] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.025999 ms
[component_container_isolated-10] [INFO] [1773124865.373254172] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000181 ms
[component_container_isolated-10] [INFO] [1773124865.373334425] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.017133 ms
[component_container_isolated-10] [INFO] [1773124865.373369993] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.024737 ms
[component_container_isolated-10] [INFO] [1773124865.385663685] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773124865.416835062] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773124865.573129109] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000301 ms
[component_container_isolated-10] [INFO] [1773124865.573217559] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.015179 ms
[component_container_isolated-10] [INFO] [1773124865.573246233] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.020950 ms
[component_container_isolated-10] [INFO] [1773124865.773247653] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000110 ms
[component_container_isolated-10] [INFO] [1773124865.773320182] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.017013 ms
[component_container_isolated-10] [INFO] [1773124865.773352965] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.021541 ms
[component_container_isolated-10] [INFO] [1773124865.863155635] [global_costmap.global_costmap]: [ObstacleLayer] updateBounds: 0.065285 ms
[component_container_isolated-10] [INFO] [1773124865.863189420] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateBounds: 0.000121 ms
[component_container_isolated-10] [INFO] [1773124865.863196223] [global_costmap.global_costmap]: [InflationLayer] updateBounds: 0.000271 ms
[component_container_isolated-10] [INFO] [1773124865.863266728] [global_costmap.global_costmap]: [ObstacleLayer] updateCosts: 0.033915 ms
[component_container_isolated-10] [INFO] [1773124865.863287016] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateCosts: 0.014618 ms (total)
[component_container_isolated-10] [INFO] [1773124865.863643138] [global_costmap.global_costmap]: [InflationLayer] updateCosts: 0.349629 ms
[component_container_isolated-10] [INFO] [1773124865.973216550] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000141 ms
[component_container_isolated-10] [INFO] [1773124865.973275854] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.010961 ms
[component_container_isolated-10] [INFO] [1773124865.973302525] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.018987 ms
[component_container_isolated-10] [INFO] [1773124866.172996503] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000051 ms
[component_container_isolated-10] [INFO] [1773124866.173041309] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.007705 ms
[component_container_isolated-10] [INFO] [1773124866.173055075] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.008516 ms
[component_container_isolated-10] [INFO] [1773124866.373029159] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000130 ms
[component_container_isolated-10] [INFO] [1773124866.373081038] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.008055 ms
[component_container_isolated-10] [INFO] [1773124866.373097860] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.011101 ms
[component_container_isolated-10] [INFO] [1773124866.415679278] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773124866.466946868] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773124866.573313867] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000130 ms
[component_container_isolated-10] [INFO] [1773124866.573421543] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.021691 ms
[component_container_isolated-10] [INFO] [1773124866.573532735] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.097386 ms
[component_container_isolated-10] [INFO] [1773124866.772990722] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000050 ms
[component_container_isolated-10] [INFO] [1773124866.773034295] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.007765 ms
[component_container_isolated-10] [INFO] [1773124866.773074172] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.034547 ms
[component_container_isolated-10] [INFO] [1773124866.863257018] [global_costmap.global_costmap]: [ObstacleLayer] updateBounds: 0.137042 ms
[component_container_isolated-10] [INFO] [1773124866.863420150] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateBounds: 0.000271 ms
[component_container_isolated-10] [INFO] [1773124866.863434858] [global_costmap.global_costmap]: [InflationLayer] updateBounds: 0.000421 ms
[component_container_isolated-10] [INFO] [1773124866.863580456] [global_costmap.global_costmap]: [ObstacleLayer] updateCosts: 0.088920 ms
[component_container_isolated-10] [INFO] [1773124866.863617838] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateCosts: 0.025048 ms (total)
[component_container_isolated-10] [INFO] [1773124866.864353224] [global_costmap.global_costmap]: [InflationLayer] updateCosts: 0.722532 ms
[component_container_isolated-10] [INFO] [1773124866.973701465] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000180 ms
[component_container_isolated-10] [INFO] [1773124866.973784263] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.016873 ms
[component_container_isolated-10] [INFO] [1773124866.973874726] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.078050 ms
[component_container_isolated-10] [INFO] [1773124867.174840623] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000090 ms
[component_container_isolated-10] [INFO] [1773124867.174888695] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.007785 ms
[component_container_isolated-10] [INFO] [1773124867.174938160] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.042632 ms
[component_container_isolated-10] [INFO] [1773124867.373127316] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000071 ms
[component_container_isolated-10] [INFO] [1773124867.373199634] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.008887 ms
[component_container_isolated-10] [INFO] [1773124867.373256052] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.049885 ms
[component_container_isolated-10] [INFO] [1773124867.418835313] [controller_server]: scoreArcLength timing - Duration: 680 μs | Batch: 2000, Path segs: 68
[component_container_isolated-10] [INFO] [1773124867.418885679] [controller_server]: PathAlignCritic::score() timing - Duration: 839 μs | Batch: 2000, Path segs: 68
[component_container_isolated-10] [INFO] [1773124867.426784565] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773124867.466832217] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773124867.573102007] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000300 ms
[component_container_isolated-10] [INFO] [1773124867.573179375] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.011081 ms
[component_container_isolated-10] [INFO] [1773124867.573241534] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.055416 ms
[component_container_isolated-10] [INFO] [1773124867.773241043] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000221 ms
[component_container_isolated-10] [INFO] [1773124867.773320324] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.018836 ms
[component_container_isolated-10] [INFO] [1773124867.773447708] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.117104 ms
[component_container_isolated-10] [INFO] [1773124867.863343844] [global_costmap.global_costmap]: [ObstacleLayer] updateBounds: 0.220993 ms
[component_container_isolated-10] [INFO] [1773124867.863430039] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateBounds: 0.000160 ms
[component_container_isolated-10] [INFO] [1773124867.863452612] [global_costmap.global_costmap]: [InflationLayer] updateBounds: 0.001122 ms
[component_container_isolated-10] [INFO] [1773124867.863839522] [global_costmap.global_costmap]: [ObstacleLayer] updateCosts: 0.092086 ms
[component_container_isolated-10] [INFO] [1773124867.863928853] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateCosts: 0.042020 ms (total)
[component_container_isolated-10] [INFO] [1773124867.864774781] [global_costmap.global_costmap]: [InflationLayer] updateCosts: 0.820439 ms
[component_container_isolated-10] [INFO] [1773124867.973276420] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000110 ms
[component_container_isolated-10] [INFO] [1773124867.973369167] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.017634 ms
[component_container_isolated-10] [INFO] [1773124867.973506911] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.126122 ms
[component_container_isolated-10] [INFO] [1773124868.173297126] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000170 ms
[component_container_isolated-10] [INFO] [1773124868.173355117] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.011643 ms
[component_container_isolated-10] [INFO] [1773124868.173463374] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.101314 ms
[component_container_isolated-10] [INFO] [1773124868.373109503] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000401 ms
[component_container_isolated-10] [INFO] [1773124868.373258137] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.011452 ms
[component_container_isolated-10] [INFO] [1773124868.373344362] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.076657 ms
[component_container_isolated-10] [INFO] [1773124868.455736616] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773124868.516838782] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773124868.573058421] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000111 ms
[component_container_isolated-10] [INFO] [1773124868.573117284] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.009068 ms
[component_container_isolated-10] [INFO] [1773124868.573191065] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.066237 ms
[component_container_isolated-10] [INFO] [1773124868.773190329] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000471 ms
[component_container_isolated-10] [INFO] [1773124868.773301422] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.011292 ms
[component_container_isolated-10] [INFO] [1773124868.773381755] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.073951 ms
[component_container_isolated-10] [INFO] [1773124868.863236200] [global_costmap.global_costmap]: [ObstacleLayer] updateBounds: 0.131030 ms
[component_container_isolated-10] [INFO] [1773124868.863293179] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateBounds: 0.000130 ms
[component_container_isolated-10] [INFO] [1773124868.863306084] [global_costmap.global_costmap]: [InflationLayer] updateBounds: 0.000271 ms
[component_container_isolated-10] [INFO] [1773124868.863416876] [global_costmap.global_costmap]: [ObstacleLayer] updateCosts: 0.065104 ms
[component_container_isolated-10] [INFO] [1773124868.863461391] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateCosts: 0.030729 ms (total)
[component_container_isolated-10] [INFO] [1773124868.864500428] [global_costmap.global_costmap]: [InflationLayer] updateCosts: 1.020231 ms
[component_container_isolated-10] [INFO] [1773124868.973378084] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000180 ms
[component_container_isolated-10] [INFO] [1773124868.973478787] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.018275 ms
[component_container_isolated-10] [INFO] [1773124868.973674842] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.182129 ms
[component_container_isolated-10] [INFO] [1773124869.173117539] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000311 ms
[component_container_isolated-10] [INFO] [1773124869.173207451] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.015380 ms
[component_container_isolated-10] [INFO] [1773124869.173290269] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.076256 ms
[component_container_isolated-10] [INFO] [1773124869.373171284] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000420 ms
[component_container_isolated-10] [INFO] [1773124869.373236539] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.009078 ms
[component_container_isolated-10] [INFO] [1773124869.373309618] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.066487 ms
[component_container_isolated-10] [INFO] [1773124869.476127403] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773124869.516813454] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773124869.573212114] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000812 ms
[component_container_isolated-10] [INFO] [1773124869.573302868] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.012443 ms
[component_container_isolated-10] [INFO] [1773124869.573411856] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.090603 ms
[component_container_isolated-10] [INFO] [1773124869.773043604] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000040 ms
[component_container_isolated-10] [INFO] [1773124869.773090373] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.008095 ms
[component_container_isolated-10] [INFO] [1773124869.773165898] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.069523 ms
[component_container_isolated-10] [INFO] [1773124869.863245582] [global_costmap.global_costmap]: [ObstacleLayer] updateBounds: 0.123386 ms
[component_container_isolated-10] [INFO] [1773124869.863297351] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateBounds: 0.000121 ms
[component_container_isolated-10] [INFO] [1773124869.863314494] [global_costmap.global_costmap]: [InflationLayer] updateBounds: 0.000290 ms
[component_container_isolated-10] [INFO] [1773124869.863457597] [global_costmap.global_costmap]: [ObstacleLayer] updateCosts: 0.080534 ms
[component_container_isolated-10] [INFO] [1773124869.863503816] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateCosts: 0.029025 ms (total)
[component_container_isolated-10] [INFO] [1773124869.864575105] [global_costmap.global_costmap]: [InflationLayer] updateCosts: 1.031192 ms
[component_container_isolated-10] [INFO] [1773124869.973116666] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000140 ms
[component_container_isolated-10] [INFO] [1773124869.973222388] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.022693 ms
[component_container_isolated-10] [INFO] [1773124869.973360252] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.125400 ms
[component_container_isolated-10] [INFO] [1773124870.173426768] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000400 ms
[component_container_isolated-10] [INFO] [1773124870.173573158] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.026060 ms
[component_container_isolated-10] [INFO] [1773124870.173810462] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.217126 ms
[component_container_isolated-10] [INFO] [1773124870.373297279] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000110 ms
[component_container_isolated-10] [INFO] [1773124870.373380428] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.017253 ms
[component_container_isolated-10] [INFO] [1773124870.373562216] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.170036 ms
[component_container_isolated-10] [INFO] [1773124870.505189415] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773124870.566810863] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773124870.573126301] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000101 ms
[component_container_isolated-10] [INFO] [1773124870.573190303] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.011001 ms
[component_container_isolated-10] [INFO] [1773124870.573309080] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.111714 ms
[component_container_isolated-10] [INFO] [1773124870.773398039] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000301 ms
[component_container_isolated-10] [INFO] [1773124870.773507789] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.019518 ms
[component_container_isolated-10] [INFO] [1773124870.773699315] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.150217 ms
[component_container_isolated-10] [INFO] [1773124870.863140486] [global_costmap.global_costmap]: [ObstacleLayer] updateBounds: 0.058762 ms
[component_container_isolated-10] [INFO] [1773124870.863178419] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateBounds: 0.000090 ms
[component_container_isolated-10] [INFO] [1773124870.863186204] [global_costmap.global_costmap]: [InflationLayer] updateBounds: 0.000201 ms
[component_container_isolated-10] [INFO] [1773124870.863244545] [global_costmap.global_costmap]: [ObstacleLayer] updateCosts: 0.027482 ms
[component_container_isolated-10] [INFO] [1773124870.863263872] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateCosts: 0.014457 ms (total)
[component_container_isolated-10] [INFO] [1773124870.863654519] [global_costmap.global_costmap]: [InflationLayer] updateCosts: 0.384796 ms
[component_container_isolated-10] [INFO] [1773124870.973231469] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000110 ms
[component_container_isolated-10] [INFO] [1773124870.973300691] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.016912 ms
[component_container_isolated-10] [INFO] [1773124870.973468132] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.155998 ms
[component_container_isolated-10] [INFO] [1773124871.173167061] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000160 ms
[component_container_isolated-10] [INFO] [1773124871.173246803] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.010610 ms
[component_container_isolated-10] [INFO] [1773124871.173347406] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.090753 ms
[component_container_isolated-10] [INFO] [1773124871.373110357] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000141 ms
[component_container_isolated-10] [INFO] [1773124871.373190100] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.010910 ms
[component_container_isolated-10] [INFO] [1773124871.373298687] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.099330 ms
[component_container_isolated-10] [INFO] [1773124871.535316224] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773124871.566819171] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773124871.573351253] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000150 ms
[component_container_isolated-10] [INFO] [1773124871.573451044] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.018946 ms
[component_container_isolated-10] [INFO] [1773124871.573704969] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.240721 ms
[component_container_isolated-10] [INFO] [1773124871.773098033] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000160 ms
[component_container_isolated-10] [INFO] [1773124871.773164240] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.009218 ms
[component_container_isolated-10] [INFO] [1773124871.773266325] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.095222 ms
[component_container_isolated-10] [INFO] [1773124871.863277315] [global_costmap.global_costmap]: [ObstacleLayer] updateBounds: 0.159525 ms
[component_container_isolated-10] [INFO] [1773124871.863386744] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateBounds: 0.000150 ms
[component_container_isolated-10] [INFO] [1773124871.863404848] [global_costmap.global_costmap]: [InflationLayer] updateBounds: 0.000291 ms
[component_container_isolated-10] [INFO] [1773124871.863549625] [global_costmap.global_costmap]: [ObstacleLayer] updateCosts: 0.092507 ms
[component_container_isolated-10] [INFO] [1773124871.863591616] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateCosts: 0.027623 ms (total)
[component_container_isolated-10] [INFO] [1773124871.864478983] [global_costmap.global_costmap]: [InflationLayer] updateCosts: 0.871757 ms
[component_container_isolated-10] [INFO] [1773124871.973220232] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000131 ms
[component_container_isolated-10] [INFO] [1773124871.973291278] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.012053 ms
[component_container_isolated-10] [INFO] [1773124871.973398323] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.097736 ms
[component_container_isolated-10] [INFO] [1773124872.173862703] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000221 ms
[component_container_isolated-10] [INFO] [1773124872.173974697] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.023966 ms
[component_container_isolated-10] [INFO] [1773124872.174290531] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.297419 ms
[component_container_isolated-10] [INFO] [1773124872.373403235] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000230 ms
[component_container_isolated-10] [INFO] [1773124872.373531851] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.035769 ms
[component_container_isolated-10] [INFO] [1773124872.373768854] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.221373 ms
[component_container_isolated-10] [INFO] [1773124872.419990198] [controller_server]: scoreArcLength timing - Duration: 734 μs | Batch: 2000, Path segs: 59
[component_container_isolated-10] [INFO] [1773124872.420044332] [controller_server]: PathAlignCritic::score() timing - Duration: 804 μs | Batch: 2000, Path segs: 59
[component_container_isolated-10] [INFO] [1773124872.555982110] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773124872.574172287] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000260 ms
[component_container_isolated-10] [INFO] [1773124872.574283760] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.027262 ms
[component_container_isolated-10] [INFO] [1773124872.574654279] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.353326 ms
[component_container_isolated-10] [INFO] [1773124872.616808395] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773124872.773038470] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000341 ms
[component_container_isolated-10] [INFO] [1773124872.773100559] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.010360 ms
[component_container_isolated-10] [INFO] [1773124872.773216330] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.107115 ms
[component_container_isolated-10] [INFO] [1773124872.863142185] [global_costmap.global_costmap]: [ObstacleLayer] updateBounds: 0.060065 ms
[component_container_isolated-10] [INFO] [1773124872.863176150] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateBounds: 0.000030 ms
[component_container_isolated-10] [INFO] [1773124872.863182262] [global_costmap.global_costmap]: [InflationLayer] updateBounds: 0.000181 ms
[component_container_isolated-10] [INFO] [1773124872.863236015] [global_costmap.global_costmap]: [ObstacleLayer] updateCosts: 0.027062 ms
[component_container_isolated-10] [INFO] [1773124872.863258778] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateCosts: 0.017804 ms (total)
[component_container_isolated-10] [INFO] [1773124872.863669183] [global_costmap.global_costmap]: [InflationLayer] updateCosts: 0.398091 ms
[component_container_isolated-10] [INFO] [1773124872.973001922] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000120 ms
[component_container_isolated-10] [INFO] [1773124872.973052979] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.009197 ms
[component_container_isolated-10] [INFO] [1773124872.973163771] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.105001 ms
[component_container_isolated-10] [INFO] [1773124873.173502277] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000151 ms
[component_container_isolated-10] [INFO] [1773124873.173601206] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.022944 ms
[component_container_isolated-10] [INFO] [1773124873.173828330] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.212707 ms
[component_container_isolated-10] [INFO] [1773124873.373134291] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000060 ms
[component_container_isolated-10] [INFO] [1773124873.373192392] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.010400 ms
[component_container_isolated-10] [INFO] [1773124873.373290950] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.093218 ms
[component_container_isolated-10] [INFO] [1773124873.573057983] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000040 ms
[component_container_isolated-10] [INFO] [1773124873.573107888] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.008717 ms
[component_container_isolated-10] [INFO] [1773124873.573215534] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.101424 ms
[component_container_isolated-10] [INFO] [1773124873.585456994] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773124873.616813380] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773124873.774266782] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000150 ms
[component_container_isolated-10] [INFO] [1773124873.774386711] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.030409 ms
[component_container_isolated-10] [INFO] [1773124873.774794922] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.388152 ms
[component_container_isolated-10] [INFO] [1773124873.863151133] [global_costmap.global_costmap]: [ObstacleLayer] updateBounds: 0.066067 ms
[component_container_isolated-10] [INFO] [1773124873.863189988] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateBounds: 0.000090 ms
[component_container_isolated-10] [INFO] [1773124873.863196660] [global_costmap.global_costmap]: [InflationLayer] updateBounds: 0.000310 ms
[component_container_isolated-10] [INFO] [1773124873.863258959] [global_costmap.global_costmap]: [ObstacleLayer] updateCosts: 0.030558 ms
[component_container_isolated-10] [INFO] [1773124873.863277234] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateCosts: 0.013125 ms (total)
[component_container_isolated-10] [INFO] [1773124873.863652933] [global_costmap.global_costmap]: [InflationLayer] updateCosts: 0.368946 ms
[component_container_isolated-10] [INFO] [1773124873.974278672] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000551 ms
[component_container_isolated-10] [INFO] [1773124873.974400245] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.021120 ms
[component_container_isolated-10] [INFO] [1773124873.974666173] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.250008 ms
[component_container_isolated-10] [INFO] [1773124874.174143238] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000150 ms
[component_container_isolated-10] [INFO] [1773124874.174262015] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.019838 ms
[component_container_isolated-10] [INFO] [1773124874.174465614] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.190975 ms
[component_container_isolated-10] [INFO] [1773124874.373886892] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000070 ms
[component_container_isolated-10] [INFO] [1773124874.373943530] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.009118 ms
[component_container_isolated-10] [INFO] [1773124874.374103997] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.154776 ms
[component_container_isolated-10] [INFO] [1773124874.573272511] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000100 ms
[component_container_isolated-10] [INFO] [1773124874.573363435] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.019086 ms
[component_container_isolated-10] [INFO] [1773124874.573605949] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.229419 ms
[component_container_isolated-10] [INFO] [1773124874.616118809] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773124874.666838684] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773124874.773256184] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000381 ms
[component_container_isolated-10] [INFO] [1773124874.773315637] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.008666 ms
[component_container_isolated-10] [INFO] [1773124874.773412152] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.089962 ms
[component_container_isolated-10] [INFO] [1773124874.863416564] [global_costmap.global_costmap]: [ObstacleLayer] updateBounds: 0.251842 ms
[component_container_isolated-10] [INFO] [1773124874.863542965] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateBounds: 0.000251 ms
[component_container_isolated-10] [INFO] 

Locally I did some changes I didn't push cause I need to be sure about these improvmeents. They can regress a bit but I expect them to stay relatively intact I need to put unit tests do styling etc. I droppped setConvexPolygon and making TF ops batch by batch and I have added various optimizations on top of these. I hope to be able to finish this today or tomorrow.

…r draw line Filliing inside walls with specific funcs newly added Getting path segment with a resolutioned search

Signed-off-by: silanus23 <berkantali23@outlook.com>
@silanus23
Copy link
Contributor Author

silanus23 commented Mar 11, 2026

[component_container_isolated-10] [INFO] [1773264100.035177645] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000977 ms
[component_container_isolated-10] [INFO] [1773264100.035217037] [local_costmap.local_costmap]: [KeepoutFilter] updateBounds: 0.007753 ms
[component_container_isolated-10] [INFO] [1773264100.035239387] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.008940 ms
[component_container_isolated-10] [INFO] [1773264100.035286671] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.035760 ms
[component_container_isolated-10] [INFO] [1773264100.035391506] [local_costmap.local_costmap]: [KeepoutFilter] updateCosts (process): 0.093381 ms
[component_container_isolated-10] [INFO] [1773264100.235474361] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000978 ms
[component_container_isolated-10] [INFO] [1773264100.235536801] [local_costmap.local_costmap]: [KeepoutFilter] updateBounds: 0.021372 ms
[component_container_isolated-10] [INFO] [1773264100.235562852] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.008940 ms
[component_container_isolated-10] [INFO] [1773264100.235613209] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.038903 ms
[component_container_isolated-10] [INFO] [1773264100.235719022] [local_costmap.local_costmap]: [KeepoutFilter] updateCosts (process): 0.093939 ms
[component_container_isolated-10] [INFO] [1773264100.435194728] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.001397 ms
[component_container_isolated-10] [INFO] [1773264100.435243828] [local_costmap.local_costmap]: [KeepoutFilter] updateBounds: 0.011384 ms
[component_container_isolated-10] [INFO] [1773264100.435265829] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.009080 ms
[component_container_isolated-10] [INFO] [1773264100.435317233] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.040020 ms
[component_container_isolated-10] [INFO] [1773264100.435422557] [local_costmap.local_costmap]: [KeepoutFilter] updateCosts (process): 0.093240 ms
[component_container_isolated-10] [INFO] [1773264100.594251635] [planner_server]: Computing path to goal.
[component_container_isolated-10] [INFO] [1773264100.615353214] [controller_server]: Passing new path to controller.
[component_container_isolated-10] [INFO] [1773264100.635346798] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.001397 ms
[component_container_isolated-10] [INFO] [1773264100.635439270] [local_costmap.local_costmap]: [KeepoutFilter] updateBounds: 0.027169 ms
[component_container_isolated-10] [INFO] [1773264100.635473563] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.013201 ms
[component_container_isolated-10] [INFO] [1773264100.635535095] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.048961 ms
[component_container_isolated-10] [INFO] [1773264100.635645727] [local_costmap.local_costmap]: [KeepoutFilter] updateCosts (process): 0.096384 ms
[component_container_isolated-10] [INFO] [1773264100.835345491] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.001397 ms
[component_container_isolated-10] [INFO] [1773264100.835409188] [local_costmap.local_costmap]: [KeepoutFilter] updateBounds: 0.013829 ms
[component_container_isolated-10] [INFO] [1773264100.835436776] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.011594 ms
[component_container_isolated-10] [INFO] [1773264100.835512976] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.063488 ms
[component_container_isolated-10] [INFO] [1773264100.835631779] [local_costmap.local_costmap]: [KeepoutFilter] updateCosts (process): 0.104974 ms
[component_container_isolated-10] [INFO] [1773264100.970239722] [global_costmap.global_costmap]: [ObstacleLayer] updateBounds: 0.095825 ms
[component_container_isolated-10] [INFO] [1773264100.970292244] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateBounds: 0.001466 ms
[component_container_isolated-10] [INFO] [1773264100.970307260] [global_costmap.global_costmap]: [InflationLayer] updateBounds: 0.000978 ms
[component_container_isolated-10] [INFO] [1773264100.970538721] [global_costmap.global_costmap]: [KeepoutFilter] updateBounds: 0.198984 ms
[component_container_isolated-10] [INFO] [1773264100.970619810] [global_costmap.global_costmap]: [StaticLayer] updateCosts: 0.032896 ms
[component_container_isolated-10] [INFO] [1773264100.970698034] [global_costmap.global_costmap]: [ObstacleLayer] updateCosts: 0.063907 ms
[component_container_isolated-10] [INFO] [1773264100.970749509] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateCosts: 0.037296 ms (total)
[component_container_isolated-10] [INFO] [1773264100.971199859] [global_costmap.global_costmap]: [InflationLayer] updateCosts: 0.250528 ms
[component_container_isolated-10] [INFO] [1773264100.972039307] [global_costmap.global_costmap]: [KeepoutFilter] updateCosts (process): 0.784970 ms
[component_container_isolated-10] [INFO] [1773264101.035379875] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.001467 ms
[component_container_isolated-10] [INFO] [1773264101.035441407] [local_costmap.local_costmap]: [KeepoutFilter] updateBounds: 0.015366 ms
[component_container_isolated-10] [INFO] [1773264101.035483173] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.018508 ms
[component_container_isolated-10] [INFO] [1773264101.035584446] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.082695 ms
[component_container_isolated-10] [INFO] [1773264101.035828130] [local_costmap.local_costmap]: [KeepoutFilter] updateCosts (process): 0.224477 ms
[component_container_isolated-10] [INFO] [1773264101.235390581] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.001397 ms
[component_container_isolated-10] [INFO] [1773264101.235454418] [local_costmap.local_costmap]: [KeepoutFilter] updateBounds: 0.014388 ms
[component_container_isolated-10] [INFO] [1773264101.235493949] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.018089 ms
[component_container_isolated-10] [INFO] [1773264101.235595571] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.082416 ms
[component_container_isolated-10] [INFO] [1773264101.235854690] [local_costmap.local_costmap]: [KeepoutFilter] updateCosts (process): 0.240471 ms
[component_container_isolated-10] [INFO] [1773264101.435430412] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000977 ms
[component_container_isolated-10] [INFO] [1773264101.435577991] [local_costmap.local_costmap]: [KeepoutFilter] updateBounds: 0.043931 ms
[component_container_isolated-10] [INFO] [1773264101.435618919] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.018159 ms
[component_container_isolated-10] [INFO] [1773264101.435689391] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.053849 ms
[component_container_isolated-10] [INFO] [1773264101.435847028] [local_costmap.local_costmap]: [KeepoutFilter] updateCosts (process): 0.142620 ms
[component_container_isolated-10] [INFO] [1773264101.635256173] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.001397 ms
[component_container_isolated-10] [INFO] [1773264101.635322315] [local_costmap.local_costmap]: [KeepoutFilter] updateBounds: 0.014598 ms
[component_container_isolated-10] [INFO] [1773264101.635349763] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.010826 ms
[component_container_isolated-10] [INFO] [1773264101.635399492] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.036738 ms
[component_container_isolated-10] [INFO] [1773264101.635512428] [local_costmap.local_costmap]: [KeepoutFilter] updateCosts (process): 0.100156 ms
[component_container_isolated-10] [INFO] [1773264101.835391410] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000908 ms
[component_container_isolated-10] [INFO] [1773264101.835455107] [local_costmap.local_costmap]: [KeepoutFilter] updateBounds: 0.019695 ms
[component_container_isolated-10] [INFO] [1773264101.835481159] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.010337 ms
[component_container_isolated-10] [INFO] [1773264101.835527535] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.035341 ms
[component_container_isolated-10] [INFO] [1773264101.835647596] [local_costmap.local_costmap]: [KeepoutFilter] updateCosts (process): 0.108188 ms
[component_container_isolated-10] [INFO] [1773264101.970250440] [global_costmap.global_costmap]: [ObstacleLayer] updateBounds: 0.092054 ms
[component_container_isolated-10] [INFO] [1773264101.970323845] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateBounds: 0.001397 ms
[component_container_isolated-10] [INFO] [1773264101.970340049] [global_costmap.global_costmap]: [InflationLayer] updateBounds: 0.001467 ms
[component_container_isolated-10] [INFO] [1773264101.970381396] [global_costmap.global_costmap]: [KeepoutFilter] updateBounds: 0.005727 ms
[component_container_isolated-10] [INFO] [1773264101.970445792] [global_costmap.global_costmap]: [StaticLayer] updateCosts: 0.040649 ms
[component_container_isolated-10] [INFO] [1773264101.970520105] [global_costmap.global_costmap]: [ObstacleLayer] updateCosts: 0.061951 ms
[component_container_isolated-10] [INFO] [1773264101.970566970] [global_costmap.global_costmap]: [BoundedTrackingErrorLayer] updateCosts: 0.035341 ms (total)
[component_container_isolated-10] [INFO] [1773264101.970879659] [global_costmap.global_costmap]: [InflationLayer] updateCosts: 0.296625 ms
[component_container_isolated-10] [INFO] [1773264101.971524174] [global_costmap.global_costmap]: [KeepoutFilter] updateCosts (process): 0.614203 ms
[component_container_isolated-10] [INFO] [1773264102.035215914] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.001397 ms
[component_container_isolated-10] [INFO] [1773264102.035285408] [local_costmap.local_costmap]: [KeepoutFilter] updateBounds: 0.020604 ms
[component_container_isolated-10] [INFO] [1773264102.035315301] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.010057 ms
[component_container_isolated-10] [INFO] [1773264102.035338978] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.009987 ms
[component_container_isolated-10] [INFO] [1773264102.035483903] [local_costmap.local_costmap]: [KeepoutFilter] updateCosts (process): 0.111540 ms
[component_container_isolated-10] [INFO] [1773264102.235390682] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.001397 ms
[component_container_isolated-10] [INFO] [1773264102.235470234] [local_costmap.local_costmap]: [KeepoutFilter] updateBounds: 0.015645 ms
[component_container_isolated-10] [INFO] [1773264102.235499778] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.012293 ms
[component_container_isolated-10] [INFO] [1773264102.235526039] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.013270 ms
[component_container_isolated-10] [INFO] [1773264102.235636321] [local_costmap.local_costmap]: [KeepoutFilter] updateCosts (process): 0.097851 ms
[component_container_isolated-10] [INFO] [1773264102.435421573] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.001885 ms
[component_container_isolated-10] [INFO] [1773264102.435561330] [local_costmap.local_costmap]: [KeepoutFilter] updateBounds: 0.034573 ms
[component_container_isolated-10] [INFO] [1773264102.435604772] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.017112 ms
[component_container_isolated-10] [INFO] [1773264102.435638646] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.020465 ms
[component_container_isolated-10] [INFO] [1773264102.435796772] [local_costmap.local_costmap]: [KeepoutFilter] updateCosts (process): 0.140944 ms
[component_container_isolated-10] [INFO] [1773264102.635451556] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.000977 ms
[component_container_isolated-10] [INFO] [1773264102.635559324] [local_costmap.local_costmap]: [KeepoutFilter] updateBounds: 0.035690 ms
[component_container_isolated-10] [INFO] [1773264102.635614710] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.025772 ms
[component_container_isolated-10] [INFO] [1773264102.635676522] [local_costmap.local_costmap]: [InflationLayer] updateCosts: 0.039462 ms
[component_container_isolated-10] [INFO] [1773264102.635983693] [local_costmap.local_costmap]: [KeepoutFilter] updateCosts (process): 0.280561 ms
[component_container_isolated-10] [INFO] [1773264102.835371117] [local_costmap.local_costmap]: [InflationLayer] updateBounds: 0.001397 ms
[component_container_isolated-10] [INFO] [1773264102.835445360] [local_costmap.local_costmap]: [KeepoutFilter] updateBounds: 0.017460 ms
[component_container_isolated-10] [INFO] [1773264102.835482098] [local_costmap.local_costmap]: [ObstacleLayer] updateCosts: 0.014178 ms
image

Just FYI colcon test didn't show those linting errors.
tests need update near placeholder for now.
current structure holds up as far as I have tested. I have added new functions so those little gaps are limitted only to outer

Signed-off-by: silanus23 <berkantali23@outlook.com>
Signed-off-by: silanus23 <berkantali23@outlook.com>
@SteveMacenski
Copy link
Member

What were the improvements made from those changes? Are we now at or below the other layers (the logs are quite long and hard to read -- some analyzed values might be nice and easier for us to review 😉 )

@silanus23
Copy link
Contributor Author

silanus23 commented Mar 12, 2026

I have written a python script to help us analyze the results

COSTMAP LAYER PERFORMANCE ANALYSIS

GLOBAL COSTMAP
--------------------------------------------------------------------------------

  BoundedTrackingErrorLayer:
    updateBounds:
      Average: 0.001432 ms
      Min:     0.001397 ms
      Max:     0.001466 ms
      Count:   2
    updateCosts:
      Average: 0.036319 ms
      Min:     0.035341 ms
      Max:     0.037296 ms
      Count:   2

  InflationLayer:
    updateBounds:
      Average: 0.001223 ms
      Min:     0.000978 ms
      Max:     0.001467 ms
      Count:   2
    updateCosts:
      Average: 0.273577 ms
      Min:     0.250528 ms
      Max:     0.296625 ms
      Count:   2

  KeepoutFilter:
    updateBounds:
      Average: 0.102356 ms
      Min:     0.005727 ms
      Max:     0.198984 ms
      Count:   2

  ObstacleLayer:
    updateBounds:
      Average: 0.093939 ms
      Min:     0.092054 ms
      Max:     0.095825 ms
      Count:   2
    updateCosts:
      Average: 0.062929 ms
      Min:     0.061951 ms
      Max:     0.063907 ms
      Count:   2

  StaticLayer:
    updateCosts:
      Average: 0.036772 ms
      Min:     0.032896 ms
      Max:     0.040649 ms
      Count:   2

I think current one is close to static_layer I dropped polygon (didn't know it was this consuming) dropping but there were gaps in diagonal paths so I wrote 2 functions specificially for diagonal gaps. I use nav2_util s LineIterator instead adding another bresenham function and try to fill around that first thickness wise and after that diagonal wise.

The only problem is if the wall_thickness gets wider the outer rows become crochet like in the image above. I am keeping diagonals limited cause I have seen they can consume if given chance so maybe non-parameterize width or let user decide.

Of course as a last I have implemented that TF loop thing you suggested above. It created diff too. I couldn't catch it in the first time :)

As a last thing should I increase the log size and again put here. 2 maybe not that enough.

@SteveMacenski
Copy link
Member

Oh nice, that's definitely performant enough I think. I think fixing that crochet pattern would be the only last thing to resolve so that we have that wall, but not the sparse effects that don't seem related to the 3-deep wall thickness. Are all the right cells being touched though? Looking at the image you showed at the diagonal, it looks like there's some cells that would be equidistant from the others that aren't included. It would expect it to look a little more 'straight'

…ccording to new approach

Signed-off-by: silanus23 <berkantali23@outlook.com>
@silanus23
Copy link
Contributor Author

silanus23 commented Mar 19, 2026

Screenshot from 2026-03-19 21-50-36

straight lines.

Screenshot from 2026-03-19 21-49-51

diagonals.

Iterating 2 lines on both sides and span buffering their inners. If this output looks good to you, I can start refining the implementation immediately.

Just consuming slighlty more than half time of static layer. Only at the beggining of motion it goes beyond static layer.

Should I make some of helper functions into another classes files?

Signed-off-by: silanus23 <berkantali23@outlook.com>
Signed-off-by: silanus23 <berkantali23@outlook.com>
@SteveMacenski
Copy link
Member

SteveMacenski commented Mar 20, 2026

Yes this looks good to me. I would ask though an eample of a non-striaght path to see & making sure that the thickness is added to the outside of the bound limitations set (not in the middle)

Make sure to add test coverage to the functional methods like getting the wall / segment / filling / etc. Stong unit tests there with straight, curved, and random paths would be good to showcase it works correctly

Generally avoid friend classes


void BoundedTrackingErrorLayer::reset()
{
std::lock_guard<std::mutex> lock(data_mutex_);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why not add the lock to the inside of resetState so that you don't need to lock here manually / in the deactivate / other places

*/
class BoundedTrackingErrorLayer : public nav2_costmap_2d::Layer
{
// Friend declaration for test access
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this should be removed

* @brief Callback for goal pose updates.
* @param msg Incoming goal pose message.
*/
void goalCallback(const geometry_msgs::msg::PoseStamped::SharedPtr msg);
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ConstSharedPtr, also for other subscriptions

return;
}

if (on_set_params_handler_) {
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This should only be in deactivate()

this, std::placeholders::_1));
}

void BoundedTrackingErrorLayer::goalCallback(const geometry_msgs::msg::PoseStamped::SharedPtr msg)
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@silanus23 This is still valid

return;
}

current_path_index_.store(msg->current_path_index);
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If you only need the current path index, can't that be calculated in this layer instead of subscribing it?

int /*min_i*/, int /*min_j*/, int /*max_i*/, int /*max_j*/)
{
nav2_util::ExecutionTimer timer;
timer.start();
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I understand this can be useful for testing performance, but please remove it after you tested

if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) {
if (param_name == name_ + "." + "look_ahead") {
const double new_value = parameter.as_double();
// Values above 3.0m cause corridor rendering artifacts
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It feels strange to me that it can only be 0-3m, can you explain why

}

// Update cached resolution
resolution_ = layered_costmap_->getCostmap()->getResolution();
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You should not do this in every updateCosts call, maybe in matchSize?

return;
}

const std::string costmap_frame = layered_costmap_->getGlobalFrameID();
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same for this, this should not be called in every updatecosts loop

return;
}

const double res = layered_costmap_->getCostmap()->getResolution();
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

resolution_?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

4 participants