Skip to content

Conversation

@SteveMacenski
Copy link
Member

@SteveMacenski SteveMacenski commented Nov 19, 2021

There have been near-endless tickets of issues regarding live groot monitoring, so we'll be removing it from Nav2 since it really hasn't worked out well since we introduced it.

It was a great feature idea but never quite panned out, especially after we introduced multiple navigator types in the BT Navigator server. The issue we run into primarily is that Zero-MQ prevents users from producing multiple logger types in the same process. Since BT nav has multiple servers, the swapping between them for viewing has never had a clean hand off causing folks to file tickets or have nasty logs appear or ZMQ crashes in the background. The BT.CPP client for this doesn't allow us to have a clean shutdown process so we're left with hoping that ZMQ properly handles the situation, which it rarely does. Further, Groot only supports visualizing one type of tree at a time so for applications often switching between navigator types, its not possible to use a single groot client, causing great frustration.

So, what I propose here is to remove live monitoring of the BT from Nav2. We can still use Groot to modify, visualize, and generally work with behavior trees, the only thing being removed is to live view the executing behavior tree as Nav2 is currently executing it (it used to light up the boxes of the current nodes). This was of dubious value anyhow, since the tree ticks so fast its difficult to visualize and get meaningful insights into things as the system is moving so quickly.

Ex. tickets

@ros-navigation ros-navigation deleted a comment from mergify bot Nov 20, 2021
@SteveMacenski SteveMacenski merged commit c15ccbf into main Nov 20, 2021
@SteveMacenski SteveMacenski deleted the remove_live_groot branch November 20, 2021 02:07
@elyarzv
Copy link

elyarzv commented Feb 28, 2022

I have created a behavior tree in ROS1. I am able to have live tree monitoring in Groot. The only problem is that is doesn't reflect the status of the last node and consequetly the whole tree.

macstepien added a commit to husarion/rosbot_xl_ros that referenced this pull request Jul 12, 2022
sergigraum pushed a commit to umdlife/navigation2 that referenced this pull request Aug 26, 2022
* Name bt_navigator action nodes uniquely (#2410)

Co-authored-by: Jonatan Olofsson <[email protected]>

* Fix code coverage (#2419)

* Include filter only by packge name
as using package source paths can exclude coverage from other packages
such as header files reported usign under workspace's install path

* formating

* Process gcno
Process both gcno and gcda coverage files.
This option is useful for capturing untested files in the coverage report.

* Validate sources
Check if every source file exists

* Dump statistic
Dump total statistic at the end

* Branch coverage
Include only the most useful branches in the coverage report.

* Fix install path

* Explicitly exclude packages
to ignore rviz package
but still explicitly include packages
as the include filter is what mostly speeds up processing

* Revert "Branch coverage"

This reverts commit 20f28949904ef965c8b5b011f3e387037adc93ce.

* Keep path fixes relative to workspace

As the working directory used for running code coverage report script 
is already at the root of the colcon workspace,
avoiding the use of unnecessary path globbing

* Followup to PR 2413 for main branch (fix for operator= in observation.hpp) (#2425)

* in observation.hpp fixed operator=

* style fix

* Update README.md

* Add lazy_theta_star (#1839)

* Add lazy_theta_star

* Added license

* Added license

* Update lazy_theta_star_b.cpp

* restructured files

- separated planner part and the algorithm
- implemented all the changes as suggested

* restructured files

* Update CMakeLists.txt

* removed unnecessary comments

* removed comments

* Delete planner.cpp

* Delete lazy_theta_star_b.cpp

* Delete lazy_theta_star_b.h

* Delete planner.h

* Delete CMakeLists.txt

* Delete global_planner_plugin.xml

* Delete package.xml

* replaced the files

- refactored code
- improved reliability
- have to write a code similar to that in nav2_system_tests, to test it (working on it)

* removed comments

* removed comments

* Update lazy_theta_star2.cpp

* update files

- replaced manual management of priority queue with stl priority queue
- added the parameter ".lethal_cost"
- removed unnecessary parameters passed to the functions

* update files

- updated the header files in accordance to their .cpp counterparts

* Delete lazy_theta_star2.h

* Delete lazy_theta_star_planner.h

* Delete lazy_theta_star2.cpp

* Delete lazy_theta_star_planner.cpp

* Delete CMakeLists.txt

* Delete package.xml

* Delete global_planner_plugin.xml

* upload the changed code

Changes from last time are:
- the code has been changed to the Lazy Theta* P variant, in order to account for the costmap traversal costs
- parameters are available to change the weights of the costmap traversal cost (weight = 1.75, as of now) and the distance function (weight = 1.0, as of now
-

* Delete lazy_theta_star_p_planner directory

* Replace the old files

- the structure of code has been changed
- new functions have been added, namely : getTraversalCost, getEuclideanCost, getCellCost, isSafe[it is now an overloaded function]
- documentation added for variables and functions
- the parameters for the planner now consists of : how_many_corners, costmap_tolerance, euc_tolerance (documentation to added soon)
- fixed a bug where the incorrect traversal cost of the node was taken

* Delete lazy_theta_star_p_planner directory

* update the files

- renamed the project to nav2_theta_star_planner from lazy_theta_star_p_planner
- renamed files from lazy_theta_p_planner.hpp/.cpp to theta_star_planner.hpp/.cpp and lazy_theta_star.hpp/.cpp to theta_star.hpp/.cpp
- added a readme file outlining the parameters, usage notes and images to be added soon
- added parameters and renamed the parameters for the cost function (costmap_tolerance -> w_traversal_cost ; euc_tolerance -> w_euc_cost ; added a parameter for the heuristic)
- replaced the SharedPtr with a WeakPtr for node
- removed +1 and the pusher_ variable added to compensate for it

* Update README.md

* update the code

- linted the code 
- **updates to readme, are still pending**
- changed the type of message from INFO to DEBUG
- replaced the capital letters with the smaller ones

* update the readme file

* Update README.md

* Update README.md

* Update README.md

* Update README.md

* Delete global_planner_plugin.xml

* fix the linting issues

* remove the space on line 7

* change RCLCPP_INFO to RCLCPP_DEBUG

* Update README.md

* Add test coverage

- added tests to check the algorithm itself and its helper functions
- added smoke test to detect plugin level issues
- inlined some functions 
- shifted the functions `setStartAndGoal()` and `isSafeToPlan()` to the ThetaStar class
- removed the functions `dist()` and `getCellCost()` from the ThetaStar class

* update the test file

* update the test file

* Update README.md

* Update README.md

* Update README.md

* add test on the size of the output path

* Update README.md

* Update README.md

* change the function name from `isSafeToPlan()` to `isUnsafeToPlan()`

* update the files

- inlined the functions `getIndex` and `addIndex`
- removed typos from the comments

* fix typos

* Update README.md

* Update README.md

* Update README.md

* Update README.md

* Update README.md

* Update README.md

* Update README.md

* fix the typo

- the first isSafe calls output wasn't negated, it has been fixed

* Update theta_star.hpp

- added the `getCost()` function (again)
- replaced the use of indices with pointers to store the node's data, changes were made to the following functions - `addIndex()`, `getIndex()`, `initialisePosn()`.
- the priority queue now stores the pointer to node's data and accordingly changes were made to `comp` struct
- the global variable `curr_node` was renamed to `exp_node`
- removed the struct `pos`

* Update theta_star.cpp

* update default parameters

* update default parameters

* Update README.md

* update the test file

* fix linting issues

* Update README.md

* Update README.md

* Update README.md

* Update theta_star_planner.cpp

* update LETHAL_COST

* update README.md

* update dependency list

* Update package.xml

* Remove deprecated pluginlib boost feature disable (#2431)

Boost features have been deprecated and removed
in pluginlib for rolling

* Improve coverage for NavFn package (#2420)

* feat(navfn): improve coverage

* wip(navfn): add new test launch

* refactor(navfn): check expect_failure flag value

* Reduce nodes for nav2_waypoint_follower  (#2441)

* Reduce node of waypoint_follower by using callback group and executor

Signed-off-by: zhenpeng ge <[email protected]>

* fix linting failures

Signed-off-by: zhenpeng ge <[email protected]>

* missing comma in bt_navigator plugin list (#2447)

* Feature addition: capability for the RRP to drive the robot backwards  (#2443)

* Feature addition: capability for the RRP to drive the robot backwards

* findDirectionChange(): returns maximum double value + removing the size check for the indexer in for loop

* satisfying ament_uncrustify and ament_cpplint

* removing the unnecessary condition in the cusp determination

* Satisfying ament_uncrustify - 2

* Adding launch_testing_ros dep on nav2 utils to install (#2450)

* Update README.md (#2461)

* Refactor actions to rebuild CI image from CI (#2405)

* Add dependabot config

* Workarround missing ARG support in dependabot
Parrent image can't yet be parameterized for version parsing
https://github.com/dependabot/dependabot-core/issues/2057

* Fix CCACHE_DIR to be absolute path
https://github.com/ros-planning/navigation2/pull/2403

* Remove FAIL_ON_BUILD_FAILURE ARG
now that CI image builds from rolling testing
and no longer ros2 nightly
so forcing image rebuilds is no longer needed

* Trigger rebuild on changes to Dockerfile

* Add github-actions to dependabot

* Refactor actions to rebuild CI image from CI

* Clean old dockerhub build hook

* Rename action

* Combine workflows to avoid dispaching
as that requires a github personal access token
which is an inconvenience to generate and add to repo secrets

* Add needs param to define job order

* Use job outputs for condition instead of env
Seems that env in context is not yet avalable at the job level
but only at the current job's step level
https://github.community/t/how-to-set-and-access-a-workflow-variable/17335/6
https://docs.github.com/en/actions/reference/workflow-syntax-for-github-actions#jobsjob_idoutputs

* Use multi-line syntax for tags param

* Use toJSON for job conditional

* Test with always

* Update param syntax

* Test with always

* Update if syntax

* Test if trigger for only check_ci_files

* Simplify if params

* Try using GitHub's Container registry

* Indent formating

* Add step conditional

* Default arg to build from unpinned parrent stage
allowing CI to build from pinned testing image
while enabling dependabot to find and update testing image version
ensuring CI images are up-to-date with upstream registries

* Set build arg for continuous integration

* Ignore .github folder

* testing

* Update colcon-cache

* Revert to rolling

* Revert testing

* Update README

* SMAC Planner: Treating "inscribed" costs not as collision anymore (#2464)

* Reduce map saver nodes (#2454)

* reduce MapSaver nodes by using callback group/executor combo

Signed-off-by: zhenpeng ge <[email protected]>

* set use_rclcpp_node false

* a cleaner solution using a future and spin_until_future_complete()

Signed-off-by: zhenpeng ge <[email protected]>

* Update nav2_controller.cpp (#2462)

Add `costmap_thread_.reset()` on the destructor of ControllerServer class

* Reduce lifecycle manager nodes (#2456)

* remove bond_client_node_ in class LifecycleManager

Signed-off-by: zhenpeng ge <[email protected]>

* clear unused variables

Signed-off-by: zhenpeng ge <[email protected]>

* fix lint

Signed-off-by: zhenpeng ge <[email protected]>

* use dedicated executor thread

Signed-off-by: William Woodall <[email protected]>

* fix building error

Signed-off-by: zhenpeng ge <[email protected]>

* support to process executor for NodeThread

Signed-off-by: zhenpeng ge <[email protected]>

* use  NodeThread for LifecycleManager

Signed-off-by: zhenpeng ge <[email protected]>

Co-authored-by: William Woodall <[email protected]>

* sync with main and use ros_diff_drive in case name changes (#2472)

Co-authored-by: YOUSSEF LAHROUNI <[email protected]>

* Reduce lifecycle service client nodes (#2469)

* remove LifecycleServiceClient's constructor which create internal node

Signed-off-by: zhenpeng ge <[email protected]>

* fix the linter

Signed-off-by: zhenpeng ge <[email protected]>

* Python string format (#2466)

* Convert to python format strings for readability

* Merge concatenated strings

* Revert converting generated files

* Single quotes for consistency

* Just print the exception

* Fix Smac cleanup (#2477)

* fix smac2d cleanup

* same for hybrid

* Naming BT client node after action name (#2470)

* Put action name in node namespace instead of node name

* Put namespace remapping in node options

* Rename client node with action name replacing "/" by "_"

* Code formatting

* Code formatting

* improve SimpleActionServer (#2459)

* improve SimpleActionServer

Signed-off-by: zhenpeng ge <[email protected]>

add a bool argument spin_thread whether use callback group/executor combo with dedicated thread to handle server

Signed-off-by: zhenpeng ge <[email protected]>

* use Nodethread for executor

Signed-off-by: zhenpeng ge <[email protected]>

* add constructor's arg options and member variable executor_

Signed-off-by: zhenpeng ge <[email protected]>

* fix nav2 params and launch file to publish Local and global costmaps in multi robots example (#2471)

* adjust launch file with needed gazebo plugin and set groot to False for multi-robot params

* correct unwanted changes

* change port and set groot to false

* fix lints

Co-authored-by: YOUSSEF LAHROUNI <[email protected]>

* reduce planner server nodes (#2480)

Signed-off-by: zhenpeng ge <[email protected]>

* Reduce controller server nodes (#2479)

* reduce controller server nodes by setting SimpleActionServer's argument spin_thread true

Signed-off-by: zhenpeng ge <[email protected]>

* remove duplicated action_server_.reste()

Signed-off-by: zhenpeng ge <[email protected]>

* Update regulated_pure_pursuit_controller.cpp (#2484)

* [SmacPlanner2D] make tolerance parameter dynamic (#2475)

* make tolerance dyn param

* full reconfigure

* fix typo

* Place function above the variables

* lock param callback

* Modify the BtServiceNode to include an on_success call. (#2481)

* Modify the BtServiceNode to include an on_success call.

* PR: Fix linter error by removing trailing whitespaces.

* PR: Rename on_success() to on_completion() to improve understandability.

* Accept path of length 1 (#2495)

* Use regex anchors when checking for updates (#2500)

to fix conner cases like this:

https://github.com/ros-planning/navigation2/runs/3277796714?check_suite_focus=true

https://stackoverflow.com/a/4709921

* Update README.md

* adding default template constructor (#2501)

* Fix null pointer in amcl on_cleanup (#2503)

* fix data race: addPlugin() and resizeMap() can be executed concurrently (#2512)

Co-authored-by: Kai-Tao Xie <[email protected]>

* fix data race: VoxelLayer::matchSize may be executed concurrently (#2513)

Co-authored-by: Kai-Tao Xie <[email protected]>

* catch runtime_error if the message from laser is malformed (#2511)

* catch runtime_error if the message from laser is malformed

* fix styling

Co-authored-by: Kai-Tao Xie <[email protected]>

* Smac planner bad alloc (#2516)

* test(nav2_smac_planner): show short path bad_alloc

When given a goal that is one or zero costmap
cells away, AStarAlgorithm throws std::bad_alloc

* fix(nav2_smac_planner): fixed bad_alloc

* [ObstacleLayer] Use message_filter timeout (#2518)

* , tf2::durationFromSec(transform_tolerance)

* use message_filter timeout in AMCL

* also for sensor_msgs::msg::PointCloud2

* fix possible use-after-free: unsafe shared_ptr in multithread (#2510)

Co-authored-by: Kai-Tao Xie <[email protected]>

* Spawn turtlebot3 separately (#2473)

* add nav2 gazebo spawner

* fix origin pose

* add robot_description

* remove urdf arg

* fix whitespace

* spawn from file ;add initial pose

* remove spawn launch include

* param and rviz edit

* conflict resolve

* pose

* remove world tags and add tf remap

* use nav2 waffle model and spawn entity

* change nav2_spawner to  spawn_entity

* add tf remap

* delete nav2_gazebo_spawner

* sdf param

* added in readme

* changes

* fix export dependency and library (#2521)

Signed-off-by: zhenpeng ge <[email protected]>

* Add argument node options (#2522)

* add argument node_options

Signed-off-by: zhenpeng ge <[email protected]>

* change node's name

Signed-off-by: zhenpeng ge <[email protected]>

* fix code style

Signed-off-by: zhenpeng ge <[email protected]>

* Add more semantic checks for amcl parameters (#2528)

* Fix null pointer in amcl on_cleanup

* Add more semantic checks for amcl

* fix possible use-after-free: unsafe shared_ptr in multithread (#2530)

Co-authored-by: Kai-Tao Xie <[email protected]>

* Hot fix rrp slow (#2526)

* review update

* updated the 2nd review comments

* String formatting

* fix multi_robot_test (#2524)

* Update README.md

* remove old build tools (#2532)

* Fix out of voxel grid array regression (#2460)

* Update dwb_local_planner.hpp (#2533)

Add remarks

* nav2_bringup reorder (#2527)

* nav2_bringup reorder

* change to trigger

* manual remove cmd

* revert

* add manual rm comd

* change

* change

* change

* change

* change

* change

* revert

* change

* change

* change v1 to v2

* try --cmake-clean-cache

* try --cmake-clean-cache

* v2 cache

* v3 cache

* Add new test for smac_planner_2d (#2531)

* Add new test for smac_planner_2d

* Fix costmap initialization

* Change set_parameters() with set_parameters_atomically()

* Improving coverage

* Remove debug helper method

* Fix linting issue introduced in https://github.com/ros-planning/navigation2/pull/2533 (#2539)

* [All 2D planners] Fix last pose orientation, fix small path and add ignore_goal_orientation parameter (#2488)

* end point orientation

* add ignore_goal_orientation to dyn param

* back()  instead of [path.poses.size() - 1]

* Smac2d use_final_approach_orientation name

* add in NavFn

* add in theta_star

* wip

* deal with navfn double end pose case

* add tests

* back and revert test smac2d

* get path hotfix

* navfn wip

* Corner cases

* Checks consistency accross the 3 2D planners

* comment

* interpolate final orientation in planner instead of smoother

* clarify and homogenize comments

* using same cell test instead of distance compared to resolution

* remove unneeded else

* lint

* fix smac2d goal orientation override

* fix and add tests

* update comment

* typo

* simplify if (_use_final_approach_orientation) block

* Use worldToMapEnforceBounds in clear_costmap_service (#2544)

to avoid buffer overflow

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

* Add new test for nav2_regulated_pure_pursuit (#2542)

* unit test for findDirChg

* lint fix

* add test for unchanged direction

* fix  for loop ending

* Enabled runtime configuration of parameters for Hybrid A* (#2540)

* Enabled runtime configuration of parameters for Hybrid A*

* Fix parameter name

* Fix parameter type

* fix pf_ use-before-initial in laserReceived() callback (#2550)

Co-authored-by: Kai-Tao Xie <[email protected]>

* add semantic checks (#2557)

Co-authored-by: Kai-Tao Xie <[email protected]>

* Fix deprecated type conversion (#2538) (#2543)

Replace implicit deprecated type conversion from rclcpp::Client::FutureAndRequestId to std::shared_future with call to convenience method FutureAndRequestId::share()

Co-authored-by: Nikolay Panov <[email protected]>

* Register nodes as components (#2562)

Signed-off-by: zhenpeng ge <[email protected]>

* Updates to Nav2 Theta Star Planner docs (#2559)

* - removing 'w_heuristic_cost_' from Nav2 Theta Star Planner as a user configurable parameter
    - updates to `nav2_theta_star_planner/README.md` to remove its reference wherever applicable
    - updates to `nav2_theta_star_planner/src/theta_star_planner.cpp` to set `w_heuristic_cost` as `std::min(1.0, w_euc_cost_)`
- fixed an incorrect check of whether the start and goal pose are the same in `nav2_theta_star_planner/src/theta_star_planner.cpp`

* Update theta_star_planner.hpp

clean up stuff from forced merge

* Update theta_star_planner.cpp

clean up stuff from a forced merge

* Update README.md

* Update theta_star_planner.cpp

Re-adding the goal to ensure, that the last pose, is the goal exactly

* fix linting issues

* Update theta_star_planner.cpp

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

* Fixed vector::reserve exception in smac planner due to precision error (#2563)

- Related issue: https://github.com/ros-planning/navigation2/issues/2547

* Fixing minor build warnings (#2564)

* Fixed test_bt_navigator_with_groot_monitoring (#2568)

* removed redundant params in smac example (#2570)

* Support manual composed bringup for Nav2 applications (#2555)

* support manual composed bringup for Nav2 applications

Signed-off-by: zhenpeng ge <[email protected]>

* fix linters

Signed-off-by: zhenpeng ge <[email protected]>

* update

Signed-off-by: zhenpeng ge <[email protected]>

* rm composed_bringup_launch.py

Signed-off-by: zhenpeng ge <[email protected]>

* Update nav2_bringup/src/composed_bringup.cpp

* Update nav2_bringup/src/composed_bringup.cpp

* Update nav2_bringup/src/composed_bringup.cpp

* Update nav2_bringup/src/composed_bringup.cpp

* Update nav2_bringup/src/composed_bringup.cpp

* Update nav2_bringup/src/composed_bringup.cpp

* Update nav2_bringup/README.md

* Update nav2_bringup/README.md

* Update nav2_bringup/README.md

* Update nav2_bringup/README.md

* update nav2_bringup/README.md

Signed-off-by: zhenpeng ge <[email protected]>

* remove unused use_lifecycle_mgr

Signed-off-by: zhenpeng ge <[email protected]>

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

* Fixed model loading issue with Gazebo and Rviz2 (#2577)

1. Update uri(model://) of dae files for waffle model in waffle.model(Gazebo uses)
2. Update uri(package://) of dae files for turtlebot3_waffle.urdf(Rviz2
   uses)

* [Draft] Set parameters result example (#2576)

* change dyn param method

* typo

* remove unnecessary log

* handler init in activate

* Fix typo (#2583)

fix typo in warning msg;

* The smac planner max_planning_time parameter can timeout the A* planning stage (#2586)

- Until now the max_planning_time parameter only had an effect on the smoothing and sampling stages of the planner, so the actual A* planning could possibly take a lot longer

* Change dynamic parameters method (#2585)

* dyn param method

* dont add to reset for checkers

* fix test

* Resolving 2453: Adding timeout for recoveries in case of stuck conditions (#2589)

* allowing backup and spin to have timeouts in case of error / getting stuck

* fix linting

* Removing multi-robot test, flaky in CI and unneeded (#2601)

* Create mergify.yml (#2602)

* Create .mergify.yml

* Rename .mergify.yml to mergify.yml

* Fixes for Windows into main (#2603)

* Fix nav2_util

* Don't include libgen.h on Windows
* Replace sleep with Sleep on Windows

* Fix rviz plugin

Undef NO_ERROR from windows headers

* Fix smac_planner 

* Define _USE_MATH_DEFINES for M_PI
* Replace uint with unsigned int
* Don't add compiler flags that aren't supported on MSVC
* Use vector instead of VLA when building with MSVC

* Fix dirname for \ paths

* Fix typo

* Fix linter

* Delete head branch automatically on PR merge (#2608)

* Modified the projection_time calculation (#2609) (#2610)

(cherry picked from commit 8faa0f0550027edc7bf2640f23cff13b2af60a8f)

Co-authored-by: Narahari Rahul Malayanur <[email protected]>

* Update mergify.yml (#2612)

* Update mergify.yml

* Update mergify.yml

* Update mergify.yml

* Update mergify.yml

* Update mergify.yml

* Update mergify.yml (#2616)

* Update mergify.yml for Foxy backports and maintainer exceptions (#2620)

* Update mergify.yml

* Update mergify.yml

* adding dynamic params to RPP and cleaningup style in others (#2607)

* adding dynamic params to RPP and cleaningup style in others

* adding tests

* tests working

* adding alot more read me context and updates (#2625)

* Stopping networking-related BT failures from failing task, rather fail specific BT node (#2624)

* addig try/catch around non-tree exceptions to fail node

* Update bt_action_node.hpp

* linting

* Updating mergify rules for capitalization of usernames (#2630)

* adding groot separation by BT type (continuation on 2409) (#2627)

* adding groot separation by BT type

* fixing linting

* refactor of #2624 for simplicity (#2629)

* removing kinematic limiting from RPP (#2631)

* removing kinematic limiting from RPP

* update tests

* Resolving 2574: Smac 2D on map (#2588)

* Fixed model loading issue with Gazebo and Rviz2
1. Update uri(model://) of dae files for waffle model in waffle.model(Gazebo uses)
2. Update uri(package://) of dae files for turtlebot3_waffle.urdf(Rviz2
   uses)

* fixing off map expansions

Co-authored-by: aliben <[email protected]>

* Add dynamic parameters do Costmap2DROS (#2592)

* dyn params for costmap2dros

* simplify dyn footprint padding

* add test

* updated header for rolling

* Bug fix: set the BT Navigator "default_nav_to_pose_bt_xml" and "default_nav_through_pose_bt_xml" from the yaml file (#2664)

* removing the has_parameter() and replacing with the get_parameter()

* fixing navigate_through_poses as well

* Adding comment to clarify intent

* Refactored amcl code for modularization of motion models(main branch) (#2642)

* Delete nav2_amcl directory

* Add files via upload

* Remove "."

* Update CHANGELOG.rst

* Remove redundant code from CMakelists.txt

* Reverted amcl_node.cpp

* Cleaned up differential_motion_model.cpp

* Update plugins.xml

Removed redundant code,to make both the models under one library.

* Cleaned up omni_motion_model.cpp

* Cleaned up motion_model.cpp

* Delete CHANGELOG.rst

* Update CMakeLists.txt

* Update motion_model.hpp

* Add header files via upload

* Update amcl_node.cpp

* Update differential_motion_model.cpp

* Update omni_motion_model.cpp

* Update CMakeLists.txt

* Update differential_motion_model.hpp

* Update motion_model.hpp

* Update omni_motion_model.hpp

* Update amcl_node.cpp

* Update differential_motion_model.cpp

* Update motion_model.cpp

* Update omni_motion_model.cpp

* Update differential_motion_model.cpp

* Update differential_motion_model.hpp

* Update motion_model.hpp

* Update omni_motion_model.hpp

* Update differential_motion_model.cpp

* Update motion_model.cpp

* Update omni_motion_model.cpp

* Update differential_motion_model.hpp

* Update motion_model.hpp

* Update omni_motion_model.hpp

* Update motion_model.cpp

* Update motion_model.cpp

* Update nav2_params.yaml

* Update CMakeLists.txt

* Update nav2_multirobot_params_2.yaml

* Update nav2_multirobot_params_1.yaml

* Update speed_global_params.yaml

* Update speed_local_params.yaml

* Update keepout_params.yaml

* Footprint collision checking for nav2_regulated_pure_pursuit (#2556)

* initial

* initial

* initialize

* un

* working

* lint fix

* wrk

* clean_up

* remove code repettion

* rm unused variable

* initialize footprint on configure itself

* revert to defaulted constructer

* remove rviz change

* remove unneccessary changes

* review changes

* define traverse unkown

* set true

* reviw changes

* styling changes

* collision checking condition

* used back()

* make loop end condition fixed

* review changes

* fix

* removed midpose curvature

* removed stop collision check at goal pose

* Windows fix (#2672)

* Add support for reconfiguring params using GUI in ThetaStarPlanner (#2665)

* - removing 'w_heuristic_cost_' from Nav2 Theta Star Planner as a user configurable parameter
    - updates to `nav2_theta_star_planner/README.md` to remove its reference wherever applicable
    - updates to `nav2_theta_star_planner/src/theta_star_planner.cpp` to set `w_heuristic_cost` as `std::min(1.0, w_euc_cost_)`
- fixed an incorrect check of whether the start and goal pose are the same in `nav2_theta_star_planner/src/theta_star_planner.cpp`

* Update theta_star_planner.hpp

clean up stuff from forced merge

* Update theta_star_planner.cpp

clean up stuff from a forced merge

* Update README.md

* Update theta_star_planner.cpp

Re-adding the goal to ensure, that the last pose, is the goal exactly

* fix linting issues

* Update theta_star_planner.cpp

* update the README and code to prevent errors

* add support for reconfiguring params using GUI

* Update theta_star_planner.hpp

* fix linting issues

* remove  being set as the param

* Update theta_star_planner.cpp

* Update theta_star_planner.cpp

* Update theta_star_planner.cpp

* Update theta_star_planner.cpp

* Update theta_star_planner.cpp

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

* Corrected reinitialization in nav2_smac_planner::HybridMotionTable (#2680)

- The HybridMotionTable did not reinitialize properly in case the min_turning_radius or the motion_model was changed.

* State Lattice Planner Work Revival (#2582)

* adding state lattice beginning point

* refactoring to remove analytic expansion into its own object

* moving smoother and collision checker into cpp files

* allowing smac planner to work with irregular bin distributions

* integrating @jwallice42 s work and enabling reverse expansions

* adding in intermediate collision checking and backtracing

* adding traversal function

* adding test coverage and passing for node lattice

* adding updated rosdep key

* compiling, generating paths (though bogus)

* adding working base code

* adding search info

* fully working for non-lateral lattices

* removing downsampler for lattice, pushing in cost penalty

* adding in updated heuristics, tuned gains, and generally working for ackermann cases

* reverse expansion working

* adding complete support, refactoring, etc

* adding forgotten files

* adding readme updates

* adding max planning time to state lattice

* adding dynamic parameters

* removing extra config file

* fix linting

* updating test

* adding several unit tests

* adding system test

* fixing crash

* adding default model

* adding corrected exporting of plugins

* adding more test coverage

* reorder tests to see if natters

* unlink motions_lib plugin library in nav2_amcl (#2675)

* separate amcl_core library from motions_lib plugin library

Signed-off-by: zhenpeng ge <[email protected]>

* update plugins.xml

Signed-off-by: zhenpeng ge <[email protected]>

* update default value of robot_model_type

Signed-off-by: zhenpeng ge <[email protected]>

* debugging flaky shutdown on plugin planner tests (#2682)

* debugging flaky shutdown on plugin planner tests

* adding independent tests

* adding types

* adding new QoS and fix param declares

* try this

* try tihis

* try 10hz

* try sleeping on setup

* add footprint pub

* adding additional pub for debug

* try adding a spin for debug types

* Fix spin recovery test (#2684)

* debugging flaky shutdown on plugin planner tests

* adding independent tests

* adding types

* adding new QoS and fix param declares

* try this

* try tihis

* try 10hz

* try sleeping on setup

* add footprint pub

* adding additional pub for debug

* try adding a spin for debug types

* replacing spin with sleep

* Updating regex for mergify (#2691)

* Smoother server (#2569)

* old version of smoother server with path truncation and without collision checker and footprint subscriber

* Removed path truncation from smoother server, added footprint subscriber
and path collision checking

* smoother code styling fixes

* Update nav2_tree_nodes.xml

* WIP: PR #2569 fixes

* smoother server changes as requested in PR #2569, tests added

* cpplint fixes

* added nav2_smoother to composed bringup

* smoother server: improved test coverage, details fixed

* removed smoother from composed bringup lifecycle nodes as it fails on
non-existing plugins

* removed smoother server default plugin since it's not merged yet, readded into bringup

* nav2_smoother tests: added mocked class loader to improve
nav2_smoother.cpp test coverage

* nav2_smoother 100% test coverage

* test_smoother_server cpplint fix

* test_smoother_server added cleanup transition

* nav2_smoother added default plugin type autoconfig test

* Update nav2_smoother/README.md

* removed smoother_server_rclcpp_node from nav2_params.yaml, added
smoother_server to other config YAML files

Co-authored-by: afrixs <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>
Co-authored-by: Matej Vargovcik <[email protected]>

* removing dead code from AMCL (#2693)

* Lifecycle startup fix (#2694)

* removed init_timer from lifecycle callback group

* lifecycle manager: startup() on autostart_ calling from callback_group_
(Bond::waitUntilFormed needs node spinning in the background)

Co-authored-by: Matej Vargovcik <[email protected]>

* If not downsampling costmap, default factor to 1 (#2695)

* removing live groot monitoring from Nav2 (#2696)

* removing live groot monitoring from Nav2

* rename test

* fixing linting issues

* readd default

* linting

* Remove "wrong"/unnecessary dependency (#2700)

* Theta star planner fix (#2703)

* add test to check if the goal is unsafe with theta star planner

Signed-off-by: Daisuke Sato <[email protected]>

* check if a plan is generated (#2698)

Signed-off-by: Daisuke Sato <[email protected]>

* adding max analytic expansion length (#2697)

* adding max analytic expansion length

* fix tests and add dynamic parameter support

* [RPP] remove velocity scaling option (now required) and enable orientation sp projection times (#2701)

* remove velocity scaling option (now required) and enable orientation sp projection times

* get max radius

* Version bump up colcon extensions (#2706)

* Always initialize clearing endpoints in voxel layer (#2705)

* Prohibit of simultaneous usage of callbacks accessing to pf_ object (#2712)

* CostmapTopicCollisionChecker tf stamp fix (#2687)

* fixed tf lookup in costmap_topic_collision_checker unorientFootprint method

* minor cleanup

* uncrustified

* fixed stamps for tests which include CostmapTopicCollisionChecker

* updated CostmapTopicCollisionChecker construction for nav2_smoother

* cleaned up CostmapTopicCollisionChecker and FootprintSubscriber

* global_frame declaration returned to recovery_server as it is needed by
recovery plugins

* collision checker params updated

* Made transformFootprint same-input-output-safe

* uncrustified footprint.cpp

* CostmapTopicCollisionChecker enabled to fetch footprint only once per
multiple checks (same like costmap)

* CostmapTopicCollisionChecker: updated doxygen

* Update nav2_costmap_2d/include/nav2_costmap_2d/costmap_topic_collision_checker.hpp

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

* Update costmap_topic_collision_checker.hpp

Co-authored-by: afrixs <[email protected]>
Co-authored-by: Matej Vargovcik <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* adding dynamic parameters support for controller, planner, and waypoint servers (#2704)

* adding dynamic parameters support for controller, planner, and waypoint servers

* reset dynaic params on deactivate

* adding mutex to dynamic parameters support for 3 servers

* removing waypoint follower lock

* kill composition for 1 test

* adding test coverage for dynamic parameters in main task servers

* changing header for composed bringup

* adding backwards state update (#2717)

* Clean .gcda files for invalidated package tests (#2715)

* Clean .gcda files for invalidated package tests
"Each time you run the program, the execution counts are summed into any existing .gcda files, so be sure to remove any old files if you do not want their contents to be included."
https://llvm.org/docs/CommandGuide/llvm-cov.html

* Clean .gcno files for invalidated package builds
"At the time you compile the instrumented code, a .gcno data file will be generated for each object file."
https://llvm.org/docs/CommandGuide/llvm-cov.html

* Bump up cache for testing

* Revert .gcno cleaning
cmake should handle stale files

* Explicitly test uppassed tests as well
keeping TEST_FAILURES even if redudnet,
as it's still useful to echo for diagnostics

* Bump up cache for testing

* Cache test results
to avoid this error with colcon test-results:
Path 'test_results' does not exist

* Bump up cache for testing

* changing formulation of Hybrid-A* to be admissible and retune (#2713)

* adding shim rotation controller plugin (#2718)

* adding shim rotation controller plugin

* adding to metapackage

* adding max kinematic accel

* removing old note

* adding video to readme

* adding collision detector

* adding projection time for collision checking to rotation shim controller

* add another test case

* adding dynamic param tests for sim ahead time

* Update PULL_REQUEST_TEMPLATE.md

* Update mergify.yml

* Smac anomalies fix (#2724)

* fixed analytic expansion poses skipping and restoring of original pose
if neighbor not interesting

* Revert "fixed restoring of original pose"

This reverts commit a4f51ee28b03bf49f2cb63debfed49f7390fe6ef except of
analytic expansion skipping

* --

* removed API change, doing cleanup inside AnalyticExpansion

* smac analytic expansion: removed node skipping

* Update analytic_expansion.cpp

* fixed linting errors

* changed raw pointers to unique_ptrs

* Update analytic_expansion.cpp

* linter errors fix

Co-authored-by: Matej Vargovcik <[email protected]>

* Fixed min lookahead dist when moving backwards (#2726)

Co-authored-by: seasony-vp <[email protected]>

* adding reversing to smoothers (#2727)

* adding reversing to smoothers

* smoother working

* fixing CI

* update test

* Smoother feasbility (#2731)

* first go at a new smoother feasibility

* adding doxygen

* adding fix for reeds shepp mini expansion issue

* removing comments

* removing old line

* reordering declaration

* fixing last bug

* phew, that was a hard bug to fix...

* adding test coverage

* increase general test coverage (#2735)

* increase test coverage

* adding more coverage

* adding more coverage

* Apt upgrade with new pkgs (#2737)

* Apt upgrade with new pkgs
using --with-new-pkgs flag
to ensure all packages in CI image are updated
https://unix.stackexchange.com/a/241062/213124

* Pipe stdout from apt upgrade to log file
for better debuging and transparency

* adding dynamic parameter tests to navfn (#2743)

* RPP max lookahead collision detection time limited by lookahead point itself (#2741)

* adding RPP max lookahead collision detection time limited by lookahead point itself

* linting

* linting

* allowing rviz to visualize laser scans again with rolling binaries (#2745)

* increasing backup distance and speed (#2746)

* increasing backup distance and speed

* increasing speed

* Update colcon and install lld (#2761)

* Use LLD linker (#2734)

* Use LLD linker
https://lld.llvm.org

https://github.com/colcon/colcon-mixin-repository/pull/28

* Bump cache for testing

* docs: clarify that container images are for building, not deploying (#2763)

Signed-off-by: Adam Aposhian <[email protected]>

* Simplify coverage jobs for CI (#2762)

* Test coverage from release build

* Bump up cache for testing

* Merge test jobs
and name coverage uploads
using set RMW

* fix invert logic (#2772)

* Updated primitives file to latest version (#2774)

* Updated primitives file to latest version

Signed-off-by: Matthew Booker <[email protected]>

* Fixed tests for parsing and path checking

* Fix : misspelling in smac_planner's readme (#2778)

* Linting fix (#2779)

* Bugfix tf lookup of goal pose in nav2_controller (#2780)

Signed-off-by: Erik Örjehag <[email protected]>

* adding support for in-place rotations in state lattice (#2747)

* [costmap2d] make robot_base_frame param dynamic (#2782)

* make costmap2d robot_base_frame_param dynamic

* add test

* add rejecting logic and test

* support dynamic composed bringup (#2750)

* support dynamic composed bringup

Signed-off-by: zhenpeng ge <[email protected]>

* update

Signed-off-by: zhenpeng ge <[email protected]>

* update delcares in launch

Signed-off-by: zhenpeng ge <[email protected]>

* use component_container_isolated

Signed-off-by: zhenpeng ge <[email protected]>

* update README

Signed-off-by: zhenpeng ge <[email protected]>

* State Lattice Planner Control Set Generation (#2587)

* Initial version of motion primitive generation using sampling

Signed-off-by: Matthew Booker <[email protected]>

* Changed to lattice motion primitive generation

Signed-off-by: Matthew Booker <[email protected]>

* minor clarity fix for yaw equation

Signed-off-by: Matthew Booker <[email protected]>

* WIP - change of parameters + altering of step_distance

Signed-off-by: Matthew Booker <[email protected]>

* Implemented simplified method using arcs and geometry

Signed-off-by: Matthew Booker <[email protected]>

* Added testing for trajectory generator

Signed-off-by: Matthew Booker <[email protected]>

* Fixed several bugs and changed trajectory generator to use step distance

Signed-off-by: Matthew Booker <[email protected]>

* Added left turn parameter

Signed-off-by: Matthew Booker <[email protected]>

* Updated tester to match latest trajectory generator

Signed-off-by: Matthew Booker <[email protected]>

* Implemented lattice generator

Signed-off-by: Matthew Booker <[email protected]>

* Added edge case for parallel lines at 90 degrees

Signed-off-by: Matthew Booker <[email protected]>

* Added generation of paths in all quadrants

Signed-off-by: Matthew Booker <[email protected]>

* Update to parameter names and return values

Signed-off-by: Matthew Booker <[email protected]>

* Bug fixes

Signed-off-by: Matthew Booker <[email protected]>

* Added sample config file

Signed-off-by: Matthew Booker <[email protected]>

* Added script for generating and writing to file

Signed-off-by: Matthew Booker <[email protected]>

* Fixed end pose in list not being actual end point

Signed-off-by: Matthew Booker <[email protected]>

* Output now sorted by startAngle then endAngle

Signed-off-by: Matthew Booker <[email protected]>

* Start level calculated by flooring instead of rounding

Signed-off-by: Matthew Booker <[email protected]>

* Tidy code and added indentation to output file

Signed-off-by: Matthew Booker <[email protected]>

* Fixed start/end angle being set to 180 or -0

Signed-off-by: Matthew Booker <[email protected]>

* Added dataclasses instead of passing around tuples

Signed-off-by: Matthew Booker <[email protected]>

* Added yaws to path

Signed-off-by: Matthew Booker <[email protected]>

* Updated tests

Signed-off-by: Matthew Booker <[email protected]>

* Fixed bug in line path and added function comments

Signed-off-by: Matthew Booker <[email protected]>

* Updated to reflect changes in trajectory generator

Signed-off-by: Matthew Booker <[email protected]>

* Fixed missing negative sign for start angles

Signed-off-by: Matthew Booker <[email protected]>

* Fixed min trajectory length being calculated wrongly

Signed-off-by: Matthew Booker <[email protected]>

* Fixed negative zero appearing in poses

Signed-off-by: Matthew Booker <[email protected]>

* Set step distance to always be 10% of grid separation

Signed-off-by: Matthew Booker <[email protected]>

* Explicitly create yaws as float64 type

Signed-off-by: Matthew Booker <[email protected]>

* Updated tests to reflect step distance change

Signed-off-by: Matthew Booker <[email protected]>

* Added motion model handling

Signed-off-by: Matthew Booker <[email protected]>

* Changed dataclasses to be frozen

Signed-off-by: Matthew Booker <[email protected]>

* step distance must now be passed in to trajectory generator

Signed-off-by: Matthew Booker <[email protected]>

* Added trajectory generation for all quadrants

Signed-off-by: Matthew Booker <[email protected]>

* Added logging

Signed-off-by: Matthew Booker <[email protected]>

* Added arc length and total length computed properties to trajectoryParams

Signed-off-by: Matthew Booker <[email protected]>

* Fixed trajectory generation for all quadrants

Signed-off-by: Matthew Booker <[email protected]>

* Added a method to create params for trajectories with no arcs

Signed-off-by: Matthew Booker <[email protected]>

* Simplified lattice generation

Signed-off-by: Matthew Booker <[email protected]>

* Moved some functions to a separate file

Signed-off-by: Matthew Booker <[email protected]>

* Changed to use purely radians

Signed-off-by: Matthew Booker <[email protected]>

* Fixed -0.0 appearing again

Signed-off-by: Matthew Booker <[email protected]>

* Fixed angle difference calculation to account for turning direction

Signed-off-by: Matthew Booker <[email protected]>

* Yaws properly generate when crossing -180/180 boundary

Signed-off-by: Matthew Booker <[email protected]>

* Changed input/output parameters to be snake case

Signed-off-by: Matthew Booker <[email protected]>

* Moved yaw interpolation to helper

Signed-off-by: Matthew Booker <[email protected]>

* Fixed rounding in outputs

Signed-off-by: Matthew Booker <[email protected]>

* Fixed paths to be relative to file location

Signed-off-by: Matthew Booker <[email protected]>

* Added a trajectory visualizer for easier testing/debugging

Signed-off-by: Matthew Booker <[email protected]>

* Sorted primitives by angle starting at 0.0 and running CCW

Signed-off-by: Matthew Booker <[email protected]>

* Fixed path generation when distance was very small

Signed-off-by: Matthew Booker <[email protected]>

* Added R-Tree to speedup minimal path search

Signed-off-by: Matthew Booker <[email protected]>

* Added printing of time taken

Signed-off-by: Matthew Booker <[email protected]>

* Changed max length to stopping threshold

Signed-off-by: Matthew Booker <[email protected]>

* Use numpy functions instead of python functions for converting trajectories to list

Signed-off-by: Matthew Booker <[email protected]>

* Added a requirements.txt file

Signed-off-by: Matthew Booker <[email protected]>

* Fixed saving of visualizations to create the folder if it does not exist

Signed-off-by: Matthew Booker <[email protected]>

* Removed unused import

Signed-off-by: Matthew Booker <[email protected]>

* Generated a few samples for use

Signed-off-by: Matthew Booker <[email protected]>

* Removed spaces from folder names

Signed-off-by: Matthew Booker <[email protected]>

* Fixed interpolating of yaws to use vectorization

Signed-off-by: Matthew Booker <[email protected]>

* Fixed bug causing differing precision in angles when flipping

Signed-off-by: Matthew Booker <[email protected]>

* Plots now have same axis across trajectories

Signed-off-by: Matthew Booker <[email protected]>

* Replaced function with lambda

Signed-off-by: Matthew Booker <[email protected]>

* Added a README

Signed-off-by: Matthew Booker <[email protected]>

* Updated samples

Signed-off-by: Matthew Booker <[email protected]>

* Refactored to follow pycodestyle

Signed-off-by: Matthew Booker <[email protected]>

* Commented code and adjusted to match pycodestyle

Signed-off-by: Matthew Booker <[email protected]>

* Commented code and adjusted to match pycodestyle

Signed-off-by: Matthew Booker <[email protected]>

* Moved MotionModel class into LatticeGenerator

Signed-off-by: Matthew Booker <[email protected]>

* Changed start/end angle in output to be index of angle in heading_angles

Signed-off-by: Matthew Booker <[email protected]>

* Sample primitives now only contain 5cm x [0.5m, 1m] x [ackermann, diff,
omni]

Signed-off-by: Matthew Booker <[email protected]>

* Added config file parsing

Signed-off-by: Matthew Booker <[email protected]>

* Updated README to include file structure details

Signed-off-by: Matthew Booker <[email protected]>

* Renamed level to wavefront for better clarity

Signed-off-by: Matthew Booker <[email protected]>

* Added Apache 2.0 License

Signed-off-by: Matthew Booker <[email protected]>

* Changed how paths are passed in and updated the output file

Signed-off-by: Matthew Booker <[email protected]>

* Updated sample primitives and added visualizations

Signed-off-by: Matthew Booker <[email protected]>

* Added rotation matrix helper function

Signed-off-by: Matthew Booker <[email protected]>

* Added additional helper functions

Signed-off-by: Matthew Booker <[email protected]>

* Fixed path spacing issues

Signed-off-by: Matthew Booker <[email protected]>

* Changed member variables of Parameter dataclass

Signed-off-by: Matthew Booker <[email protected]>

* Changed how path spacing is handled

Signed-off-by: Matthew Booker <[email protected]>

* Updated docstrings and type annotations

Signed-off-by: Matthew Booker <[email protected]>

* Added printing of distances between points for trajectory visualizer

Signed-off-by: Matthew Booker <[email protected]>

* Fixed bug in omni and diff model generation

Signed-off-by: Matthew Booker <[email protected]>

* Regenerated all sample files using latest version

Signed-off-by: Matthew Booker <[email protected]>

* Added more comments for better clarity

Signed-off-by: Matthew Booker <[email protected]>

* Updated readme for better clarity

Signed-off-by: Matthew Booker <[email protected]>

* Added recommended values to parameters

Signed-off-by: Matthew Booker <[email protected]>

* Refactored TrajectoryPath and added docstrings for classes

Signed-off-by: Matthew Booker <[email protected]>

* Added comments for purpose of script

Signed-off-by: Matthew Booker <[email protected]>

* Added docstring to classes

Signed-off-by: Matthew Booker <[email protected]>

* Removed leftover print statement

Signed-off-by: Matthew Booker <[email protected]>

* Moved version constant to separate file

Signed-off-by: Matthew Booker <[email protected]>

* Fixed linting errors

Signed-off-by: Matthew Booker <[email protected]>

* Removed backslashes in docstrings and made summaries one-liners

Signed-off-by: Matthew Booker <[email protected]>

* Smac planner admissible obstacle heuristic (#2765)

* added obstacle_heuristic_admissible, change_reverse_penalty,
max_analytic_expansion_angle_range,
max_analytic_expansion_cost_subelevation and max_analytic_expansion_length options

* a_star test build fixed

* tests partially fixed

* --

* tests fixed

* obstacle heuristic improved

* removed max_analytic_expansion_length

* returned heuristic costmap downsampling

* cleanup before feature separation

* change_reverse_penalty feature separation

* analytic_expansion_constraints feature separation

* smac smoother bypass separation

* smac planner debug separation

* uncrustified smac planner changes

* improved smac admissible heuristic code readability

* fixed cleanup errors

* smac planner: added retrospective_penalty for speedup

* smac retrospective penalty: fixed errors, adjusted value in readme

* fixed doxygen, added new params to tests

* fixed smac tests

* Update node_hybrid.cpp

* removed inadmissible heuristic computation, updated names + signedness
to match previous implementation

* Smac: updated README.md

* Smac planner: setting retrospective_penalty default to 0.025, updating
readme and costmap_downsampler code styling

* Smac: fixed out-of-map cell obstacle heuristic crash, updated tests

* Smac: fixed merge errors and test values

* Smac: reorganized obstacle heuristic method code

* Smac: removed redundant check

* Update nav2_smac_planner/src/smac_planner_hybrid.cpp

Co-authored-by: afrixs <[email protected]>
Co-authored-by: Matej Vargovcik <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* Updating smoother for unknown space (#2791)

* adding an abstract BTNode for action cancellation (#2787)

* adding an abstract BT for action cancellation

* review update and adding test

* adding controller cancel BT Node

* Fixing the copyrights

* review updates

* satisfying lint

* adding the bt to the defaults

* update

* Cleaned up version of is path valid (#2591)

* Working replanning if path is vaild, however there is a bug with new goal points

* Completed tested of path replanning

* Delete uncrustify.cfg

* Clean up for code review

* steady

* small code review changes

* listen to server_timeout in input port

* Lint issues

* reverted file for navigate to pose

* lint fixes

* added global update condition

* headless

* revert default bt

* Add image of new bt tree

* circle ci and comments

* add test for globally updated goal condition

* added  plath replanning only if path is invalid to navigate to pose

* Added nodes to nav2_tree_nodes

* cleanup BT tree for invalid path

* code fixeds

* lint fixes

* added default timeout

* lint fix

* server timeout fix

* removed images of new BTs

* added rate controller

* lint fix

* Moved server timeout to constructor

* fixed xml lint error

* fixed test for is path valid

* new bt image for reference

* remove reference

* Feature to call controller action server to follow path (#2789)

* Added call to controller action server with a path to follow
++ Added a new function  in robot_navigator,py
++ Added a launch script to test  function
++ Updated setup.py to include demo_follow_path.py

* Code refactoring

* Code refactoring

* Code refactoring for consistency

* Updated README.md

* Resolved executable conflict in setup.py for example_follow_path.py

* Code refactoring with  ament_flake8

* BT nodes xml naming fix (#2805)

* Add recoveries to simple commander (#2792)

* fix Typo

* add recoveries

* add docs

* added demo using backup and spin

* rename isNavigationComplete to isTaskComplete

* rename cancelNav to cancelTask

* add prints

* fix premature exit

* rename NavResult to TaskResult

* fix readme order

* fix import order

* renaming

* renaming

* added planner_id (#2806)

* Fixing the issue #2781: raytraceLine with same start and end point (#2784)

* Fixing the issue #2781: raytraceLine with same start and end point no longer causes segmentation fault

* Some whitespace modifications to make the code pass release_test

* Add testcase for raytraceLine the same point

Co-authored-by: Alexey Merzlyakov <[email protected]>

* Add optional node names to wait (#2811)

* add option to specify navigator and localizer to wait for

* add docs for waituntilNav2Active

* wait for pose only for amcl

* revert order

* Drop unneeded dependency on python-enum34 (#2819)

The enum module was added in PEP 435 and is present in Python versions
3.4 and newer, which includes all currently supported Python versions.

* remove resizing on update message callback (#2818)

* smoother fix (#2822)

* Dynamic parameter setting of costmap layers (inflation/static/voxel) (#2760)

* added dynamic params to inflation layer

* Fixed codestyle divergence

* Added test for inflation param setting

* Added dynamic parameter setting to voxel layer

* Fixed code styling

* Added test for parameter setting of voxel layer

* Added dynamic parameter setting for static layer

* Added test for dynamic param setting of static layer

* turtlesim3 simulation testing bugfixes

* Imported some after param change function calls from ROS1 for all the layers

* Updated changes to the main branch

* Review changes by Alexey

* Review comments by Alexey 2

* Fixed codestyle divergence

* Removed blank line

* Review comments by Alexey 3

* Removed blank lineS

* Review change by Steven

* restrict test_msgs to test_dependency (#2827)

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

* remove unused odometry smoother in bt navigator (#2829)

* remove unused odometry smoother in bt navigator

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

* reorganize bt navigator to shared odom_smoother object with servers

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

* fix: modify build failure of nav2 bt navigator (#2836)

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

* Add all action options (#2834)

* added options

* update docs

* edge fix (#2840)

* edge fix

* code review

* Launch single (#2837)

* found error

* complete test setup

* updated metrics

* reverted planner server

* revert launch changes

* remove edits

* reverted nav2_bringup

* revet robot navigator

* add spaces

* removed map

* linting fix

* removed package, moved valuable stuff to tools

* addede more planners

* planner benchmarking

* adding stable dynamic reconfigure behavior (#2843)

* Update RPP readme

* Adding theta* to the main packages list

* Ci focal rolling (#2851)

* use rolling-ros-base-focal

* hotfix: remove rosdep update from ci

* Fix large angle changes in lattice primitive generator (#2831)

* Changed normalize_angle to exclude -pi and include pi

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

* Run normalize_angle on yaws to fix angle changes

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

* Added testing for the Lattice Generator

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

* Fixed linting errors

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

* Changed normalize_angle to exclude -pi and include pi

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

* Run normalize_angle on yaws to fix angle changes

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

* Added testing for the Lattice Generator

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

* Fixed linting errors

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

* Updated sample primitive files

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

* Removed default_model.json file (duplicate of sample primitives)

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

* Fixed issue caused by merge

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

* Replaced default primitive files

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

* Removed whitespace in folder names

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

* Moved angle normalization to occur before output instead of during generation

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

* Adjusted angle normalization to output in the range of [0, 2pi)

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

* Updated primitive files with latest changes

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

* Fixed normalize_angle docstring

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

* Fix: bt_navigator crashes on lc transitions (#2848)

* fix empty address access on halt all actions

* fix unsafe declaration of parameters

* restore odom smoother

* fix styling issues

* add missing semicolumn

* fix-collision checker must capture lethal before unknow (#2854)

* Bound closest pose by costmap and turnaround point (#2812)

* created integrated distance util

* chng transform begin , end and always limit lp pt

* chg trnsfm begin end and use euclidean distance

* linting fix

* linting fix

* limit trnsfm to cusp

* remove print

* linting fix

* lint fix

* hypot

* use direction change as upper bound for closest pose

* bound closest waypoint by direction change

* use max_transform_dist for closest_pose_upper_bound

* remove first_element_beyond optimization todo

* added path_utils for test path generation

* initial test for path_utils

* added full failing test for path_utils

* fixed path_utils segfault

* properly initialize straight transform

* fixed right turn infinite loop

* fixed path_utils transforms for half-turns

* all path_utils tests passing

* added half turn test for path_utils

* remove unused dependencies from test_path_utils

* move path_utils classes into path_building_blocks namespace

* use hypot for euclidean_distance

* rename findDirectionChange to findCusp

* use integrated distance for lookahead distance

* Revert "use integrated distance for lookahead distance"

This reverts commit 6e4c6cd3a795faf29f977df7316b5d58d9c1f135.

* parameterize transformation_begin bound

* change default to a regular constant

* use std::hypot for x, y, z

* initial failing test for transformGlobalPlan

* refactor transform global plan into separate test fixture

* make TransformGlobalPlan test fixture, and fix transforms

* no_pruning_on_large_costmap test passing

* added another transformGlobalPlan test

* added a test for all poses outside of costmap

* added good shortcut test for transformGlobalPlan

* added more tests for rpp costmap pruning

* cpplint

* remove unused rclcpp::init and rclcpp::shutdown

* change default max_distance_between_iterations to max_costmap_extent

* rename max_distance_between_iterations to max_robot_pose_search_dist

* increase default dwb prune distance

* add initial docs for max_robot_pose_search_dist to README

* add note about when to set max_robot_pose_search_dist

* rename first_element_beyond to first_after_integrated_distance

* renamed findCusp to findVelocitySignChange

* move path_utils to RPP tests

* only check velocity sign change when reversing is enabled

* do not check cusp for dwb transformed plan end

Co-authored-by: sathak93 <[email protected]>
Co-authored-by: Adam Aposhian <[email protected]>

* Apply raytraceLine 3D fixes to its 2D version (#2857)

(back-port of #2460 and #2784)

* adding Bt to cancel wait, spin and backup (#2856)

* adding Bt to cancel wait

* Adding cancel for spining recovery

* adding BT for cancelling the backup behavior

* adding cancel recoveries to param files for wider test coverage

* updating BT's XML

* updating XML nodes

* Fix cpplint include order errors (#2860)

* fix nav2_smac_planner cpplint

* fix dwb_core cpplint

* fix nav2_map_server cpplint

* fix nav2_waypoint_follower include order

* fix nav_2d_utils include order

* Linter fixes (#2861)

* satisfying uncrustify

* cpplint fixes

* Additional revision for costmap_bresenham_2d test (#2862)

* Removing old unused function and comment (#2863)

* fix core linting errors (#2864)

* fix core linting

* fix smac tests

* fix filepath

* fix angle normalization

* fix smac testes

* finish lint

* euclidean distance: by default use 2d mode (#2865)

Signed-off-by: Vinny Ruia <[email protected]>

* add the missing ports and description for the XML nodes (#2866)

* add the missing ports and description

* update

* update

* Fixed first_map_only parameter issue (#2870)

* Fixed first_map_only parameter issue

Signed-off-by: Harshal Deshpande <[email protected]>

* Adressed comments on PR

Signed-off-by: Harshal Deshpande <[email protected]>

* Fixed linting error

Signed-off-by: Harshal Deshpande <[email protected]>

* Mixed replan (#2841)

* working global time expired node

* test for global_time_expired_condition

* revert navigate to pose

* added '

* added space

* fix

* code review

* added 15 sec replanning time

* new bt

* revert bt

* fix

* reset timer when path is updated

* name change and fixes, it works!

* completed tests

* revert

* code review

* code review

* replanning time adjustment, rename

* removed commented code

* test fix

* remove comment

* Adding a new BT node Is_path_longer_on_approach (#2802)

* adding behavior and updating BT tree

* update BT

* updating copyrights

* fixing wrong test fixture

* review update

* update comments

* review update

* review update after testing

* Update na…
savalena pushed a commit to savalena/navigation2 that referenced this pull request Jul 5, 2024
* removing live groot monitoring from Nav2

* rename test

* fixing linting issues

* readd default

* linting
ajtudela added a commit to grupo-avispa/navigation2 that referenced this pull request Feb 25, 2025
ajtudela added a commit to grupo-avispa/navigation2 that referenced this pull request Mar 5, 2025
ajtudela added a commit to grupo-avispa/navigation2 that referenced this pull request Mar 5, 2025
ajtudela added a commit to grupo-avispa/navigation2 that referenced this pull request Mar 11, 2025
ajtudela added a commit to grupo-avispa/navigation2 that referenced this pull request Mar 25, 2025
ajtudela added a commit to grupo-avispa/navigation2 that referenced this pull request Apr 3, 2025
@RasmusLar RasmusLar mentioned this pull request Apr 7, 2025
7 tasks
ajtudela added a commit to grupo-avispa/navigation2 that referenced this pull request Apr 8, 2025
ajtudela added a commit to grupo-avispa/navigation2 that referenced this pull request Apr 10, 2025
SteveMacenski pushed a commit that referenced this pull request Apr 10, 2025
* Revert removing live groot monitoring from Nav2 (#2696)

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

* Update to Groot2

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

* Added JSON conversions

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

* Fix rebase

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

* Update to nav_msgs::Goals

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

* Added nav_msgs to json utils

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

* Add register to types

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

* Fix null-dereference

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

* Added Json test

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

* Fix some tests

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

* Fix flake

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

* Update package dependency

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

* Minor fixes

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

* Fix test

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

* Rename groot_publisher_port parameter to groot_server_port

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

* Minor  fix in tst

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

* Added JSON for waypoint_status

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

---------

Signed-off-by: Alberto Tudela <[email protected]>
SteveMacenski added a commit that referenced this pull request Apr 28, 2025
* Pre-Commit (#4915)

* Add pre-commit

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

* Add codespell workflow

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

* Codespell write_changes=false. As otherwise CI does not fail.

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

* Configure isort

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

* add precommit

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

* Introducing some issues.

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

* Revert "Introducing some issues."

This reverts commit 5377b65.

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

* Removing pre-commit workflow.

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

* Fix formatting error

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

* Merge remote-tracking branch 'origin/main' into precommit

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

* Change v31 to v32

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

* Revert "Merge remote-tracking branch 'origin/main' into precommit"

This reverts commit 8a7ca39.

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

* Rm submodule

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

* pre-commit run --all after merge

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

---------

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

* Fix path comparison to avoid unnecessary updates (#5009)

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

* nav2_rviz_plugins: Don't use non-existent slot (#5016)

The definition of the slot was removed in commit
e6f500e ("nav2_rviz_plugins: Remove slots without
implementation (#4974)", 2025-03-10), because it had no
implementation. But we forgot to remove the reference to this slot,
because the compiler cannot detect it.

We remove the reference now. Without this, rviz shows warnings like:

    QObject::connect: No such slot nav2_rviz_plugins::CostmapCostTool::updateAutoDeactivate()
    QObject::connect:  (sender name:   'Single click')

Signed-off-by: Michal Sojka <[email protected]>

* * Parametrize collision checking in nav2_graceful_controller (#5006)

* * Parametrize collision checking in nav2_graceful_controller

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

* * Fix linting errors

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

* * Address PR comments
* Add parameter to dynamic reconfigure

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

* * Add test for the use_collision_detection parameter

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

---------

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

* Update smac planner types (#4927)

* Update smac planner types

Signed-off-by: Michael Carlstrom <[email protected]>

* Test ament_mypy

Signed-off-by: Michael Carlstrom <[email protected]>

* Add packages

Signed-off-by: Michael Carlstrom <[email protected]>

* Fix arg name

Signed-off-by: Michael Carlstrom <[email protected]>

* Add **

Signed-off-by: Michael Carlstrom <[email protected]>

* Specific package

Signed-off-by: Michael Carlstrom <[email protected]>

* re-run ci

Signed-off-by: Michael Carlstrom <[email protected]>

* re-run ci

Signed-off-by: Michael Carlstrom <[email protected]>

---------

Signed-off-by: Michael Carlstrom <[email protected]>

* Declare_parameter_if_not_declared in docking navigator (#5023)

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

* Fix naming of launch file

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

* Fixed naming conventions of launch file

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

* navfn : fix performance issue (#4945)

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

* Configured mypy strict for nav2_smac_planner (#5022)

* Configured mypy strict on nav2_smac_planner.

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

* Modify workflow to contain mypy configuration.

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

* Added dependency for type support

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

---------

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

* Mypy nav2 common (#5031)

* Configured mypy for nav2_common

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

* Added nav2_common to the workflow.

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

* Removed all instances of Any.

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

* Fixed unsafe fixes using ruff.

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

---------

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

* Clear costmap if reset distance exceeds costmap bounds. (#5010)

* Migrate costmap bound check to clearArea for STVL override

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

* Added unbounded map to world function.

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

* Added test for mapToWorldNoBounds

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

---------

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

* Add near collision cost and warnings for misaligned parameter settings in MPPI critics (#4996)

* Add warning when settings not aligned; Add tunable option for near collision

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

* Linting

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

* Add more information for warning

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

* Add test for coverage

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

* Throw controller exception instead of invalid argument

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

---------

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

* Added pre-commit with ament ignores to the workflow. (#5029)

* Added pre-commit with ament ignores to the workflow.

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

* Removed codespell from workflow and enabled write changes in pre-commit.

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

* Update pull request template with a testing description section.

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

---------

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

* feat(nav2_rotation_shim_controller): add use_path_orientations (#5034)

* feat(nav2_rotation_shim_controller): add use_path_orientations

Signed-off-by: Kemal Bektas <[email protected]>

* Update nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp

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

---------

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

* Mypy nav2 bringup (#5040)

* Configured nav2_bringup to be compatible with mypy.

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

* Added nav2_bringup to the linting workflow.

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

---------

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

* Add service introspection (#4955)

* Add service introspection for client and server side, more tests to go

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

* Add test for service server, fix repeat declaration

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

* Fix cpplint

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

* Add test for coverage

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

* Declare and set the parameter in service client and server class

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

* Add typedef; Fix costmap cost tool and bt service

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

* Rebase; Add tests for coverage

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

* Fix costmap cost tool; Typedef

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

* Cleanup

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

* Add spin thread

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

* Add spin

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

* Change spin thread to internal executor

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

* Use rclcpp spin when no internal executor

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

* Update nav2_util/include/nav2_util/service_client.hpp

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

* Update nav2_util/include/nav2_util/service_client.hpp

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

* Update nav2_util/include/nav2_util/service_client.hpp

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

* Update nav2_util/include/nav2_util/service_client.hpp

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

* Refactor

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

* Update nav2_util/include/nav2_util/service_client.hpp

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

---------

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

* Mypy nav2_collision_monitor (#5043)

* Configured nav2_collision_monitor to use mypy strict.

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

* Added nav2_collision_monitor to the workflow.

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

---------

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

* Mypy nav2 costmap 2d (#5044)

* Configured mypy to run on the costmap_2d package.

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

* Added mypy_nav2_costmap_2d to the workflow.

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

---------

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

* Halt recovery action when main action succeeds to reset status (#5027)

* Halt recovery action when main action succeeds to reset status

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

* Update nav2_behavior_tree/plugins/control/recovery_node.cpp

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

---------

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

* Mypy opennav_docking (#5047)

* Define attributes for nav2_msgs.

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

* Configured opennav_docking to use strict mypy.

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

* Added opennav_docking to the mypy linting workflow.

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

---------

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

* Remove unused code in BT utils (#5048)

* Clean set port

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

* Remove set

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

---------

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

* Mypy nav2 lifecycle manager (#5051)

* Configured nav2_lifecycle_manager to be compatible with mypy

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

* Added nav2_lifecycle_manager to the workflow.

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

---------

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

* fix initializing in drive on heading action node (#5053)

Signed-off-by: Johannes Plapp <[email protected]>

* Mypy nav2 loopback sim (#5052)

* Configured nav2_loopback_sim to be compatible with mypy.

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

* Added nav2_loopback_sim to the workflow.

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

* Separated packages from list for mypy workflow.

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

---------

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

* Fix mppi bidirectional settings (#4954)

* Add constraint; fix settings

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

* Add lower and upper bound

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

* Update tests

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

* Update nav2_mppi_controller/include/nav2_mppi_controller/motion_models.hpp

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

* Update nav2_mppi_controller/include/nav2_mppi_controller/motion_models.hpp

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

* Update nav2_mppi_controller/include/nav2_mppi_controller/motion_models.hpp

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

* Update nav2_mppi_controller/include/nav2_mppi_controller/motion_models.hpp

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

---------

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

* Mypy nav2 map server (#5058)

* Configured nav2_map_server to be mypy compliant.

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

* Added nav2_map_server to the mypy workflow.

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

---------

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

* Publishing a full time-series MPPI trajectory if desirable (#5057)

* Publishing a full MPPI trajectory if desirable

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

* only create publisher when needed

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

* adjust topics

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

* Moving for lint

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

* updating topics in tests

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

---------

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

* Add double spin_some in some BT nodes (#5055)

* Add a double spin

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

* Add comment

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

* Move spin to constructor

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

---------

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

* Remove duplicate test (#5062)

There remained a duplicate test of test_system_launch after Groot
monitoring was removed

Signed-off-by: Rasmus Larsson <[email protected]>

* Remove docking absolute topic namespaces (#5068)

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

* Mypy nav2 simple commander (#5059)

* Added most nav2_simple_commander files that can be trivially converted to be mypy compatible.

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

* Modified edge cases and types for robot_navigator to pass mypy checks.

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

* Added nav2_simple_commander to the linting workflow.

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

* Added logs and ignored type errors due to spins w/o timeout.

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

---------

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

* Make NavigateThroughPoses navigator report waypoint statuses information. (fix #4846) (#4994)

* Add WaypointStatus message type & Remove MissedWaypoint message type

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

* Add waypoint_statuses records in RemoveInCollisionGoals/RemovePassedGoals actions

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

* Add validation tests

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

* Make NavigateThroughPoses navigator report waypoint statuses information

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

* Make WaypointFollower use WaypointStatus message type in action result

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

* Split MISSED status into SKIPPED & FAILED

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

* fix edge case handle in RemoveInCollision/RemovePassed BT actions

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

* Add validation test cases for RemoveInCollision&RemovePassed BT actions

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

* Update RemovePassedGoals/RemoveInCollisionGoals node in Groot XML

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

---------

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

* Enable Groot2 monitoring (#5065)

* Revert removing live groot monitoring from Nav2 (#2696)

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

* Update to Groot2

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

* Added JSON conversions

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

* Fix rebase

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

* Update to nav_msgs::Goals

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

* Added nav_msgs to json utils

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

* Add register to types

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

* Fix null-dereference

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

* Added Json test

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

* Fix some tests

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

* Fix flake

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

* Update package dependency

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

* Minor fixes

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

* Fix test

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

* Rename groot_publisher_port parameter to groot_server_port

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

* Minor  fix in tst

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

* Added JSON for waypoint_status

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

---------

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

* Fix incorrect world <-> map coordinates conversions (#5049)

* Fix incorrect world <-> map coordinates conversions

The conversion between world and map continuous (!) coordinates do not
require a +/-0.5. This offset is only required when converting discrete
map cell indexes to the coordinates of its center.

Signed-off-by: Dylan De Coeyer <[email protected]>

* nav2_smac_planner: fix smoother test when path is in collision

The added pose was indeed invalid, but the it was ignored by the
smoother, since considered as a cusp.

Instead, let's make the end of the plan invalid as it won't be ignored.
Also, let's duplicate the last pose to make the orientation estimation
fail, rather than adding a new arbitrary pose.

Signed-off-by: Dylan De Coeyer <[email protected]>

---------

Signed-off-by: Dylan De Coeyer <[email protected]>

* [AMCL] 50% initialisation (and reset) speed improvement  (#4941)

* index lookup and comparator optimisation

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

* lint

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

---------

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

* Add note to Asynchronous nodes (#5035)

* Add warning to some of the nodes

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

* remove unused includes

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

* Add warning to remaining nodes using isStatusActive to initialize

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

* Change to note & update phrsing

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

* replace reset by re-initialize

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

---------

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

* [AMCL] Rebuild cspace map only when needed (#5076)

* for LikelihoodFieldModel

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

* for LikelihoodFieldModelProb

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

* typo

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

* init max_occ_dist in map.c and remove unnecessary condition

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

---------

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

* Consistency in Groot 2 (#5078)

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

* Remove duplicate code (#5080)

* Remove duplicate code

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

* Add twist validation for controller server

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

---------

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

* Added waypointstatus to bt_utils (#5077)

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

* Lock costmap in getCostsCallback (#5075)

* Add IsStoppedBTNode

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

* add topic name + reformat

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

* fix comment

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

* fix abs

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

* remove log

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

* add getter functions for raw twist

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

* remove unused code

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

* use odomsmoother

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

* fix formatting

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

* update groot

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

* Add test

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

* reset at success

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

* FIX velocity_threshold_

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

* Fix stopped Node

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

* Add tests  to odometry_utils

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

* fix linting

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

* lock costmap

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

* improvement

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

* remove spacing

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

* remove unlock

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

---------

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

* Mypy nav2 system tests (#5083)

* Configured nodes of nav2_system_tests to be mypy compliant.

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

* Configured launch files of nav2_system_tests to be mypy compliant.

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

* Added nav2_system_tests to the linting workflow.

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

---------

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

* Configure the entire nav2 stack with mypy (#5084)

* Configured tools to be mypy compliant.

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

* Added mypy as a pre-commit hook.

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

* Simplified workflow by including all packages with mypy.

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

---------

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

* 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

* Docking backwards as plugin param (#5079)

* Replace dock_backwards_ param with dock plugin function

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

* Deprecated dock_backwards warning

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

* Convert dockDirection from bool to enum

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

* Minor fixes

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

* Improve deprecated param handling

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

* Set default to forward

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

* Added tests

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

* Update nav2_docking/README.md

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

* Upper and others

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

* Revert declare_parameters_from_overrides

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

* Added throw on configure plugin

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

* Remove node_utils

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

---------

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

* 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]>

* Fix CI builds (#5104)

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

* Increase docking coverage && fix backward docking (#5097)

* Add dock_database tests

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

* Add utils test

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

* Improve filter tests

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

* Added simple charging tests

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

* Improve comments

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

* Fix backward and redo main test

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

* Change test period to reduce test time

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

* Revert "Change test period to reduce test time"

This reverts commit ef1555e.

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

* Delete print pose

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

---------

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

* Run ament_uncrustify to remove linting issues

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

---------

Signed-off-by: Nils-ChristianIseke <[email protected]>
Signed-off-by: Tatsuro Sakaguchi <[email protected]>
Signed-off-by: Michal Sojka <[email protected]>
Signed-off-by: suchetanrs <[email protected]>
Signed-off-by: Michael Carlstrom <[email protected]>
Signed-off-by: Alberto Tudela <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Signed-off-by: Yancey <[email protected]>
Signed-off-by: Leander Stephen D'Souza <[email protected]>
Signed-off-by: mini-1235 <[email protected]>
Signed-off-by: Kemal Bektas <[email protected]>
Signed-off-by: Johannes Plapp <[email protected]>
Signed-off-by: Rasmus Larsson <[email protected]>
Signed-off-by: zz990099 <[email protected]>
Signed-off-by: Dylan De Coeyer <[email protected]>
Signed-off-by: Guillaume Doisy <[email protected]>
Signed-off-by: Adi Vardi <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Vignesh T <[email protected]>
Signed-off-by: coderwyvern <[email protected]>
Co-authored-by: Nils-Christian Iseke <[email protected]>
Co-authored-by: Tatsuro Sakaguchi <[email protected]>
Co-authored-by: Michal Sojka <[email protected]>
Co-authored-by: suchetanrs <[email protected]>
Co-authored-by: Michael Carlstrom <[email protected]>
Co-authored-by: Alberto Tudela <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>
Co-authored-by: Yancey <[email protected]>
Co-authored-by: Leander Stephen D'Souza <[email protected]>
Co-authored-by: mini-1235 <[email protected]>
Co-authored-by: Kemal Bektas <[email protected]>
Co-authored-by: Kemal Bektas <[email protected]>
Co-authored-by: Johannes Plapp <[email protected]>
Co-authored-by: RasmusLar <[email protected]>
Co-authored-by: zz99 <[email protected]>
Co-authored-by: DylanDeCoeyer-Quimesis <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Adi Vardi <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: Sandeep Dutta <[email protected]>
Co-authored-by: Vignesh T <[email protected]>
stevedanomodolor pushed a commit to stevedanomodolor/navigation2 that referenced this pull request Apr 29, 2025
* Revert removing live groot monitoring from Nav2 (ros-navigation#2696)

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

* Update to Groot2

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

* Added JSON conversions

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

* Fix rebase

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

* Update to nav_msgs::Goals

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

* Added nav_msgs to json utils

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

* Add register to types

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

* Fix null-dereference

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

* Added Json test

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

* Fix some tests

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

* Fix flake

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

* Update package dependency

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

* Minor fixes

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

* Fix test

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

* Rename groot_publisher_port parameter to groot_server_port

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

* Minor  fix in tst

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

* Added JSON for waypoint_status

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

---------

Signed-off-by: Alberto Tudela <[email protected]>
Signed-off-by: stevedanomodolor <[email protected]>
SteveMacenski added a commit that referenced this pull request May 13, 2025
* Pre-Commit (#4915)

* Add pre-commit

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

* Add codespell workflow

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

* Codespell write_changes=false. As otherwise CI does not fail.

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

* Configure isort

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

* add precommit

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

* Introducing some issues.

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

* Revert "Introducing some issues."

This reverts commit 5377b656361ef220dce6d6af36013060798f06de.

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

* Removing pre-commit workflow.

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

* Fix formatting error

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

* Merge remote-tracking branch 'origin/main' into precommit

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

* Change v31 to v32

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

* Revert "Merge remote-tracking branch 'origin/main' into precommit"

This reverts commit 8a7ca3983a0b93ef5a94e9517e9598de96be2fe6.

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

* Rm submodule

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

* pre-commit run --all after merge

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

---------

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

* Fix path comparison to avoid unnecessary updates (#5009)

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

* nav2_rviz_plugins: Don't use non-existent slot (#5016)

The definition of the slot was removed in commit
e6f500e5 ("nav2_rviz_plugins: Remove slots without
implementation (#4974)", 2025-03-10), because it had no
implementation. But we forgot to remove the reference to this slot,
because the compiler cannot detect it.

We remove the reference now. Without this, rviz shows warnings like:

    QObject::connect: No such slot nav2_rviz_plugins::CostmapCostTool::updateAutoDeactivate()
    QObject::connect:  (sender name:   'Single click')

Signed-off-by: Michal Sojka <[email protected]>

* * Parametrize collision checking in nav2_graceful_controller (#5006)

* * Parametrize collision checking in nav2_graceful_controller

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

* * Fix linting errors

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

* * Address PR comments
* Add parameter to dynamic reconfigure

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

* * Add test for the use_collision_detection parameter

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

---------

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

* Update smac planner types (#4927)

* Update smac planner types

Signed-off-by: Michael Carlstrom <[email protected]>

* Test ament_mypy

Signed-off-by: Michael Carlstrom <[email protected]>

* Add packages

Signed-off-by: Michael Carlstrom <[email protected]>

* Fix arg name

Signed-off-by: Michael Carlstrom <[email protected]>

* Add **

Signed-off-by: Michael Carlstrom <[email protected]>

* Specific package

Signed-off-by: Michael Carlstrom <[email protected]>

* re-run ci

Signed-off-by: Michael Carlstrom <[email protected]>

* re-run ci

Signed-off-by: Michael Carlstrom <[email protected]>

---------

Signed-off-by: Michael Carlstrom <[email protected]>

* Declare_parameter_if_not_declared in docking navigator (#5023)

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

* Fix naming of launch file

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

* Fixed naming conventions of launch file

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

* navfn : fix performance issue (#4945)

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

* Configured mypy strict for nav2_smac_planner (#5022)

* Configured mypy strict on nav2_smac_planner.

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

* Modify workflow to contain mypy configuration.

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

* Added dependency for type support

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

---------

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

* Mypy nav2 common (#5031)

* Configured mypy for nav2_common

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

* Added nav2_common to the workflow.

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

* Removed all instances of Any.

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

* Fixed unsafe fixes using ruff.

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

---------

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

* Clear costmap if reset distance exceeds costmap bounds. (#5010)

* Migrate costmap bound check to clearArea for STVL override

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

* Added unbounded map to world function.

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

* Added test for mapToWorldNoBounds

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

---------

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

* Add near collision cost and warnings for misaligned parameter settings in MPPI critics (#4996)

* Add warning when settings not aligned; Add tunable option for near collision

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

* Linting

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

* Add more information for warning

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

* Add test for coverage

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

* Throw controller exception instead of invalid argument

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

---------

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

* Added pre-commit with ament ignores to the workflow. (#5029)

* Added pre-commit with ament ignores to the workflow.

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

* Removed codespell from workflow and enabled write changes in pre-commit.

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

* Update pull request template with a testing description section.

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

---------

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

* feat(nav2_rotation_shim_controller): add use_path_orientations (#5034)

* feat(nav2_rotation_shim_controller): add use_path_orientations

Signed-off-by: Kemal Bektas <[email protected]>

* Update nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp

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

---------

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

* Mypy nav2 bringup (#5040)

* Configured nav2_bringup to be compatible with mypy.

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

* Added nav2_bringup to the linting workflow.

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

---------

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

* Add service introspection (#4955)

* Add service introspection for client and server side, more tests to go

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

* Add test for service server, fix repeat declaration

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

* Fix cpplint

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

* Add test for coverage

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

* Declare and set the parameter in service client and server class

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

* Add typedef; Fix costmap cost tool and bt service

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

* Rebase; Add tests for coverage

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

* Fix costmap cost tool; Typedef

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

* Cleanup

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

* Add spin thread

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

* Add spin

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

* Change spin thread to internal executor

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

* Use rclcpp spin when no internal executor

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

* Update nav2_util/include/nav2_util/service_client.hpp

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

* Update nav2_util/include/nav2_util/service_client.hpp

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

* Update nav2_util/include/nav2_util/service_client.hpp

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

* Update nav2_util/include/nav2_util/service_client.hpp

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

* Refactor

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

* Update nav2_util/include/nav2_util/service_client.hpp

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

---------

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

* Mypy nav2_collision_monitor (#5043)

* Configured nav2_collision_monitor to use mypy strict.

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

* Added nav2_collision_monitor to the workflow.

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

---------

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

* Mypy nav2 costmap 2d (#5044)

* Configured mypy to run on the costmap_2d package.

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

* Added mypy_nav2_costmap_2d to the workflow.

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

---------

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

* Halt recovery action when main action succeeds to reset status (#5027)

* Halt recovery action when main action succeeds to reset status

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

* Update nav2_behavior_tree/plugins/control/recovery_node.cpp

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

---------

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

* Mypy opennav_docking (#5047)

* Define attributes for nav2_msgs.

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

* Configured opennav_docking to use strict mypy.

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

* Added opennav_docking to the mypy linting workflow.

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

---------

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

* Remove unused code in BT utils (#5048)

* Clean set port

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

* Remove set

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

---------

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

* Mypy nav2 lifecycle manager (#5051)

* Configured nav2_lifecycle_manager to be compatible with mypy

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

* Added nav2_lifecycle_manager to the workflow.

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

---------

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

* fix initializing in drive on heading action node (#5053)

Signed-off-by: Johannes Plapp <[email protected]>

* Mypy nav2 loopback sim (#5052)

* Configured nav2_loopback_sim to be compatible with mypy.

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

* Added nav2_loopback_sim to the workflow.

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

* Separated packages from list for mypy workflow.

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

---------

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

* Fix mppi bidirectional settings (#4954)

* Add constraint; fix settings

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

* Add lower and upper bound

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

* Update tests

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

* Update nav2_mppi_controller/include/nav2_mppi_controller/motion_models.hpp

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

* Update nav2_mppi_controller/include/nav2_mppi_controller/motion_models.hpp

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

* Update nav2_mppi_controller/include/nav2_mppi_controller/motion_models.hpp

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

* Update nav2_mppi_controller/include/nav2_mppi_controller/motion_models.hpp

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

---------

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

* Mypy nav2 map server (#5058)

* Configured nav2_map_server to be mypy compliant.

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

* Added nav2_map_server to the mypy workflow.

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

---------

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

* Publishing a full time-series MPPI trajectory if desirable (#5057)

* Publishing a full MPPI trajectory if desirable

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

* only create publisher when needed

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

* adjust topics

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

* Moving for lint

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

* updating topics in tests

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

---------

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

* Add double spin_some in some BT nodes (#5055)

* Add a double spin

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

* Add comment

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

* Move spin to constructor

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

---------

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

* Remove duplicate test (#5062)

There remained a duplicate test of test_system_launch after Groot
monitoring was removed

Signed-off-by: Rasmus Larsson <[email protected]>

* Remove docking absolute topic namespaces (#5068)

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

* Mypy nav2 simple commander (#5059)

* Added most nav2_simple_commander files that can be trivially converted to be mypy compatible.

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

* Modified edge cases and types for robot_navigator to pass mypy checks.

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

* Added nav2_simple_commander to the linting workflow.

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

* Added logs and ignored type errors due to spins w/o timeout.

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

---------

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

* Make NavigateThroughPoses navigator report waypoint statuses information. (fix #4846) (#4994)

* Add WaypointStatus message type & Remove MissedWaypoint message type

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

* Add waypoint_statuses records in RemoveInCollisionGoals/RemovePassedGoals actions

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

* Add validation tests

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

* Make NavigateThroughPoses navigator report waypoint statuses information

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

* Make WaypointFollower use WaypointStatus message type in action result

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

* Split MISSED status into SKIPPED & FAILED

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

* fix edge case handle in RemoveInCollision/RemovePassed BT actions

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

* Add validation test cases for RemoveInCollision&RemovePassed BT actions

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

* Update RemovePassedGoals/RemoveInCollisionGoals node in Groot XML

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

---------

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

* Enable Groot2 monitoring (#5065)

* Revert removing live groot monitoring from Nav2 (#2696)

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

* Update to Groot2

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

* Added JSON conversions

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

* Fix rebase

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

* Update to nav_msgs::Goals

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

* Added nav_msgs to json utils

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

* Add register to types

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

* Fix null-dereference

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

* Added Json test

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

* Fix some tests

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

* Fix flake

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

* Update package dependency

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

* Minor fixes

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

* Fix test

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

* Rename groot_publisher_port parameter to groot_server_port

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

* Minor  fix in tst

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

* Added JSON for waypoint_status

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

---------

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

* Fix incorrect world <-> map coordinates conversions (#5049)

* Fix incorrect world <-> map coordinates conversions

The conversion between world and map continuous (!) coordinates do not
require a +/-0.5. This offset is only required when converting discrete
map cell indexes to the coordinates of its center.

Signed-off-by: Dylan De Coeyer <[email protected]>

* nav2_smac_planner: fix smoother test when path is in collision

The added pose was indeed invalid, but the it was ignored by the
smoother, since considered as a cusp.

Instead, let's make the end of the plan invalid as it won't be ignored.
Also, let's duplicate the last pose to make the orientation estimation
fail, rather than adding a new arbitrary pose.

Signed-off-by: Dylan De Coeyer <[email protected]>

---------

Signed-off-by: Dylan De Coeyer <[email protected]>

* [AMCL] 50% initialisation (and reset) speed improvement  (#4941)

* index lookup and comparator optimisation

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

* lint

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

---------

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

* Add note to Asynchronous nodes (#5035)

* Add warning to some of the nodes

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

* remove unused includes

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

* Add warning to remaining nodes using isStatusActive to initialize

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

* Change to note & update phrsing

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

* replace reset by re-initialize

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

---------

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

* [AMCL] Rebuild cspace map only when needed (#5076)

* for LikelihoodFieldModel

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

* for LikelihoodFieldModelProb

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

* typo

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

* init max_occ_dist in map.c and remove unnecessary condition

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

---------

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

* Consistency in Groot 2 (#5078)

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

* Remove duplicate code (#5080)

* Remove duplicate code

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

* Add twist validation for controller server

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

---------

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

* Added waypointstatus to bt_utils (#5077)

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

* Lock costmap in getCostsCallback (#5075)

* Add IsStoppedBTNode

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

* add topic name + reformat

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

* fix comment

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

* fix abs

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

* remove log

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

* add getter functions for raw twist

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

* remove unused code

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

* use odomsmoother

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

* fix formatting

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

* update groot

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

* Add test

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

* reset at success

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

* FIX velocity_threshold_

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

* Fix stopped Node

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

* Add tests  to odometry_utils

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

* fix linting

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

* lock costmap

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

* improvement

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

* remove spacing

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

* remove unlock

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

---------

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

* Mypy nav2 system tests (#5083)

* Configured nodes of nav2_system_tests to be mypy compliant.

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

* Configured launch files of nav2_system_tests to be mypy compliant.

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

* Added nav2_system_tests to the linting workflow.

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

---------

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

* Configure the entire nav2 stack with mypy (#5084)

* Configured tools to be mypy compliant.

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

* Added mypy as a pre-commit hook.

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

* Simplified workflow by including all packages with mypy.

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

---------

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

* 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

* Docking backwards as plugin param (#5079)

* Replace dock_backwards_ param with dock plugin function

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

* Deprecated dock_backwards warning

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

* Convert dockDirection from bool to enum

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

* Minor fixes

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

* Improve deprecated param handling

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

* Set default to forward

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

* Added tests

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

* Update nav2_docking/README.md

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

* Upper and others

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

* Revert declare_parameters_from_overrides

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

* Added throw on configure plugin

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

* Remove node_utils

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

---------

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

* 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]>

* Fix CI builds (#5104)

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

* Increase docking coverage && fix backward docking (#5097)

* Add dock_database tests

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

* Add utils test

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

* Improve filter tests

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

* Added simple charging tests

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

* Improve comments

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

* Fix backward and redo main test

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

* Change test period to reduce test time

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

* Revert "Change test period to reduce test time"

This reverts commit ef1555ec43cb4849fd658c32377189cf414ff9b7.

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

* Delete print pose

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

---------

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

* Initialize dock backwards (#5114)

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

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

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

* Nav2 Route Server (#5056)

* skeleton of main server and visualization tools

* adding complete Kd-tree search for initial and goal node iDs for search

* initial planner complete

* added path converter

* fix conversion util

* adding change graph service

* added edge scoring to the search + pluginlib definitions + a plugin example instance

* moved to src directory

* linting

* contextual error codes + default bringup

* adding rviz default views of rgaph

* adding missing exception file

* fix segfault that was previously optimized out

* whoops, removing duplicate plugin registration

* remove nanoflann TODO

* adding 2 more edge plugins, use of closed edges in the API design, and added service to modify a set of closed edges being tracked

* fix indexing bug for certain request types

* adding costmap scoring route plugin

* readme todo list updates

* readme details

* adding unit test coverage

* add dynamic cost adjustment by application systems

* adding in operations API

* minor fixes

* add compute and track route action def

* initial prototype compiling and basic interface working for tracking action

* updates to TODO list

* state management

* remove divide by zero potential error

* added in working mostly  demog

* adding rerouting service and a bunch of new tests for operations

* adding new trigger event plugin + base class for service calls + test coverage to complete operations manager

* conventions

* adding initial (maybe working?) collision checker + added blocked ID propogation from operations to allow for rerouting with info from operations

* adding in 3 new algorithms: Time Scorer, Time Marker, and Semantic Scorer

* adding complete unit testing for collision monitor

* adding tests for the planner on a fully connected 4x4 graph

* adding rereouting with starting point to use for the initial condition when along route

* sharing common shared action server code in main server

* refactor, added goal intent extractor, updated necessary tests

* updating todo notes

* adding tests and functionoing goal intent extractor and pruning cost updates

* a little cleanup

* adding readme

* completing unit tests

* large reorg of information around the rerouting state information and output formats for practical use

* Nav2 route server parser (#3398)

* aws graph working

* graph parser first stage

* naming cleanup

* remove

* update graph file

* added fileExists to api

* moved filepath param

* vect to string

* parser cleanup

* debug log

* added tests for geojson graph parser

* added logging to parser

* cleanup

* catch exceptions in route service

* code review

* undo cmake

* added graph loader test

* undo cmake

* code review

* frame convesion support

* comments

* fix

* Parse edge and node metadata

* parse operations

* completed metadata parsing

* added recursion for parser

* code review

* undo cmake

* support vectors

* refactor tests

* fix

* general cleanup

* code review

* added timestamp

---------

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

* adding unit tests for complex handling of reentrant requests

* adding demos for python3 API

* adding conditions if graph is empty in routing request

* working MVP tracking demos working

* adding integration testing expanded TODO list before beta testers

* Example graph (#3438)

* added simple graph

* added metadata and operations to graph

* update

* add space

* added test for sample_graph

* added to readme

* testing system-wise, mostly working

* update remaining TODO list

* updates for pruning starting in rerouting

* adding a full roster of default plugins

* complete tested feature set

* adding configuration guide to readme

* adding plugins info

* testing collapse

* smaller titles

* adding becnhmarking script

* adding metrics to readme

* adding image for architecture

* resize

* resize

* adding design info

* new image

* turtlebot3 world graph (#3472)

* turtlebot3 world graph

* remove line

* add line back

* scripts for route (#3490)

* tmp push for moving computers

* Nav2 route server goal orientation scorer (#4866)

* added goal pose and bool to check for last edge for all scorers

Signed-off-by: Alexander Yuen <[email protected]>

* added goal_orientation scorer

Signed-off-by: Alexander Yuen <[email protected]>

* added test for GoalOrientationScorer

Signed-off-by: Alexander Yuen <[email protected]>

* changed goal pose to a const ref, and moved score to end as implicit return

Signed-off-by: Alexander Yuen <[email protected]>

* changed goal arguments to const ref

Signed-off-by: Alexander Yuen <[email protected]>

* using const ref for goal pose, rearranged total_score to match header

Signed-off-by: Alexander Yuen <[email protected]>

* linting on goal_orientation_scorer.hpp

Signed-off-by: Alexander Yuen <[email protected]>

* using M_PI as default threshold, fixed angle wrapping by using angles library, no longer modifying cost

Signed-off-by: Alexander Yuen <[email protected]>

* changed arguments to use const refs, changed argument order in score function to matach header

Signed-off-by: Alexander Yuen <[email protected]>

* changed calling of score to match argument sequence, changed GoalOrientaitonScorer to test the opposite direction and check the return value

Signed-off-by: Alexander Yuen <[email protected]>

* switched cost edge pairs to imply return of cost, default orientation as M_PI / 2.0

Signed-off-by: Alexander Yuen <[email protected]>

---------

Signed-off-by: Alexander Yuen <[email protected]>

* minor updates

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

* fix a few bugs, clarify a few things

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

* more validation and inline comments to help readers understand complex interactions

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

* CI turning over

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

* adding error_msg

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

* updated cmake style to be in line with repo

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

* Adding afew mores features from TODO list

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

* Nav2 route server start pose orientation scorer (#4950)

* adding flag to identify start node, passing tf_buffer to edge scorer

Signed-off-by: Alexander Yuen <[email protected]>

* passing tf to route planner

Signed-off-by: Alexander Yuen <[email protected]>

* added null buffer to tests

Signed-off-by: Alexander Yuen <[email protected]>

* added null buffer to planner configure in performance bench marking test

Signed-off-by: Alexander Yuen <[email protected]>

* changed arguments of all old edge scorers to also take tf_buffer

Signed-off-by: Alexander Yuen <[email protected]>

* changed configure to take tf_buffer, added bool to identify start_edge in score method for all existing edge scorers

Signed-off-by: Alexander Yuen <[email protected]>

* added start_pose_orientation_scorer to CMake

Signed-off-by: Alexander Yuen <[email protected]>

* added StartPoseOrientationScorer as and edge scroer

Signed-off-by: Alexander Yuen <[email protected]>

* added tf_buffer to constructor, added start edge bool on score method, added tf_buffer as a protected variable

Signed-off-by: Alexander Yuen <[email protected]>

* added tf_buffer to configure method, added start_id_ member variable, added isStart method to identify initial node for route_planner.hpp

Signed-off-by: Alexander Yuen <[email protected]>

* modified all configures to take a tf_buffer, modified all score functions to take a start edge bool, added test for start_pose_orientation_scorer

Signed-off-by: Alexander Yuen <[email protected]>

* adding start_pose_orientation_scorer.cpp

Signed-off-by: Alexander Yuen <[email protected]>

* edge scorer modified to take in tf_buffer and pass it to scorer plugins, bool for start edge also passed down to plugins

Signed-off-by: Alexander Yuen <[email protected]>

* removed redundant parameter declarations, changed robot frame to base frame, year bump

Signed-off-by: Alexander Yuen <[email protected]>

* changed robot frame to base frame, year bump on copy right

Signed-off-by: Alexander Yuen <[email protected]>

* removed unnecessary tf_buffer_ from edge_scorer

Signed-off-by: Alexander Yuen <[email protected]>

* added EdgeType enum class

Signed-off-by: Alexander Yuen <[email protected]>

* all edge scorer plugins changed to use EdgeType

Signed-off-by: Alexander Yuen <[email protected]>

* edge_scorer modified to use EdgeType enum class

Signed-off-by: Alexander Yuen <[email protected]>

* edge_cost_function base class modified to use EdgeType enum class

Signed-off-by: Alexander Yuen <[email protected]>

* modified tests for new scorer signature

Signed-off-by: Alexander Yuen <[email protected]>

* added method to classify edge type

Signed-off-by: Alexander Yuen <[email protected]>

* ament_cpplinting

Signed-off-by: Alexander Yuen <[email protected]>

* linting

Signed-off-by: Alexander Yuen <[email protected]>

* changed EdgeType to const ref

Signed-off-by: Alexander Yuen <[email protected]>

* added option to score orientations instead of outright rejecting start poses

Signed-off-by: Alexander Yuen <[email protected]>

* updated docstrings to have better description for goal pose and start pose orientation goal checker

Signed-off-by: Alexander Yuen <[email protected]>

* fixed merge conflict in goal_orientation_scorer.hpp

Signed-off-by: Alexander Yuen <[email protected]>

* fixed merge conflict in edge_cost_function.hpp

Signed-off-by: Alexander Yuen <[email protected]>

* removed TODO from costmap_scorer.cpp

Signed-off-by: Alexander Yuen <[email protected]>

* added getStart method to goal_intent_extract and start pose argument for findRoute

Signed-off-by: Alexander Yuen <[email protected]>

* added RouteData struct to types.hpp

Signed-off-by: Alexander Yuen <[email protected]>

* added start_pose to edge scorer hpp and cpp

Signed-off-by: Alexander Yuen <[email protected]>

* fixed type getStart return type in goal_intent_extractor.cpp

Signed-off-by: Alexander Yuen <[email protected]>

* added passing of start_pose down to scorer in route_planner

Signed-off-by: Alexander Yuen <[email protected]>

* added start pose to base edge cost function class

Signed-off-by: Alexander Yuen <[email protected]>

* underscore fix for goal_intent_extractor_

Signed-off-by: Alexander Yuen <[email protected]>

* changed signature of all edge cost functions to take start_pose

Signed-off-by: Alexander Yuen <[email protected]>

* populating RouteData and passing it into findRoute

Signed-off-by: Alexander Yuen <[email protected]>

* passing route_data down to getTraversalCost

Signed-off-by: Alexander Yuen <[email protected]>

* plugins modified to take in route_data, tests updated accordingly

Signed-off-by: Alexander Yuen <[email protected]>

* using route data for goal_orientation_scorer and start_pose_orientation_scorer, modified tests accordingly

Signed-off-by: Alexander Yuen <[email protected]>

* removed route frame, robot frame, and getRobotPose from start_pose_orientation_scorer

Signed-off-by: Alexander Yuen <[email protected]>

* removed used of stat_pose and goal_pose as it is replaced with route data

Signed-off-by: Alexander Yuen <[email protected]>

* added InvalidCriticUse exception to nav2_core, goal_orientation_scorer and start_pose_orientation_scorer throws this exception if route_data.use_poses is false, route_server catches this exception, added exception test in the edge scorer tester

Signed-off-by: Alexander Yuen <[email protected]>

* added INVALID_CRITIC_USE error code in route actions

Signed-off-by: Alexander Yuen <[email protected]>

* added orientation weighting for cost as an option instead of out right rejection

Signed-off-by: Alexander Yuen <[email protected]>

* updated docstring for goal orientation scorer

Signed-off-by: Alexander Yuen <[email protected]>

* renamed Critic to EdgeScorer

Signed-off-by: Alexander Yuen <[email protected]>

* changed Critic to EdgeScorer in edge cost functions

Signed-off-by: Alexander Yuen <[email protected]>

* changed Critic to EdgeScorer, storing exception message in error msg

Signed-off-by: Alexander Yuen <[email protected]>

* changed Critic to EdgeScorer in edge scorer tests

Signed-off-by: Alexander Yuen <[email protected]>

* changed INVALID_CRITIC_USE to IVALID_EDGE_SCORER_US in actions

* changed RouteData and route_data to RouteRequest and route_request respectively, added doxygen for RouteRequest struct

Signed-off-by: Alexander Yuen <[email protected]>

* added doxygen for EdgeType

Signed-off-by: Alexander Yuen <[email protected]>

---------

Signed-off-by: Alexander Yuen <[email protected]>

* updates

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

* better handle the route situation in the simple commander API

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

* completed TB4 migration

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

* route updates

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

* updating radme

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

* one last comment for the day

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

* adding in BT ndoes, tests, and graphs for bringup

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

* updating error code locations

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

* test for route planner complete

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

* Update to use service server from nav2_utils for service introspection

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

* fix small error

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

* adding in additional smoke tests, prototype working of tracking test to be continued

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

* updates

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

* completed system tests

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

* reenable collision checking

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

* remove unnecssary logging

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

* linting

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

* Update package.xml

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

* closing test gap

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

* a few more lines

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

* changing permissions

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

* fix system test

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

* adding in additional coverage

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

* finalized test coverage

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

* adding file

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

* simple commander demo working

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

* python happiness

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

* precommit spelling happy

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

* wtf pprecommit, why didn't you mention this before

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

* spelling

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

* Update nav2_route/README.md

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

* Update route_planner.cpp

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

* fix mistake in merge conflict resolution

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

* type check fix

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

* lint

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

* linting

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

* more design ideas

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

* Configuring nav2_route_server branch to be mypy compliant (#5081)

* Added definitions for nav2_msgs actions and messages.

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

* Enabled example_route to be compatible with mypy.

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

* Added return definition for route_example_launch.py.

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

* Ported robot_navigator.py to be compliant with mypy.

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

---------

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

* Demo 1 completed

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

* second demo completed

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

* final linting

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

* adding route server for test to pass

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

* adding smoother server

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

* Configured nav2_system_tests to be mypy compliant. (#5085)

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

* Route Tool Rviz Panel (#4775)

* added route tool skeleton code and gui

Signed-off-by: John Chrosniak <[email protected]>

* rviz2 panel can load route graph

Signed-off-by: John Chrosniak <[email protected]>

* can add nodes using route tool

Signed-off-by: John Chrosniak <[email protected]>

* added logic for creating edges

Signed-off-by: John Chrosniak <[email protected]>

* graph nodes can be edited, existing edges will still connect if a node is moved

Signed-off-by: John Chrosniak <[email protected]>

* can edit edges

Signed-off-by: John Chrosniak <[email protected]>

* can delete nodes and edges

Signed-off-by: John Chrosniak <[email protected]>

* route graphs can be saved

Signed-off-by: John Chrosniak <[email protected]>

* fixed bug for loading in route graphs

Signed-off-by: John Chrosniak <[email protected]>

* added dynamic text to UI, created launch file and rviz configuration

Signed-off-by: John Chrosniak <[email protected]>

* fixed bug for deleting nodes

Signed-off-by: John Chrosniak <[email protected]>

* actually fixed node removal bug

Signed-off-by: John Chrosniak <[email protected]>

* publishing clicked point populates x and y fields

Signed-off-by: John Chrosniak <[email protected]>

* removed debugging log statements

Signed-off-by: John Chrosniak <[email protected]>

* added check to make sure node/edges exist before editing

Signed-off-by: John Chrosniak <[email protected]>

* bug fix

Signed-off-by: John Chrosniak <[email protected]>

* migrated route tool to rviz plugin

Signed-off-by: John Chrosniak <[email protected]>

* minor refactoring

Signed-off-by: John Chrosniak <[email protected]>

* added metadata and operations to graph saver so nothing should be erased

Signed-off-by: John Chrosniak <[email protected]>

* edited set route service to clear current route before setting new

Signed-off-by: John Chrosniak <[email protected]>

* Update README.md

Signed-off-by: John Chrosniak <[email protected]>

* addressed comments

Signed-off-by: John Chrosniak <[email protected]>

* documentation cleanup

Signed-off-by: John Chrosniak <[email protected]>

* changed copyright

Signed-off-by: John Chrosniak <[email protected]>

* addressed comments

Signed-off-by: John Chrosniak <[email protected]>

* moved copyright due to compiler error

Signed-off-by: John Chrosniak <[email protected]>

* revert removal of files

Signed-off-by: John Chrosniak <[email protected]>

* added gen ai comment

Signed-off-by: John Chrosniak <[email protected]>

* fixed rebasing issue

Signed-off-by: John Chrosniak <[email protected]>

* fix linting errors

Signed-off-by: John Chrosniak <[email protected]>

* added export for graph saver dependencies

Signed-off-by: John Chrosniak <[email protected]>

* added ui file to library

Signed-off-by: John Chrosniak <[email protected]>

* added nav2_route_core to link libaries

Signed-off-by: John Chrosniak <[email protected]>

* fixed cmake error

Signed-off-by: John Chrosniak <[email protected]>

* fixed build issues

Signed-off-by: John Chrosniak <[email protected]>

* uncrustified

Signed-off-by: John Chrosniak <[email protected]>

* cpplint

Signed-off-by: John Chrosniak <[email protected]>

* added unit tests and fixed bugs

Signed-off-by: John Chrosniak <[email protected]>

* increased test coverage

Signed-off-by: John Chrosniak <[email protected]>

* fixed linter errors

Signed-off-by: John Chrosniak <[email protected]>

* fixed pre-commit errors

Signed-off-by: John Chrosniak <[email protected]>

* fixed formatting error

Signed-off-by: John Chrosniak <[email protected]>

* double -> single quotes

Signed-off-by: John Chrosniak <[email protected]>

* added test for using default filepath

Signed-off-by: John Chrosniak <[email protected]>

* fixed license

Signed-off-by: John Chrosniak <[email protected]>

* addressed comments

Signed-off-by: John Chrosniak <[email protected]>

* Update nav2_route/include/nav2_route/graph_saver.hpp

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

* Update nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp

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

* Update nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp

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

* Update nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp

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

* Update nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp

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

* linter fix

Signed-off-by: John Chrosniak <[email protected]>

---------

Signed-off-by: John Chrosniak <[email protected]>
Co-authored-by: Saikrishna Bairamoni <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* fixing linting

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

* Updating readme table

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

* lint

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

* adding multifloor

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

* adding BFS goal intent search

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

* fix bug

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

* adding unit tests for goal intent search

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

* fixing collision check

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

* Update nav2_simple_commander/nav2_simple_commander/robot_navigator.py

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

---------

Signed-off-by: Alexander Yuen <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Signed-off-by: Leander Stephen D'Souza <[email protected]>
Signed-off-by: John Chrosniak <[email protected]>
Co-authored-by: Joshua Wallace <[email protected]>
Co-authored-by: alexanderjyuen <[email protected]>
Co-authored-by: Leander Stephen D'Souza <[email protected]>
Co-authored-by: John Chrosniak <[email protected]>
Co-authored-by: Saikrishna Bairamoni <[email protected]>

* Feat/smac planner include orientation flexibility (#4127)

* include functionality to allow multiple goal heading for smac planner

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

* include missing parameter inclusion

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

* increase test coverage

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

---------

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

* Support zero value for std_wz in mppi controller (#5110)

* Support zero value for std_wz in mppi controller

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

* Update for better readability

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

---------

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

* Update update_ci_image.yaml to include jazzy build (#5120)

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

* Update update_ci_image.yaml to add humble

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

* message_filters hpp headers have been backported (#5127)

* message_filters hpp headers have been backported

Signed-off-by: Tim Clephas <[email protected]>

* fixup! message_filters hpp headers have been backported

Signed-off-by: Tim Clephas <[email protected]>

---------

Signed-off-by: Tim Clephas <[email protected]>

* Update PULL_REQUEST_TEMPLATE.md

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

* Bibtex formatting (#5126)

* Align citation text to be within the bullet points.

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

* Align formatting to match bibtex guide.

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

* Add justified spacing for readability.
Signed-off-by: Leander Stephen D'Souza <[email protected]>

---------

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

* Make sure fixed curvature lookahead distance doesn't overshoot distance to cusp (#5134)

Related issue: https://github.com/ros-navigation/navigation2/issues/5098

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

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

* Added keepout filter for depot and warehouse maps (#5125)

* Added keepout region to warehouse map.

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

* Support keepout_map as a launch argument.

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

* Added a dictionary to switch between tb4 maps.

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

* Added dedicated launch file for map modifiers.

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

* Added support for depot keepout filter.

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

* Updated keepout masks for depot and warehouse.

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

* Renamed keepout filter launch arguments to keepout zones.

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

* Renamed keepout map launch argument to keepout mask

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

* Renamed map_modifier.launch.py to keepout_zone_launch.py.

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

* Preserve duplication of nodes for keepout test.

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

* Removed padding from keepout zones from depot map.

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

* Added keepout zone at the centre of the warehouse map.

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

* Added utility script to handle namespaces for keepout_filter.

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

* Used utility function to simplify namespace calls.

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

* Moved joinWithParentNamespace to the Layer object.

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

---------

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

* Fix lattice backward 180 deg issue (#5141)

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

* [lifecycle_manager] expose service_timeout (#4838)

* [lifecycle_manager] expose service_timeout

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

* restore original change_state, and detect non_default_timeout

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

* lint

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

* spell

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

* collapse change_state and remove non_default_timeout logic

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

* Update nav2_util/src/lifecycle_service_client.cpp

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

---------

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

* Update simple_action_server.hpp for description (#5150)

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

* reset motion model (#5149)

Signed-off-by: Adi Vardi <[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]>

---------

Signed-off-by: Nils-ChristianIseke <[email protected]>
Signed-off-by: Tatsuro Sakaguchi <[email protected]>
Signed-off-by: Michal Sojka <[email protected]>
Signed-off-by: suchetanrs <[email protected]>
Signed-off-by: Michael Carlstrom <[email protected]>
Signed-off-by: Alberto Tudela <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Signed-off-by: Yancey <[email protected]>
Signed-off-by: Leander Stephen D'Souza <[email protected]>
Signed-off-by: mini-1235 <[email protected]>
Signed-off-by: Kemal Bektas <[email protected]>
Signed-off-by: Johannes Plapp <[email protected]>
Signed-off-by: Rasmus Larsson <[email protected]>
Signed-off-by: zz990099 <[email protected]>
Signed-off-by: Dylan De Coeyer <[email protected]>
Signed-off-by: Guillaume Doisy <[email protected]>
Signed-off-by: Adi Vardi <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Vignesh T <[email protected]>
Signed-off-by: Alexander Yuen <[email protected]>
Signed-off-by: John Chrosniak <[email protected]>
Signed-off-by: stevedanomodolor <[email protected]>
Signed-off-by: Tim Clephas <[email protected]>
Signed-off-by: Pradheep <[email protected]>
Signed-off-by: selazarev <[email protected]>
Signed-off-by: Guillaume Doisy <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Co-authored-by: Nils-Christian Iseke <[email protected]>
Co-authored-by: Tatsuro Sakaguchi <[email protected]>
Co-authored-by: Michal Sojka <[email protected]>
Co-authored-by: Michael Carlstrom <[email protected]>
Co-authored-by: Alberto Tudela <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>
Co-authored-by: Yancey <[email protected]>
Co-authored-by: Leander Stephen D'Souza <[email protected]>
Co-authored-by: mini-1235 <[email protected]>
Co-authored-by: Kemal Bektas <[email protected]>
Co-authored-by: Kemal Bektas <[email protected]>
Co-authored-by: Johannes Plapp <[email protected]>
Co-authored-by: RasmusLar <[email protected]>
Co-authored-by: zz99 <[email protected]>
Co-authored-by: DylanDeCoeyer-Quimesis <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Adi Vardi <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: Sandeep Dutta <[email protected]>
Co-authored-by: Vignesh T <[email protected]>
Co-authored-by: Joshua Wallace <[email protected]>
Co-authored-by: alexanderjyuen <[email protected]>
Co-authored-by: John Chrosniak <[email protected]>
Co-authored-by: Saikrishna Bairamoni <[email protected]>
Co-authored-by: Stevedan Ogochukwu Omodolor <[email protected]>
Co-authored-by: Tim Clephas <[email protected]>
Co-authored-by: moooeeeep <[email protected]>
Co-authored-by: Pradheep Krishna <[email protected]>
Co-authored-by: Semyon <[email protected]>
SakshayMahna pushed a commit to SakshayMahna/navigation2 that referenced this pull request Jun 8, 2025
* Revert removing live groot monitoring from Nav2 (ros-navigation#2696)

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

* Update to Groot2

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

* Added JSON conversions

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

* Fix rebase

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

* Update to nav_msgs::Goals

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

* Added nav_msgs to json utils

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

* Add register to types

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

* Fix null-dereference

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

* Added Json test

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

* Fix some tests

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

* Fix flake

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

* Update package dependency

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

* Minor fixes

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

* Fix test

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

* Rename groot_publisher_port parameter to groot_server_port

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

* Minor  fix in tst

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

* Added JSON for waypoint_status

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

---------

Signed-off-by: Alberto Tudela <[email protected]>
Signed-off-by: Sakshay Mahna <[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.

3 participants