Skip to content

Conversation

@MarcoMatteoBassa
Copy link
Contributor

Basic Info

Info Please fill out this column
Primary OS tested on Ubuntu
Robotic platform tested on Independent
Does this PR contain AI generated software? No

Description of contribution in a few bullet points

The added utility tackles 2 issues:

  • Reduces the amount of boilerplate code required to declare and get parameters, and consequently makes it less likely to introduce typos: it combines declare_parameter_if_not_declared and get_parameter in a single instruction.

Example:

nav2_util::declare_parameter_if_not_declared(
    node,
    "max_rotational_vel", rclcpp::ParameterValue(1.0));
  node->get_parameter("max_rotational_vel", max_rotational_vel_);

Can be rewritten as

max_rotational_vel_ = nav2_util::declare_or_get_param(node, "max_rotational_vel", 1.0);

  • Helps tracking typos / mismatching namespaces in the parameters overrides: if a parameter is not found in the overrides, resulting in the default value being used, the utility can optionally print a WARN message. This can often help the developers catch configuration mistakes, and is particularly useful when relying on the default value likely results in degraded performance.

The utility can be used either through a generic node pointer, or (useful when using derived nodes) using the internal node interfaces.

Description of how this change was tested

  • Added a unit test.
  • As I didn't add the utilty to any node yet, it won't affect any existing behavior.

Future work that may be required in bullet points

  • The utility can be used for refactoring purposes or for the development of new modules.

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

@codecov
Copy link

codecov bot commented May 13, 2025

Codecov Report

Attention: Patch coverage is 96.00000% with 1 line in your changes missing coverage. Please review.

Files with missing lines Patch % Lines
nav2_util/include/nav2_util/node_utils.hpp 96.00% 1 Missing ⚠️
Files with missing lines Coverage Δ
nav2_util/include/nav2_util/node_utils.hpp 91.66% <96.00%> (+5.00%) ⬆️

... and 3 files with indirect coverage changes

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

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.

As a potential suggestion, this is declare_parameter_if_not_declared

template<typename NodeT>
void declare_parameter_if_not_declared(
  NodeT node,
  const std::string & param_name,
  const rclcpp::ParameterValue & param_value,
  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
  rcl_interfaces::msg::ParameterDescriptor())
{
  if (!node->has_parameter(param_name)) {
    node->declare_parameter(param_name, param_type, parameter_descriptor);
  }
}

The declare_parameter bit can/will return a ParameterValue that we can work with if its not been declared, and otherwise we can add a get_parameter as an else condition to return the value.

We could actually just adapt the declare_parameter_if_not_declared to have a return type instead and use that as a single-call. Possibly even rename at that point to declare_or_get_parameter and use that globally, except the one situation below which is only in a handful of places.

Note: We also have a version for parameter types rather than values for the case in which we want to declare a parameter without a default value but only declare its type. We'd have to keep that in place with the current workflow of declare & get I think.

What do you think?

@MarcoMatteoBassa
Copy link
Contributor Author

Hi, yes the util is basically doing that, but in addition it also removes the need to explicitally transform the parameters with rclcpp::ParameterValue() when calling it by using the type template.
The WARN part is also quite handy, but if you feel that would be too spammy, we could default it to false.

I didn't want to modify declare_parameter_if_not_declared to avoid intrusion in the code base and possibly generate unused-return-value warnings, but using an unified strategy later would for sure be beneficial :)

Yes, the Type-Only version of declare_parameter_if_not_declared should stay there. As in this case the parameter might not have a value, I would leave it as void; alternatively we could add a version of declare_or_get returning an optional rclcpp::ParameterValue if an rclcpp::ParameterType is used.

Let me know what you prefer :)

@SteveMacenski
Copy link
Member

I suppose I'm less tied to a particular implementation and more interested in just removing redundancy as much as possible. Maybe we don't need to do everything at once :-) It would be nice as you say to have a version that doesn't produce a unused return value warning --

Yes, the Type-Only version of declare_parameter_if_not_declared should stay there. As in this case the parameter might not have a value, I would leave it as void; alternatively we could add a version of declare_or_get returning an optional rclcpp::ParameterValue if an rclcpp::ParameterType is used.

We could add in the version but allow get_parameter throw in the case it was not declared (as it does). As long as the doxygen mentions this behavior, I think that's OK. So it would return a value if one is given, else throws. That should be a known behavior in that case and I believe all uses in Nav2 wraps those calls in try/catch anyway to capture it and allow for a 1:1 replacement.

The WARN part is also quite handy, but if you feel that would be too spammy, we could default it to false.

I do like default false personally. I'm curious to know why its a warning to use a default value - is your expectation that all nodes are full configured in YAML files? I suppose that is good practice, but would spam the terminal quite alot for existing users that are less disciplined (including nav2_bringup currently 🥲 )

@MarcoMatteoBassa
Copy link
Contributor Author

We could add in the version but allow get_parameter throw in the case it was not declared (as it does). As long as the doxygen mentions this behavior, I think that's OK. So it would return a value if one is given, else throws. That should be a known behavior in that case and I believe all uses in Nav2 wraps those calls in try/catch anyway to capture it and allow for a 1:1 replacement.

I added a version that handles the declaration by type, it will return a parameter_not_set type if the param is not there. The exception will eventually come when trying to cast if that is done without checking the type.

I do like default false personally. I'm curious to know why its a warning to use a default value - is your expectation that all nodes are full configured in YAML files? I suppose that is good practice, but would spam the terminal quite alot for existing users that are less disciplined (including nav2_bringup currently 🥲 )

Yes, having the warning combined with fully configured YAML files has a lot of advantages:

  • You always know if the param defined in the yaml takes effect -> It's easy to spot typos in the parameter names or when these are defined in the wrong namespace
  • Makes it easier to maintain compatibility between the configuration files and the source code (which is particularly challenging when maintaining multiple robots/environments that require the yamls to be defined in separate packages)
  • Makes it easier for the user to understand what can be configured in the node without having to call param_list at runtime -> the YAML files can become part of the documentation

But I don't want to enforce this on everyone, so I defaulted to false now :)

@SteveMacenski
Copy link
Member

SteveMacenski commented May 15, 2025

Honestly I totally agree. If I was building applications I would be fully describing my configuration files. However, I don't want to overwhelm people reading the config file for the first few times (its already alot) so that's why nav2_bringup isn't as complete

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.

LGTM, ready to merge on your front?

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.

Just to trigger that warning message to complete coverage metrics

@SteveMacenski
Copy link
Member

Mhm, there are some tests that are failing, can you rebase? We did make some changes in the default bringup recently related to the failing tests and I'm wondering if there's a caching issue.

Signed-off-by: Marco Bassa <[email protected]>
@mergify
Copy link
Contributor

mergify bot commented May 16, 2025

@MarcoMatteoBassa, your PR has failed to build. Please check CI outputs and resolve issues.
You may need to rebase or pull in main due to API changes (or your contribution genuinely fails).

@MarcoMatteoBassa
Copy link
Contributor Author

I realized that subsequent calls of declare_or_get by type would result in an exception instead of an uninitialized parameter, so I changed it to consistently return an uninitialized parameter.

PS, a possible way to allow the user to globally choose for a node if he wants warnings for missing overrides, could be to enable it through an optional dedicated boolean parameter, ex by changing it to:

template<typename ParamType, typename NodeT>
ParamType declare_or_get_parameter(
  NodeT node, const std::string & parameter_name,
  const ParamType & default_value, const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
{
  const auto ParamBool = rclcpp::ParameterType::PARAMETER_BOOL;
  auto warn_value = declare_or_get_parameter(node, "warn_missing_parameter_overrides", ParamBool);
  const bool warn = warn_value.get_type() == ParamBool && warn_value.template get<bool>();
  return declare_or_get_parameter(node->get_logger(), node->get_node_parameters_interface(),
      parameter_name, default_value, warn, parameter_descriptor);
}

In this way there wouldn't be a need to hard-code a choice in the function call, and by default there would be no warning.

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.

Love it, anything else or can I merge?

Sorry for the back and forth, I think this is better though because of it!

@MarcoMatteoBassa
Copy link
Contributor Author

All good from my side :) Maybe I'll do a follow-up proposal for enabling the warning through a parameter, but that might not be very "elegant".

@SteveMacenski SteveMacenski merged commit 09c4617 into ros-navigation:main May 20, 2025
14 checks passed
SteveMacenski added a commit that referenced this pull request May 29, 2025
* Adding declare_or_get_param util to node utils

Signed-off-by: Marco Bassa <[email protected]>

* Adding test for declare_or_get_param util

Signed-off-by: Marco Bassa <[email protected]>

* Adding declare_or_get_parameter function by type, using explicit variable names, disabling param warnings by default

Signed-off-by: Marco Bassa <[email protected]>

* Update nav2_util/test/test_node_utils.cpp

Signed-off-by: Steve Macenski <[email protected]>

* Fixing codecove test

Signed-off-by: Marco Bassa <[email protected]>

* Catching possible exception in declare_or_get_by_type

Signed-off-by: Marco Bassa <[email protected]>

* Templating return type of declare parameter by value

Signed-off-by: Marco Bassa <[email protected]>

---------

Signed-off-by: Marco Bassa <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>
SteveMacenski added a commit that referenced this pull request May 30, 2025
* Dynamic param patterns (#4971)

* redesign dynamic param patterns

Signed-off-by: Nils-ChristianIseke <[email protected]>

* change cache version

Signed-off-by: Nils-ChristianIseke <[email protected]>

* check that parameter of type double are  >=0.0

Signed-off-by: Nils-ChristianIseke <[email protected]>

---------

Signed-off-by: Nils-ChristianIseke <[email protected]>

* [nav2_behavior_tree] Add force_use_current_pose to ComputePathToPoseAction (#4925)

* Add force_use_current_pose

Signed-off-by: Guillaume Doisy <[email protected]>

* xml update

Signed-off-by: Guillaume Doisy <[email protected]>

* rename to use_start

Signed-off-by: Guillaume Doisy <[email protected]>

* lint

Signed-off-by: Guillaume Doisy <[email protected]>

* descriptions

Signed-off-by: Guillaume Doisy <[email protected]>

* simplify logic

Signed-off-by: Guillaume Doisy <[email protected]>

---------

Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>

* [CostmapTopicCollisionChecker] Alternative constructor with footprint string (#4926)

* [CostmapTopicCollisionChecker] Alternative constructor with footprint

Signed-off-by: Guillaume Doisy <[email protected]>

* raw pointer

Signed-off-by: Guillaume Doisy <[email protected]>

* suggestions from review

Signed-off-by: Guillaume Doisy <[email protected]>

---------

Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>

* Merged Fix navfn_planner from humble PR #5087 (#5092)

* merged changes from humble for goal.header fix

* reverted back, error in merge

* ported goal.header fix in navfn_planner.cpp from humble

* reverted to navfn_planner.cpp to origin/main

* merged navfn_planner.cpp from humble

* fixed the merge

* Update map_io library to use Eigen method for faster map loading (#5071)

* Update map_io library to use opencv method for faster map loading

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit config changes

Signed-off-by: Vignesh T <[email protected]>

* Use Eigen approach instead of OpenCV

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit changes

Signed-off-by: Vignesh T <[email protected]>

* Update include header include order

Signed-off-by: Vignesh T <[email protected]>

* Remove intermediary alpha matrix

Signed-off-by: Vignesh T <[email protected]>

* Add comments for the code understanding

Signed-off-by: Vignesh T <[email protected]>

* Fix else braces rule issue

Signed-off-by: Vignesh T <[email protected]>

* Create and use alpha_matrix when applying mask

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit changes

Signed-off-by: Vignesh T <[email protected]>

* Take flip part out of if-else

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit changes

Signed-off-by: Vignesh T <[email protected]>

---------

Signed-off-by: Vignesh T <[email protected]>

* Precompute yaw trigonometric values in smac planner (#5109)

Signed-off-by: mini-1235 <[email protected]>

* removing the start navigation message in the paused state from rviz buttons (#5137)

Signed-off-by: Pradheep <[email protected]>

* Show error if inflation radius is smaller than circumscribed radius (#5148)

* Warn if inflation radius is smaller than circumscribed radius

Signed-off-by: Tony Najjar <[email protected]>

* Update nav2_mppi_controller/src/critics/cost_critic.cpp

Co-authored-by: Steve Macenski <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>

* Update nav2_smac_planner/include/nav2_smac_planner/utils.hpp

Co-authored-by: Steve Macenski <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* Prevent MPPI controller from resetting speed limits upon goal execution. (#5165)

Signed-off-by: Leander Stephen D'Souza <[email protected]>

* Fixing docking server when already docked at the requeste ddock (#5171)

Signed-off-by: Steve Macenski <[email protected]>

* Adding parameter util to node utils (#5154)

* Adding declare_or_get_param util to node utils

Signed-off-by: Marco Bassa <[email protected]>

* Adding test for declare_or_get_param util

Signed-off-by: Marco Bassa <[email protected]>

* Adding declare_or_get_parameter function by type, using explicit variable names, disabling param warnings by default

Signed-off-by: Marco Bassa <[email protected]>

* Update nav2_util/test/test_node_utils.cpp

Signed-off-by: Steve Macenski <[email protected]>

* Fixing codecove test

Signed-off-by: Marco Bassa <[email protected]>

* Catching possible exception in declare_or_get_by_type

Signed-off-by: Marco Bassa <[email protected]>

* Templating return type of declare parameter by value

Signed-off-by: Marco Bassa <[email protected]>

---------

Signed-off-by: Marco Bassa <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* added config for laserscan in lb-sim (#5174)

* added config for laserscan in lb-sim

Signed-off-by: RamanaBotta <[email protected]>

* fixing ament_flake8 errors

Signed-off-by: RamanaBotta <[email protected]>

* review: use_inf is default:true and added parameters on readme #4992

Signed-off-by: RamanaBotta <[email protected]>

* refactor: meaningfull value for scan_angle_increment

Signed-off-by: RamanaBotta <[email protected]>

---------

Signed-off-by: RamanaBotta <[email protected]>
Co-authored-by: RamanaBotta <[email protected]>

* Publish planned footprints after smoothing (#5155)

* Publish planned footprints after smoothing

Signed-off-by: Tony Najjar <[email protected]>

* Revert "Publish planned footprints after smoothing"

This reverts commit c9b349a.

* Add smoothed footprints publishing

Signed-off-by: Tony Najjar <[email protected]>

* fix formatting

Signed-off-by: Tony Najjar <[email protected]>

* Fix indentation for publisher creation in SmacPlannerHybrid and SmacPlannerLattice

Signed-off-by: Tony Najjar <[email protected]>

* address PR comments

Signed-off-by: Tony Najjar <[email protected]>

* fixes

Signed-off-by: Tony Najjar <[email protected]>

* fix build error

Signed-off-by: Tony Najjar <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>

* fixing deprecation warning (#5182)

Signed-off-by: Steve Macenski <[email protected]>

* Adding missing dep to loopback sim (#5204)

* Adding missing dep

Signed-off-by: Steve Macenski <[email protected]>

* typo

Signed-off-by: Steve Macenski <[email protected]>

* updating fix

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>

* Adding parameter warn_when_defaulting_parameters to control default parameter warnings (#5189)

* Adding a parameter warn_when_defaulting_parameters to control default parameter warnings instead of using a flag

Signed-off-by: Marco Bassa <[email protected]>

* Adding parameter strict_param_loading for optionally throwing an exception if parameter overrides are missing

Signed-off-by: Marco Bassa <[email protected]>

* Using default false declaration instead of declare_or_get in param util

Signed-off-by: Marco Bassa <[email protected]>

---------

Signed-off-by: Marco Bassa <[email protected]>

* bumping to 1.3.7 for release

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Nils-ChristianIseke <[email protected]>
Signed-off-by: Guillaume Doisy <[email protected]>
Signed-off-by: Vignesh T <[email protected]>
Signed-off-by: mini-1235 <[email protected]>
Signed-off-by: Pradheep <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Leander Stephen D'Souza <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Signed-off-by: Marco Bassa <[email protected]>
Signed-off-by: RamanaBotta <[email protected]>
Co-authored-by: Nils-Christian Iseke <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Sandeep Dutta <[email protected]>
Co-authored-by: Vignesh T <[email protected]>
Co-authored-by: mini-1235 <[email protected]>
Co-authored-by: Pradheep Krishna <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: Leander Stephen D'Souza <[email protected]>
Co-authored-by: Marco Bassa <[email protected]>
Co-authored-by: Raman <[email protected]>
Co-authored-by: RamanaBotta <[email protected]>
SakshayMahna pushed a commit to SakshayMahna/navigation2 that referenced this pull request Jun 8, 2025
* Adding declare_or_get_param util to node utils

Signed-off-by: Marco Bassa <[email protected]>

* Adding test for declare_or_get_param util

Signed-off-by: Marco Bassa <[email protected]>

* Adding declare_or_get_parameter function by type, using explicit variable names, disabling param warnings by default

Signed-off-by: Marco Bassa <[email protected]>

* Update nav2_util/test/test_node_utils.cpp

Signed-off-by: Steve Macenski <[email protected]>

* Fixing codecove test

Signed-off-by: Marco Bassa <[email protected]>

* Catching possible exception in declare_or_get_by_type

Signed-off-by: Marco Bassa <[email protected]>

* Templating return type of declare parameter by value

Signed-off-by: Marco Bassa <[email protected]>

---------

Signed-off-by: Marco Bassa <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>
Signed-off-by: Sakshay Mahna <[email protected]>
RBT22 pushed a commit to EnjoyRobotics/navigation2 that referenced this pull request Sep 11, 2025
* Dynamic param patterns (ros-navigation#4971)

* redesign dynamic param patterns

Signed-off-by: Nils-ChristianIseke <[email protected]>

* change cache version

Signed-off-by: Nils-ChristianIseke <[email protected]>

* check that parameter of type double are  >=0.0

Signed-off-by: Nils-ChristianIseke <[email protected]>

---------

Signed-off-by: Nils-ChristianIseke <[email protected]>

* [nav2_behavior_tree] Add force_use_current_pose to ComputePathToPoseAction (ros-navigation#4925)

* Add force_use_current_pose

Signed-off-by: Guillaume Doisy <[email protected]>

* xml update

Signed-off-by: Guillaume Doisy <[email protected]>

* rename to use_start

Signed-off-by: Guillaume Doisy <[email protected]>

* lint

Signed-off-by: Guillaume Doisy <[email protected]>

* descriptions

Signed-off-by: Guillaume Doisy <[email protected]>

* simplify logic

Signed-off-by: Guillaume Doisy <[email protected]>

---------

Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>

* [CostmapTopicCollisionChecker] Alternative constructor with footprint string (ros-navigation#4926)

* [CostmapTopicCollisionChecker] Alternative constructor with footprint

Signed-off-by: Guillaume Doisy <[email protected]>

* raw pointer

Signed-off-by: Guillaume Doisy <[email protected]>

* suggestions from review

Signed-off-by: Guillaume Doisy <[email protected]>

---------

Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>

* Merged Fix navfn_planner from humble PR ros-navigation#5087 (ros-navigation#5092)

* merged changes from humble for goal.header fix

* reverted back, error in merge

* ported goal.header fix in navfn_planner.cpp from humble

* reverted to navfn_planner.cpp to origin/main

* merged navfn_planner.cpp from humble

* fixed the merge

* Update map_io library to use Eigen method for faster map loading (ros-navigation#5071)

* Update map_io library to use opencv method for faster map loading

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit config changes

Signed-off-by: Vignesh T <[email protected]>

* Use Eigen approach instead of OpenCV

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit changes

Signed-off-by: Vignesh T <[email protected]>

* Update include header include order

Signed-off-by: Vignesh T <[email protected]>

* Remove intermediary alpha matrix

Signed-off-by: Vignesh T <[email protected]>

* Add comments for the code understanding

Signed-off-by: Vignesh T <[email protected]>

* Fix else braces rule issue

Signed-off-by: Vignesh T <[email protected]>

* Create and use alpha_matrix when applying mask

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit changes

Signed-off-by: Vignesh T <[email protected]>

* Take flip part out of if-else

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit changes

Signed-off-by: Vignesh T <[email protected]>

---------

Signed-off-by: Vignesh T <[email protected]>

* Precompute yaw trigonometric values in smac planner (ros-navigation#5109)

Signed-off-by: mini-1235 <[email protected]>

* removing the start navigation message in the paused state from rviz buttons (ros-navigation#5137)

Signed-off-by: Pradheep <[email protected]>

* Show error if inflation radius is smaller than circumscribed radius (ros-navigation#5148)

* Warn if inflation radius is smaller than circumscribed radius

Signed-off-by: Tony Najjar <[email protected]>

* Update nav2_mppi_controller/src/critics/cost_critic.cpp

Co-authored-by: Steve Macenski <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>

* Update nav2_smac_planner/include/nav2_smac_planner/utils.hpp

Co-authored-by: Steve Macenski <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* Prevent MPPI controller from resetting speed limits upon goal execution. (ros-navigation#5165)

Signed-off-by: Leander Stephen D'Souza <[email protected]>

* Fixing docking server when already docked at the requeste ddock (ros-navigation#5171)

Signed-off-by: Steve Macenski <[email protected]>

* Adding parameter util to node utils (ros-navigation#5154)

* Adding declare_or_get_param util to node utils

Signed-off-by: Marco Bassa <[email protected]>

* Adding test for declare_or_get_param util

Signed-off-by: Marco Bassa <[email protected]>

* Adding declare_or_get_parameter function by type, using explicit variable names, disabling param warnings by default

Signed-off-by: Marco Bassa <[email protected]>

* Update nav2_util/test/test_node_utils.cpp

Signed-off-by: Steve Macenski <[email protected]>

* Fixing codecove test

Signed-off-by: Marco Bassa <[email protected]>

* Catching possible exception in declare_or_get_by_type

Signed-off-by: Marco Bassa <[email protected]>

* Templating return type of declare parameter by value

Signed-off-by: Marco Bassa <[email protected]>

---------

Signed-off-by: Marco Bassa <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* added config for laserscan in lb-sim (ros-navigation#5174)

* added config for laserscan in lb-sim

Signed-off-by: RamanaBotta <[email protected]>

* fixing ament_flake8 errors

Signed-off-by: RamanaBotta <[email protected]>

* review: use_inf is default:true and added parameters on readme ros-navigation#4992

Signed-off-by: RamanaBotta <[email protected]>

* refactor: meaningfull value for scan_angle_increment

Signed-off-by: RamanaBotta <[email protected]>

---------

Signed-off-by: RamanaBotta <[email protected]>
Co-authored-by: RamanaBotta <[email protected]>

* Publish planned footprints after smoothing (ros-navigation#5155)

* Publish planned footprints after smoothing

Signed-off-by: Tony Najjar <[email protected]>

* Revert "Publish planned footprints after smoothing"

This reverts commit c9b349a.

* Add smoothed footprints publishing

Signed-off-by: Tony Najjar <[email protected]>

* fix formatting

Signed-off-by: Tony Najjar <[email protected]>

* Fix indentation for publisher creation in SmacPlannerHybrid and SmacPlannerLattice

Signed-off-by: Tony Najjar <[email protected]>

* address PR comments

Signed-off-by: Tony Najjar <[email protected]>

* fixes

Signed-off-by: Tony Najjar <[email protected]>

* fix build error

Signed-off-by: Tony Najjar <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>

* fixing deprecation warning (ros-navigation#5182)

Signed-off-by: Steve Macenski <[email protected]>

* Adding missing dep to loopback sim (ros-navigation#5204)

* Adding missing dep

Signed-off-by: Steve Macenski <[email protected]>

* typo

Signed-off-by: Steve Macenski <[email protected]>

* updating fix

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>

* Adding parameter warn_when_defaulting_parameters to control default parameter warnings (ros-navigation#5189)

* Adding a parameter warn_when_defaulting_parameters to control default parameter warnings instead of using a flag

Signed-off-by: Marco Bassa <[email protected]>

* Adding parameter strict_param_loading for optionally throwing an exception if parameter overrides are missing

Signed-off-by: Marco Bassa <[email protected]>

* Using default false declaration instead of declare_or_get in param util

Signed-off-by: Marco Bassa <[email protected]>

---------

Signed-off-by: Marco Bassa <[email protected]>

* bumping to 1.3.7 for release

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Nils-ChristianIseke <[email protected]>
Signed-off-by: Guillaume Doisy <[email protected]>
Signed-off-by: Vignesh T <[email protected]>
Signed-off-by: mini-1235 <[email protected]>
Signed-off-by: Pradheep <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Leander Stephen D'Souza <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Signed-off-by: Marco Bassa <[email protected]>
Signed-off-by: RamanaBotta <[email protected]>
Co-authored-by: Nils-Christian Iseke <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Sandeep Dutta <[email protected]>
Co-authored-by: Vignesh T <[email protected]>
Co-authored-by: mini-1235 <[email protected]>
Co-authored-by: Pradheep Krishna <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: Leander Stephen D'Souza <[email protected]>
Co-authored-by: Marco Bassa <[email protected]>
Co-authored-by: Raman <[email protected]>
Co-authored-by: RamanaBotta <[email protected]>
RBT22 pushed a commit to EnjoyRobotics/navigation2 that referenced this pull request Dec 1, 2025
* Dynamic param patterns (ros-navigation#4971)

* redesign dynamic param patterns

Signed-off-by: Nils-ChristianIseke <[email protected]>

* change cache version

Signed-off-by: Nils-ChristianIseke <[email protected]>

* check that parameter of type double are  >=0.0

Signed-off-by: Nils-ChristianIseke <[email protected]>

---------

Signed-off-by: Nils-ChristianIseke <[email protected]>

* [nav2_behavior_tree] Add force_use_current_pose to ComputePathToPoseAction (ros-navigation#4925)

* Add force_use_current_pose

Signed-off-by: Guillaume Doisy <[email protected]>

* xml update

Signed-off-by: Guillaume Doisy <[email protected]>

* rename to use_start

Signed-off-by: Guillaume Doisy <[email protected]>

* lint

Signed-off-by: Guillaume Doisy <[email protected]>

* descriptions

Signed-off-by: Guillaume Doisy <[email protected]>

* simplify logic

Signed-off-by: Guillaume Doisy <[email protected]>

---------

Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>

* [CostmapTopicCollisionChecker] Alternative constructor with footprint string (ros-navigation#4926)

* [CostmapTopicCollisionChecker] Alternative constructor with footprint

Signed-off-by: Guillaume Doisy <[email protected]>

* raw pointer

Signed-off-by: Guillaume Doisy <[email protected]>

* suggestions from review

Signed-off-by: Guillaume Doisy <[email protected]>

---------

Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>

* Merged Fix navfn_planner from humble PR ros-navigation#5087 (ros-navigation#5092)

* merged changes from humble for goal.header fix

* reverted back, error in merge

* ported goal.header fix in navfn_planner.cpp from humble

* reverted to navfn_planner.cpp to origin/main

* merged navfn_planner.cpp from humble

* fixed the merge

* Update map_io library to use Eigen method for faster map loading (ros-navigation#5071)

* Update map_io library to use opencv method for faster map loading

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit config changes

Signed-off-by: Vignesh T <[email protected]>

* Use Eigen approach instead of OpenCV

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit changes

Signed-off-by: Vignesh T <[email protected]>

* Update include header include order

Signed-off-by: Vignesh T <[email protected]>

* Remove intermediary alpha matrix

Signed-off-by: Vignesh T <[email protected]>

* Add comments for the code understanding

Signed-off-by: Vignesh T <[email protected]>

* Fix else braces rule issue

Signed-off-by: Vignesh T <[email protected]>

* Create and use alpha_matrix when applying mask

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit changes

Signed-off-by: Vignesh T <[email protected]>

* Take flip part out of if-else

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit changes

Signed-off-by: Vignesh T <[email protected]>

---------

Signed-off-by: Vignesh T <[email protected]>

* Precompute yaw trigonometric values in smac planner (ros-navigation#5109)

Signed-off-by: mini-1235 <[email protected]>

* removing the start navigation message in the paused state from rviz buttons (ros-navigation#5137)

Signed-off-by: Pradheep <[email protected]>

* Show error if inflation radius is smaller than circumscribed radius (ros-navigation#5148)

* Warn if inflation radius is smaller than circumscribed radius

Signed-off-by: Tony Najjar <[email protected]>

* Update nav2_mppi_controller/src/critics/cost_critic.cpp

Co-authored-by: Steve Macenski <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>

* Update nav2_smac_planner/include/nav2_smac_planner/utils.hpp

Co-authored-by: Steve Macenski <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* Prevent MPPI controller from resetting speed limits upon goal execution. (ros-navigation#5165)

Signed-off-by: Leander Stephen D'Souza <[email protected]>

* Fixing docking server when already docked at the requeste ddock (ros-navigation#5171)

Signed-off-by: Steve Macenski <[email protected]>

* Adding parameter util to node utils (ros-navigation#5154)

* Adding declare_or_get_param util to node utils

Signed-off-by: Marco Bassa <[email protected]>

* Adding test for declare_or_get_param util

Signed-off-by: Marco Bassa <[email protected]>

* Adding declare_or_get_parameter function by type, using explicit variable names, disabling param warnings by default

Signed-off-by: Marco Bassa <[email protected]>

* Update nav2_util/test/test_node_utils.cpp

Signed-off-by: Steve Macenski <[email protected]>

* Fixing codecove test

Signed-off-by: Marco Bassa <[email protected]>

* Catching possible exception in declare_or_get_by_type

Signed-off-by: Marco Bassa <[email protected]>

* Templating return type of declare parameter by value

Signed-off-by: Marco Bassa <[email protected]>

---------

Signed-off-by: Marco Bassa <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* added config for laserscan in lb-sim (ros-navigation#5174)

* added config for laserscan in lb-sim

Signed-off-by: RamanaBotta <[email protected]>

* fixing ament_flake8 errors

Signed-off-by: RamanaBotta <[email protected]>

* review: use_inf is default:true and added parameters on readme ros-navigation#4992

Signed-off-by: RamanaBotta <[email protected]>

* refactor: meaningfull value for scan_angle_increment

Signed-off-by: RamanaBotta <[email protected]>

---------

Signed-off-by: RamanaBotta <[email protected]>
Co-authored-by: RamanaBotta <[email protected]>

* Publish planned footprints after smoothing (ros-navigation#5155)

* Publish planned footprints after smoothing

Signed-off-by: Tony Najjar <[email protected]>

* Revert "Publish planned footprints after smoothing"

This reverts commit c9b349a.

* Add smoothed footprints publishing

Signed-off-by: Tony Najjar <[email protected]>

* fix formatting

Signed-off-by: Tony Najjar <[email protected]>

* Fix indentation for publisher creation in SmacPlannerHybrid and SmacPlannerLattice

Signed-off-by: Tony Najjar <[email protected]>

* address PR comments

Signed-off-by: Tony Najjar <[email protected]>

* fixes

Signed-off-by: Tony Najjar <[email protected]>

* fix build error

Signed-off-by: Tony Najjar <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>

* fixing deprecation warning (ros-navigation#5182)

Signed-off-by: Steve Macenski <[email protected]>

* Adding missing dep to loopback sim (ros-navigation#5204)

* Adding missing dep

Signed-off-by: Steve Macenski <[email protected]>

* typo

Signed-off-by: Steve Macenski <[email protected]>

* updating fix

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>

* Adding parameter warn_when_defaulting_parameters to control default parameter warnings (ros-navigation#5189)

* Adding a parameter warn_when_defaulting_parameters to control default parameter warnings instead of using a flag

Signed-off-by: Marco Bassa <[email protected]>

* Adding parameter strict_param_loading for optionally throwing an exception if parameter overrides are missing

Signed-off-by: Marco Bassa <[email protected]>

* Using default false declaration instead of declare_or_get in param util

Signed-off-by: Marco Bassa <[email protected]>

---------

Signed-off-by: Marco Bassa <[email protected]>

* bumping to 1.3.7 for release

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Nils-ChristianIseke <[email protected]>
Signed-off-by: Guillaume Doisy <[email protected]>
Signed-off-by: Vignesh T <[email protected]>
Signed-off-by: mini-1235 <[email protected]>
Signed-off-by: Pradheep <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Leander Stephen D'Souza <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Signed-off-by: Marco Bassa <[email protected]>
Signed-off-by: RamanaBotta <[email protected]>
Co-authored-by: Nils-Christian Iseke <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Sandeep Dutta <[email protected]>
Co-authored-by: Vignesh T <[email protected]>
Co-authored-by: mini-1235 <[email protected]>
Co-authored-by: Pradheep Krishna <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: Leander Stephen D'Souza <[email protected]>
Co-authored-by: Marco Bassa <[email protected]>
Co-authored-by: Raman <[email protected]>
Co-authored-by: RamanaBotta <[email protected]>
redvinaa pushed a commit to EnjoyRobotics/navigation2 that referenced this pull request Dec 3, 2025
* Jazzy Sync 7: May 29 2025 (ros-navigation#5211)

* Dynamic param patterns (ros-navigation#4971)

* redesign dynamic param patterns

Signed-off-by: Nils-ChristianIseke <[email protected]>

* change cache version

Signed-off-by: Nils-ChristianIseke <[email protected]>

* check that parameter of type double are  >=0.0

Signed-off-by: Nils-ChristianIseke <[email protected]>

---------

Signed-off-by: Nils-ChristianIseke <[email protected]>

* [nav2_behavior_tree] Add force_use_current_pose to ComputePathToPoseAction (ros-navigation#4925)

* Add force_use_current_pose

Signed-off-by: Guillaume Doisy <[email protected]>

* xml update

Signed-off-by: Guillaume Doisy <[email protected]>

* rename to use_start

Signed-off-by: Guillaume Doisy <[email protected]>

* lint

Signed-off-by: Guillaume Doisy <[email protected]>

* descriptions

Signed-off-by: Guillaume Doisy <[email protected]>

* simplify logic

Signed-off-by: Guillaume Doisy <[email protected]>

---------

Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>

* [CostmapTopicCollisionChecker] Alternative constructor with footprint string (ros-navigation#4926)

* [CostmapTopicCollisionChecker] Alternative constructor with footprint

Signed-off-by: Guillaume Doisy <[email protected]>

* raw pointer

Signed-off-by: Guillaume Doisy <[email protected]>

* suggestions from review

Signed-off-by: Guillaume Doisy <[email protected]>

---------

Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>

* Merged Fix navfn_planner from humble PR ros-navigation#5087 (ros-navigation#5092)

* merged changes from humble for goal.header fix

* reverted back, error in merge

* ported goal.header fix in navfn_planner.cpp from humble

* reverted to navfn_planner.cpp to origin/main

* merged navfn_planner.cpp from humble

* fixed the merge

* Update map_io library to use Eigen method for faster map loading (ros-navigation#5071)

* Update map_io library to use opencv method for faster map loading

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit config changes

Signed-off-by: Vignesh T <[email protected]>

* Use Eigen approach instead of OpenCV

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit changes

Signed-off-by: Vignesh T <[email protected]>

* Update include header include order

Signed-off-by: Vignesh T <[email protected]>

* Remove intermediary alpha matrix

Signed-off-by: Vignesh T <[email protected]>

* Add comments for the code understanding

Signed-off-by: Vignesh T <[email protected]>

* Fix else braces rule issue

Signed-off-by: Vignesh T <[email protected]>

* Create and use alpha_matrix when applying mask

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit changes

Signed-off-by: Vignesh T <[email protected]>

* Take flip part out of if-else

Signed-off-by: Vignesh T <[email protected]>

* Update pre-commit changes

Signed-off-by: Vignesh T <[email protected]>

---------

Signed-off-by: Vignesh T <[email protected]>

* Precompute yaw trigonometric values in smac planner (ros-navigation#5109)

Signed-off-by: mini-1235 <[email protected]>

* removing the start navigation message in the paused state from rviz buttons (ros-navigation#5137)

Signed-off-by: Pradheep <[email protected]>

* Show error if inflation radius is smaller than circumscribed radius (ros-navigation#5148)

* Warn if inflation radius is smaller than circumscribed radius

Signed-off-by: Tony Najjar <[email protected]>

* Update nav2_mppi_controller/src/critics/cost_critic.cpp

Co-authored-by: Steve Macenski <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>

* Update nav2_smac_planner/include/nav2_smac_planner/utils.hpp

Co-authored-by: Steve Macenski <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* Prevent MPPI controller from resetting speed limits upon goal execution. (ros-navigation#5165)

Signed-off-by: Leander Stephen D'Souza <[email protected]>

* Fixing docking server when already docked at the requeste ddock (ros-navigation#5171)

Signed-off-by: Steve Macenski <[email protected]>

* Adding parameter util to node utils (ros-navigation#5154)

* Adding declare_or_get_param util to node utils

Signed-off-by: Marco Bassa <[email protected]>

* Adding test for declare_or_get_param util

Signed-off-by: Marco Bassa <[email protected]>

* Adding declare_or_get_parameter function by type, using explicit variable names, disabling param warnings by default

Signed-off-by: Marco Bassa <[email protected]>

* Update nav2_util/test/test_node_utils.cpp

Signed-off-by: Steve Macenski <[email protected]>

* Fixing codecove test

Signed-off-by: Marco Bassa <[email protected]>

* Catching possible exception in declare_or_get_by_type

Signed-off-by: Marco Bassa <[email protected]>

* Templating return type of declare parameter by value

Signed-off-by: Marco Bassa <[email protected]>

---------

Signed-off-by: Marco Bassa <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* added config for laserscan in lb-sim (ros-navigation#5174)

* added config for laserscan in lb-sim

Signed-off-by: RamanaBotta <[email protected]>

* fixing ament_flake8 errors

Signed-off-by: RamanaBotta <[email protected]>

* review: use_inf is default:true and added parameters on readme ros-navigation#4992

Signed-off-by: RamanaBotta <[email protected]>

* refactor: meaningfull value for scan_angle_increment

Signed-off-by: RamanaBotta <[email protected]>

---------

Signed-off-by: RamanaBotta <[email protected]>
Co-authored-by: RamanaBotta <[email protected]>

* Publish planned footprints after smoothing (ros-navigation#5155)

* Publish planned footprints after smoothing

Signed-off-by: Tony Najjar <[email protected]>

* Revert "Publish planned footprints after smoothing"

This reverts commit c9b349a.

* Add smoothed footprints publishing

Signed-off-by: Tony Najjar <[email protected]>

* fix formatting

Signed-off-by: Tony Najjar <[email protected]>

* Fix indentation for publisher creation in SmacPlannerHybrid and SmacPlannerLattice

Signed-off-by: Tony Najjar <[email protected]>

* address PR comments

Signed-off-by: Tony Najjar <[email protected]>

* fixes

Signed-off-by: Tony Najjar <[email protected]>

* fix build error

Signed-off-by: Tony Najjar <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>

* fixing deprecation warning (ros-navigation#5182)

Signed-off-by: Steve Macenski <[email protected]>

* Adding missing dep to loopback sim (ros-navigation#5204)

* Adding missing dep

Signed-off-by: Steve Macenski <[email protected]>

* typo

Signed-off-by: Steve Macenski <[email protected]>

* updating fix

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>

* Adding parameter warn_when_defaulting_parameters to control default parameter warnings (ros-navigation#5189)

* Adding a parameter warn_when_defaulting_parameters to control default parameter warnings instead of using a flag

Signed-off-by: Marco Bassa <[email protected]>

* Adding parameter strict_param_loading for optionally throwing an exception if parameter overrides are missing

Signed-off-by: Marco Bassa <[email protected]>

* Using default false declaration instead of declare_or_get in param util

Signed-off-by: Marco Bassa <[email protected]>

---------

Signed-off-by: Marco Bassa <[email protected]>

* bumping to 1.3.7 for release

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Nils-ChristianIseke <[email protected]>
Signed-off-by: Guillaume Doisy <[email protected]>
Signed-off-by: Vignesh T <[email protected]>
Signed-off-by: mini-1235 <[email protected]>
Signed-off-by: Pradheep <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Leander Stephen D'Souza <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Signed-off-by: Marco Bassa <[email protected]>
Signed-off-by: RamanaBotta <[email protected]>
Co-authored-by: Nils-Christian Iseke <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Sandeep Dutta <[email protected]>
Co-authored-by: Vignesh T <[email protected]>
Co-authored-by: mini-1235 <[email protected]>
Co-authored-by: Pradheep Krishna <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: Leander Stephen D'Souza <[email protected]>
Co-authored-by: Marco Bassa <[email protected]>
Co-authored-by: Raman <[email protected]>
Co-authored-by: RamanaBotta <[email protected]>

* Fixing Jazzy CI via new ROS 2 keys

Signed-off-by: Steve Macenski <[email protected]>

* Revert "Fix Ci from key signing (ros-navigation#5220)" (backport ros-navigation#5237) (ros-navigation#5239)

* Revert "Fix Ci from key signing (ros-navigation#5220)" (ros-navigation#5237)

* Revert "Fix Ci from key signing (ros-navigation#5220)"

This reverts the changes to the Dockerfile done in 1345c22.

Signed-off-by: Nils-Christian Iseke <[email protected]>

* Update Cache Version

Signed-off-by: Nils-Christian Iseke <[email protected]>

---------

Signed-off-by: Nils-Christian Iseke <[email protected]>
(cherry picked from commit 7f561b0)

# Conflicts:
#	.circleci/config.yml

* Update config.yml

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Nils-Christian Iseke <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* Backport bidirectional settings ros-navigation#4954 (ros-navigation#5260)

Signed-off-by: Tatsuro Sakaguchi <[email protected]>

* Add namespace support for rviz costmap cost tool (ros-navigation#5271)

Signed-off-by: Maurice-1235 <[email protected]>

* Use fixed thresholds for Trinary yaml (ros-navigation#5278) (ros-navigation#5286)

(cherry picked from commit 829e683)

Signed-off-by: Adi Vardi <[email protected]>
Co-authored-by: Adi Vardi <[email protected]>

* Clear costmap around pose jazzy (backport ros-navigation#5309) (ros-navigation#5318)

* Adding clear costmap around pose service option (ros-navigation#5309)

(cherry picked from commit c0bf67e
Signed-off-by: dw25628 <[email protected]>

* Linting

Signed-off-by: dw25628 <[email protected]>

* Removed __init__.py that came in with cherry pick

Signed-off-by: dw25628 <[email protected]>

---------

Signed-off-by: dw25628 <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* Backport "Option to Reduce Lethal to High-Cost Navigable To Get Out of Keepout Zones if Wandered In" (ros-navigation#5378)

* Option to Reduce Lethal to High-Cost Navigable To Get Out of Keepout Zones if Wandered In (ros-navigation#5187)

* Adding toggle option of keepout zone

Signed-off-by: Steve Macenski <[email protected]>

* Default off

Signed-off-by: Steve Macenski <[email protected]>

* Join conditions

Signed-off-by: Steve Macenski <[email protected]>

* spell check

Signed-off-by: Steve Macenski <[email protected]>

* copilot suggestions

Signed-off-by: Steve Macenski <[email protected]>

* Update nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp

Co-authored-by: Leander Stephen D'Souza <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>

* Update nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp

Co-authored-by: Leander Stephen D'Souza <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>

* Update keepout_filter.cpp

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Leander Stephen D'Souza <[email protected]>

* Revert bringup params changes

Signed-off-by: Maurice <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>
Signed-off-by: Maurice <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>
Co-authored-by: Leander Stephen D'Souza <[email protected]>

* Adding minimum range to PC2 in collision monitor (backport ros-navigation#5392) (ros-navigation#5393)

* Adding minimum range to PC2 in collision monitor (ros-navigation#5392)

Signed-off-by: SteveMacenski <[email protected]>
(cherry picked from commit 40a0451)

# Conflicts:
#	nav2_collision_monitor/src/pointcloud.cpp

* Update pointcloud.cpp

Signed-off-by: Steve Macenski <[email protected]>

* Update pointcloud.cpp

Signed-off-by: Steve Macenski <[email protected]>

* Update sources_test.cpp

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* Construct TF listeners passing nodes, spinning on separate thread (backport ros-navigation#5406) (ros-navigation#5431)

* Construct TF listeners passing nodes, spinning on separate thread (ros-navigation#5406)

* Construct TF listeners passing nodes, spinning on separate thread

Signed-off-by: Patrick Roncagliolo <[email protected]>

* (tentative) pin down of the impacting change

Signed-off-by: Patrick Roncagliolo <[email protected]>

---------

Signed-off-by: Patrick Roncagliolo <[email protected]>
(cherry picked from commit 1468484)

# Conflicts:
#	nav2_route/src/route_server.cpp

* Delete nav2_route/src/route_server.cpp

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Patrick Roncagliolo <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* Fix lifecycle manager deadlock during shutdown (ros-navigation#5448)

Signed-off-by: Jacob Visser <[email protected]>

* fix 5456 (ros-navigation#5458)

Signed-off-by: David G <[email protected]>

* backport the fix for setting binary_state as the default (ros-navigation#5459)

Signed-off-by: olaghattas <[email protected]>

* Sync Jazzy Aug 19, 2025 1.4.1 (ros-navigation#5469)

* Conserve curvature with LIMIT action (ros-navigation#5255)

* Conserve curvature with LIMIT action

Signed-off-by: Tony Najjar <[email protected]>

* fix format

Signed-off-by: Tony Najjar <[email protected]>

* fix test

Signed-off-by: Tony Najjar <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>

* Adding epsilon for voxel_layer precision loss (ros-navigation#5314)

* Adding epsilon for voxel_layer precision loss

Signed-off-by: bhx <[email protected]>

* Update nav2_costmap_2d/plugins/voxel_layer.cpp

Signed-off-by: Steve Macenski <[email protected]>

* Update nav2_costmap_2d/plugins/voxel_layer.cpp

Signed-off-by: Steve Macenski <[email protected]>

* Update nav2_costmap_2d/plugins/voxel_layer.cpp

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: bhx <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* fix: correct ThroughActionResult type alias in would_a_planner_recovery_help_condition (ros-navigation#5326)

The ThroughActionResult type alias was incorrectly referencing Action::Result 
instead of ThroughAction::Result, causing the condition to not work properly 
for ComputePathThroughPoses actions.

Fixes ros-navigation#5324

Co-authored-by: claude[bot] <209825114+claude[bot]@users.noreply.github.com>

* Adding slow down at target heading to RPP Controller (ros-navigation#5361)

* Adding slow down at target heading to RPP

Signed-off-by: SteveMacenski <[email protected]>

* Update test_regulated_pp.cpp

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: SteveMacenski <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>

* Eexception rethrow in dockRobot method (ros-navigation#5364)

Signed-off-by: Alberto Tudela <[email protected]>

* Add global min obstacle height in voxel layer (ros-navigation#5389)

* Add min obstacle height in voxel layer

Signed-off-by: mini-1235 <[email protected]>

* Fix linting

Signed-off-by: Maurice <[email protected]>

---------

Signed-off-by: mini-1235 <[email protected]>
Signed-off-by: Maurice <[email protected]>

* [DEX] Enforce 3 digits precision (ros-navigation#5398)

Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>

* [static_layer] limit comparison precision (ros-navigation#5405)

* [DEX] limit comparison precision

Signed-off-by: Guillaume Doisy <[email protected]>

* EPSILON 1e-5

Signed-off-by: Guillaume Doisy <[email protected]>

---------

Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>

* Smooth path even if goal pose is so much near to the robot (ros-navigation#5423)

* Smooth path even if goal pose is so much near to the robot

Signed-off-by: CihatAltiparmak <[email protected]>

* Apply suggestions

Signed-off-by: CihatAltiparmak <[email protected]>

* Remove unnecessary diff

Signed-off-by: CihatAltiparmak <[email protected]>

---------

Signed-off-by: CihatAltiparmak <[email protected]>

* Fix KeepoutFilter on the ARM architecture (ros-navigation#5436)

Signed-off-by: Sushant Chavan <[email protected]>

* Fix missing dependency (ros-navigation#5460)

* bump to 1.3.8 for Jazzy release Aug 19, 2025

Signed-off-by: SteveMacenski <[email protected]>

* load balance CI

Signed-off-by: SteveMacenski <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: bhx <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Signed-off-by: SteveMacenski <[email protected]>
Signed-off-by: Alberto Tudela <[email protected]>
Signed-off-by: mini-1235 <[email protected]>
Signed-off-by: Maurice <[email protected]>
Signed-off-by: Guillaume Doisy <[email protected]>
Signed-off-by: CihatAltiparmak <[email protected]>
Signed-off-by: Sushant Chavan <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: hutao <[email protected]>
Co-authored-by: claude[bot] <209825114+claude[bot]@users.noreply.github.com>
Co-authored-by: Alberto Tudela <[email protected]>
Co-authored-by: mini-1235 <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Cihat Kurtuluş Altıparmak <[email protected]>
Co-authored-by: Sushant Chavan <[email protected]>
Co-authored-by: Tim Clephas <[email protected]>

* fix: Move SmootherParams declaration outside smooth_path conditional (ros-navigation#5473) (ros-navigation#5474)

Fixes crash when dynamically changing smooth_path parameter from false to true.
The issue occurred because SmootherParams were only declared when smooth_path
was initially true, causing ParameterModifiedInCallbackException when trying
to declare parameters within the dynamic parameter callback.

Now SmootherParams are always declared, making them available for dynamic
reconfiguration regardless of the initial smooth_path value.

Fixes ros-navigation#5472


(cherry picked from commit 69a60df)

Co-authored-by: Steve Macenski <[email protected]>
Co-authored-by: claude[bot] <209825114+claude[bot]@users.noreply.github.com>

* Replace last pose if only orientation differs in Navfn (ros-navigation#5490) (ros-navigation#5492)

(cherry picked from commit ff80727)

Signed-off-by: mini-1235 <[email protected]>
Co-authored-by: mini-1235 <[email protected]>

* Manual Backport Route Server to Jazzy (ros-navigation#5517)

* Manual backport of Route Server to Jazzy

Signed-off-by: Steve Macenski <[email protected]>

* linting

Signed-off-by: Steve Macenski <[email protected]>

* Fix backport error

Signed-off-by: Steve Macenski <[email protected]>

* lint

Signed-off-by: Steve Macenski <[email protected]>

* Adding in Nav2 BT + Launch

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>

* Jazzy Sync Sept 19, 2025 1.3.9 (ros-navigation#5540)

* Fix dynamic param SmacPlannerLattice  (ros-navigation#5478)

* Fix SmacPlannerLattice dynamic parameter early exit

Signed-off-by: Tony Najjar <[email protected]>

* remove comment

Signed-off-by: Tony Najjar <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>

* Fix duplicate poses with computePlanThroughPoses (ros-navigation#5488)

* fix-duplicate-poses

Signed-off-by: Tony Najjar <[email protected]>

* Update nav2_planner/src/planner_server.cpp

Co-authored-by: Steve Macenski <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* Fix seg fault (ros-navigation#5501)

* Fix segmentation fault

Signed-off-by: Tony Najjar <[email protected]>

* fix linting

Signed-off-by: Tony Najjar <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>

* Add a service for enabling/disabling the collision monitor (ros-navigation#5493)

* Added std_srvs package to dependencies

Signed-off-by: Abhishekh Reddy <[email protected]>

* Declared service and callback for enabling/disabling collision monitor

Signed-off-by: Abhishekh Reddy <[email protected]>

* Declared a variable to store collision monitor enable/disable state

Signed-off-by: Abhishekh Reddy <[email protected]>

* Added initialization for collision monitor enable/disable service

Signed-off-by: Abhishekh Reddy <[email protected]>

* Implemented service callback for collision monitor enable/disable service

Signed-off-by: Abhishekh Reddy <[email protected]>

* Removed std_srvs package dependency

Signed-off-by: Abhishekh Reddy <[email protected]>

* Added Toggle interface

Signed-off-by: Abhishekh Reddy <[email protected]>

* Replaced Trigger interface with the new Toggle interface

Signed-off-by: Abhishekh Reddy <[email protected]>

* Added default initialization for enabled flag

Signed-off-by: Abhishekh Reddy <[email protected]>

* Fixed toggle service name

Signed-off-by: Abhishekh Reddy <[email protected]>

* Updated toggle logic for collision monitor

Signed-off-by: Abhishekh Reddy <[email protected]>

* Added a new line at the end of file

Signed-off-by: Abhishekh Reddy <[email protected]>

* Update nav2_collision_monitor/src/collision_monitor_node.cpp

Co-authored-by: Steve Macenski <[email protected]>
Signed-off-by: Abhishekh Reddy <[email protected]>

* Update nav2_collision_monitor/src/collision_monitor_node.cpp

Co-authored-by: Steve Macenski <[email protected]>
Signed-off-by: Abhishekh Reddy <[email protected]>

* Added enabled check for logging

Signed-off-by: Abhishekh Reddy <[email protected]>

* Added a unit test for toggle service

Signed-off-by: Abhishekh Reddy <[email protected]>

* Made the getter const and added a comment

Signed-off-by: Abhishekh Reddy <[email protected]>

* Replaced rclcpp::spin_some

Signed-off-by: Abhishekh Reddy <[email protected]>

---------

Signed-off-by: Abhishekh Reddy <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* bump Jazzy to 1.3.9 for release

Signed-off-by: SteveMacenski <[email protected]>

* Change service type for collision monitor

Signed-off-by: Steve Macenski <[email protected]>

* Fix backport error

Signed-off-by: SteveMacenski <[email protected]>

* update

Signed-off-by: SteveMacenski <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Abhishekh Reddy <[email protected]>
Signed-off-by: SteveMacenski <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: Abhishekh Reddy <[email protected]>

* Update package version from 1.1.0 to 1.3.9

Signed-off-by: Steve Macenski <[email protected]>

* Add support for dynamically changing keepout zone (ros-navigation#5429) (ros-navigation#5542)

* Add support for dynamically changing keepout zone



* Linting



* Revert binary and speed changes



---------


(cherry picked from commit e690ef0)

Signed-off-by: mini-1235 <[email protected]>
Co-authored-by: mini-1235 <[email protected]>

* Fix bad_weak_ptr in createBond() by using shared_ptr (backport ros-navigation#5341) (ros-navigation#5563)

Signed-off-by: ymd-stella <[email protected]>

* Fixed crash due to incorrect string construction (ros-navigation#5606) (ros-navigation#5613)

(cherry picked from commit 48e7e06)

Signed-off-by: Jay Herpin <[email protected]>
Co-authored-by: Jay Herpin <[email protected]>

* Add dependency on nav2_route in package.xml (ros-navigation#5639)

Signed-off-by: Steve Macenski <[email protected]>

* Revert ros-navigation#4971 in Jazzy (ros-navigation#5640)

* Revert ros-navigation#4971 in Jazzy

Signed-off-by: mini-1235 <[email protected]>

* Add

Signed-off-by: mini-1235 <[email protected]>

---------

Signed-off-by: mini-1235 <[email protected]>

* Bumping to 1.3.10 for urgent jazzy regression fixes (ros-navigation#5650)

Signed-off-by: SteveMacenski <[email protected]>

* Backporting custom height point field into Jazzy. (ros-navigation#5646)

* Summary commit of all changes for adding custom pointcloud field height. (ros-navigation#5586)

Doing this to clear out unsigned commits from history.

Signed-off-by: Greg Anderson <[email protected]>

* Corrected parameter declaration methods that aren't part of Jazzy.
Fixed parameter typo from some manual merging in pointcloud.cpp

Signed-off-by: Greg Anderson <[email protected]>

---------

Signed-off-by: Greg Anderson <[email protected]>

---------

Signed-off-by: Nils-ChristianIseke <[email protected]>
Signed-off-by: Guillaume Doisy <[email protected]>
Signed-off-by: Vignesh T <[email protected]>
Signed-off-by: mini-1235 <[email protected]>
Signed-off-by: Pradheep <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Leander Stephen D'Souza <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Signed-off-by: Marco Bassa <[email protected]>
Signed-off-by: RamanaBotta <[email protected]>
Signed-off-by: Tatsuro Sakaguchi <[email protected]>
Signed-off-by: Maurice-1235 <[email protected]>
Signed-off-by: Adi Vardi <[email protected]>
Signed-off-by: dw25628 <[email protected]>
Signed-off-by: Maurice <[email protected]>
Signed-off-by: Jacob Visser <[email protected]>
Signed-off-by: David G <[email protected]>
Signed-off-by: olaghattas <[email protected]>
Signed-off-by: bhx <[email protected]>
Signed-off-by: SteveMacenski <[email protected]>
Signed-off-by: Alberto Tudela <[email protected]>
Signed-off-by: CihatAltiparmak <[email protected]>
Signed-off-by: Sushant Chavan <[email protected]>
Signed-off-by: Abhishekh Reddy <[email protected]>
Signed-off-by: ymd-stella <[email protected]>
Signed-off-by: Jay Herpin <[email protected]>
Signed-off-by: Greg Anderson <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>
Co-authored-by: Nils-Christian Iseke <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Sandeep Dutta <[email protected]>
Co-authored-by: Vignesh T <[email protected]>
Co-authored-by: mini-1235 <[email protected]>
Co-authored-by: Pradheep Krishna <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: Leander Stephen D'Souza <[email protected]>
Co-authored-by: Marco Bassa <[email protected]>
Co-authored-by: Raman <[email protected]>
Co-authored-by: RamanaBotta <[email protected]>
Co-authored-by: mergify[bot] <37929162+mergify[bot]@users.noreply.github.com>
Co-authored-by: Tatsuro Sakaguchi <[email protected]>
Co-authored-by: Adi Vardi <[email protected]>
Co-authored-by: dw25628 <[email protected]>
Co-authored-by: Patrick Roncagliolo <[email protected]>
Co-authored-by: cboostjvisser <[email protected]>
Co-authored-by: DavidG-Develop <[email protected]>
Co-authored-by: olaghattas <[email protected]>
Co-authored-by: hutao <[email protected]>
Co-authored-by: claude[bot] <209825114+claude[bot]@users.noreply.github.com>
Co-authored-by: Alberto Tudela <[email protected]>
Co-authored-by: Cihat Kurtuluş Altıparmak <[email protected]>
Co-authored-by: Sushant Chavan <[email protected]>
Co-authored-by: Tim Clephas <[email protected]>
Co-authored-by: Abhishekh Reddy <[email protected]>
Co-authored-by: ymd-stella <[email protected]>
Co-authored-by: Jay Herpin <[email protected]>
Co-authored-by: Greg Anderson <[email protected]>
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.

2 participants