Skip to content

Commit b6a5387

Browse files
SteveMacenskijwallace42alexanderjyuenleander-dsouzajohn-chrosniak
authored
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 <stevenmacenski@gmail.com> * 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 <alex@polymathrobotics.com> * added goal_orientation scorer Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * added test for GoalOrientationScorer Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * changed goal pose to a const ref, and moved score to end as implicit return Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * changed goal arguments to const ref Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * using const ref for goal pose, rearranged total_score to match header Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * linting on goal_orientation_scorer.hpp Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * using M_PI as default threshold, fixed angle wrapping by using angles library, no longer modifying cost Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * changed arguments to use const refs, changed argument order in score function to matach header Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * 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 <alex@polymathrobotics.com> * switched cost edge pairs to imply return of cost, default orientation as M_PI / 2.0 Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> --------- Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * minor updates Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * fix a few bugs, clarify a few things Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * more validation and inline comments to help readers understand complex interactions Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * CI turning over Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * adding error_msg Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * updated cmake style to be in line with repo Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * Adding afew mores features from TODO list Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * 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 <alex@polymathrobotics.com> * passing tf to route planner Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * added null buffer to tests Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * added null buffer to planner configure in performance bench marking test Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * changed arguments of all old edge scorers to also take tf_buffer Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * 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 <alex@polymathrobotics.com> * added start_pose_orientation_scorer to CMake Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * added StartPoseOrientationScorer as and edge scroer Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * added tf_buffer to constructor, added start edge bool on score method, added tf_buffer as a protected variable Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * 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 <alex@polymathrobotics.com> * 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 <alex@polymathrobotics.com> * adding start_pose_orientation_scorer.cpp Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * 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 <alex@polymathrobotics.com> * removed redundant parameter declarations, changed robot frame to base frame, year bump Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * changed robot frame to base frame, year bump on copy right Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * removed unnecessary tf_buffer_ from edge_scorer Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * added EdgeType enum class Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * all edge scorer plugins changed to use EdgeType Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * edge_scorer modified to use EdgeType enum class Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * edge_cost_function base class modified to use EdgeType enum class Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * modified tests for new scorer signature Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * added method to classify edge type Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * ament_cpplinting Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * linting Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * changed EdgeType to const ref Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * added option to score orientations instead of outright rejecting start poses Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * updated docstrings to have better description for goal pose and start pose orientation goal checker Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * fixed merge conflict in goal_orientation_scorer.hpp Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * fixed merge conflict in edge_cost_function.hpp Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * removed TODO from costmap_scorer.cpp Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * added getStart method to goal_intent_extract and start pose argument for findRoute Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * added RouteData struct to types.hpp Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * added start_pose to edge scorer hpp and cpp Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * fixed type getStart return type in goal_intent_extractor.cpp Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * added passing of start_pose down to scorer in route_planner Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * added start pose to base edge cost function class Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * underscore fix for goal_intent_extractor_ Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * changed signature of all edge cost functions to take start_pose Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * populating RouteData and passing it into findRoute Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * passing route_data down to getTraversalCost Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * plugins modified to take in route_data, tests updated accordingly Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * using route data for goal_orientation_scorer and start_pose_orientation_scorer, modified tests accordingly Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * removed route frame, robot frame, and getRobotPose from start_pose_orientation_scorer Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * removed used of stat_pose and goal_pose as it is replaced with route data Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * 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 <alex@polymathrobotics.com> * added INVALID_CRITIC_USE error code in route actions Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * added orientation weighting for cost as an option instead of out right rejection Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * updated docstring for goal orientation scorer Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * renamed Critic to EdgeScorer Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * changed Critic to EdgeScorer in edge cost functions Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * changed Critic to EdgeScorer, storing exception message in error msg Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * changed Critic to EdgeScorer in edge scorer tests Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * 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 <alex@polymathrobotics.com> * added doxygen for EdgeType Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> --------- Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> * updates Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * better handle the route situation in the simple commander API Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * completed TB4 migration Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * route updates Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * updating radme Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * one last comment for the day Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * adding in BT ndoes, tests, and graphs for bringup Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * updating error code locations Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * test for route planner complete Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * Update to use service server from nav2_utils for service introspection Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * fix small error Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * adding in additional smoke tests, prototype working of tracking test to be continued Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * updates Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * completed system tests Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * reenable collision checking Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * remove unnecssary logging Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * linting Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * Update package.xml Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * closing test gap Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * a few more lines Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * changing permissions Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * fix system test Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * adding in additional coverage Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * finalized test coverage Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * adding file Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * simple commander demo working Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * python happiness Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * precommit spelling happy Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * wtf pprecommit, why didn't you mention this before Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * spelling Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * Update nav2_route/README.md Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * Update route_planner.cpp Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * fix mistake in merge conflict resolution Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * type check fix Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * lint Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * linting Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * more design ideas Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * 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 <leanderdsouza1234@gmail.com> * Enabled example_route to be compatible with mypy. Signed-off-by: Leander Stephen D'Souza <leanderdsouza1234@gmail.com> * Added return definition for route_example_launch.py. Signed-off-by: Leander Stephen D'Souza <leanderdsouza1234@gmail.com> * Ported robot_navigator.py to be compliant with mypy. Signed-off-by: Leander Stephen D'Souza <leanderdsouza1234@gmail.com> --------- Signed-off-by: Leander Stephen D'Souza <leanderdsouza1234@gmail.com> * Demo 1 completed Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * second demo completed Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * final linting Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * adding route server for test to pass Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * adding smoother server Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * Configured nav2_system_tests to be mypy compliant. (#5085) Signed-off-by: Leander Stephen D'Souza <leanderdsouza1234@gmail.com> * Route Tool Rviz Panel (#4775) * added route tool skeleton code and gui Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * rviz2 panel can load route graph Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * can add nodes using route tool Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added logic for creating edges Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * graph nodes can be edited, existing edges will still connect if a node is moved Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * can edit edges Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * can delete nodes and edges Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * route graphs can be saved Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed bug for loading in route graphs Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added dynamic text to UI, created launch file and rviz configuration Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed bug for deleting nodes Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * actually fixed node removal bug Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * publishing clicked point populates x and y fields Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * removed debugging log statements Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added check to make sure node/edges exist before editing Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * bug fix Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * migrated route tool to rviz plugin Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * minor refactoring Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added metadata and operations to graph saver so nothing should be erased Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * edited set route service to clear current route before setting new Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * Update README.md Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * addressed comments Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * documentation cleanup Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * changed copyright Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * addressed comments Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * moved copyright due to compiler error Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * revert removal of files Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added gen ai comment Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed rebasing issue Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fix linting errors Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added export for graph saver dependencies Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added ui file to library Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added nav2_route_core to link libaries Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed cmake error Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed build issues Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * uncrustified Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * cpplint Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added unit tests and fixed bugs Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * increased test coverage Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed linter errors Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed pre-commit errors Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed formatting error Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * double -> single quotes Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added test for using default filepath Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed license Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * addressed comments Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * Update nav2_route/include/nav2_route/graph_saver.hpp Co-authored-by: Steve Macenski <stevenmacenski@gmail.com> Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * Update nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp Co-authored-by: Steve Macenski <stevenmacenski@gmail.com> Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * Update nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp Co-authored-by: Steve Macenski <stevenmacenski@gmail.com> Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * Update nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp Co-authored-by: Steve Macenski <stevenmacenski@gmail.com> Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * Update nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp Co-authored-by: Steve Macenski <stevenmacenski@gmail.com> Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * linter fix Signed-off-by: John Chrosniak <chrosniakj@gmail.com> --------- Signed-off-by: John Chrosniak <chrosniakj@gmail.com> Co-authored-by: Saikrishna Bairamoni <84093461+SaikrishnaBairamoni@users.noreply.github.com> Co-authored-by: Steve Macenski <stevenmacenski@gmail.com> * fixing linting Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * Updating readme table Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * lint Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * adding multifloor Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * adding BFS goal intent search Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * fix bug Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * adding unit tests for goal intent search Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * fixing collision check Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * Update nav2_simple_commander/nav2_simple_commander/robot_navigator.py Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> --------- Signed-off-by: Alexander Yuen <alex@polymathrobotics.com> Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> Signed-off-by: Leander Stephen D'Souza <leanderdsouza1234@gmail.com> Signed-off-by: John Chrosniak <chrosniakj@gmail.com> Co-authored-by: Joshua Wallace <josho.wallace@gmail.com> Co-authored-by: alexanderjyuen <103065090+alexanderjyuen@users.noreply.github.com> Co-authored-by: Leander Stephen D'Souza <leanderdsouza1234@gmail.com> Co-authored-by: John Chrosniak <chrosniakj@gmail.com> Co-authored-by: Saikrishna Bairamoni <84093461+SaikrishnaBairamoni@users.noreply.github.com>
1 parent 004823e commit b6a5387

File tree

211 files changed

+21079
-210
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

211 files changed

+21079
-210
lines changed

README.md

Lines changed: 36 additions & 35 deletions
Large diffs are not rendered by default.

nav2_behavior_tree/CMakeLists.txt

Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -104,6 +104,9 @@ list(APPEND plugin_libs nav2_transform_available_condition_bt_node)
104104
add_library(nav2_goal_reached_condition_bt_node SHARED plugins/condition/goal_reached_condition.cpp)
105105
list(APPEND plugin_libs nav2_goal_reached_condition_bt_node)
106106

107+
add_library(nav2_are_poses_near_condition_bt_node SHARED plugins/condition/are_poses_near_condition.cpp)
108+
list(APPEND plugin_libs nav2_are_poses_near_condition_bt_node)
109+
107110
add_library(nav2_globally_updated_goal_condition_bt_node SHARED plugins/condition/globally_updated_goal_condition.cpp)
108111
list(APPEND plugin_libs nav2_globally_updated_goal_condition_bt_node)
109112

@@ -143,6 +146,9 @@ list(APPEND plugin_libs nav2_would_a_planner_recovery_help_condition_bt_node)
143146
add_library(nav2_would_a_smoother_recovery_help_condition_bt_node SHARED plugins/condition/would_a_smoother_recovery_help_condition.cpp)
144147
list(APPEND plugin_libs nav2_would_a_smoother_recovery_help_condition_bt_node)
145148

149+
add_library(nav2_would_a_route_recovery_help_condition_bt_node SHARED plugins/condition/would_a_route_recovery_help_condition.cpp)
150+
list(APPEND plugin_libs nav2_would_a_route_recovery_help_condition_bt_node)
151+
146152
add_library(nav2_reinitialize_global_localization_service_bt_node SHARED plugins/action/reinitialize_global_localization_service.cpp)
147153
list(APPEND plugin_libs nav2_reinitialize_global_localization_service_bt_node)
148154

@@ -158,6 +164,9 @@ list(APPEND plugin_libs nav2_speed_controller_bt_node)
158164
add_library(nav2_truncate_path_action_bt_node SHARED plugins/action/truncate_path_action.cpp)
159165
list(APPEND plugin_libs nav2_truncate_path_action_bt_node)
160166

167+
add_library(nav2_concatenate_paths_action_bt_node SHARED plugins/action/concatenate_paths_action.cpp)
168+
list(APPEND plugin_libs nav2_concatenate_paths_action_bt_node)
169+
161170
add_library(nav2_truncate_path_local_action_bt_node SHARED plugins/action/truncate_path_local_action.cpp)
162171
list(APPEND plugin_libs nav2_truncate_path_local_action_bt_node)
163172

@@ -182,9 +191,21 @@ list(APPEND plugin_libs nav2_remove_passed_goals_action_bt_node)
182191
add_library(nav2_remove_in_collision_goals_action_bt_node SHARED plugins/action/remove_in_collision_goals_action.cpp)
183192
list(APPEND plugin_libs nav2_remove_in_collision_goals_action_bt_node)
184193

194+
add_library(nav2_append_goal_pose_to_goals_action_bt_node SHARED plugins/action/append_goal_pose_to_goals_action.cpp)
195+
list(APPEND plugin_libs nav2_append_goal_pose_to_goals_action_bt_node)
196+
185197
add_library(nav2_get_pose_from_path_action_bt_node SHARED plugins/action/get_pose_from_path_action.cpp)
186198
list(APPEND plugin_libs nav2_get_pose_from_path_action_bt_node)
187199

200+
add_library(nav2_extract_route_nodes_as_goals_action_bt_node SHARED plugins/action/extract_route_nodes_as_goals_action.cpp)
201+
list(APPEND plugin_libs nav2_extract_route_nodes_as_goals_action_bt_node)
202+
203+
add_library(nav2_get_next_few_goals_action_bt_node SHARED plugins/action/get_next_few_goals_action.cpp)
204+
list(APPEND plugin_libs nav2_get_next_few_goals_action_bt_node)
205+
206+
add_library(nav2_get_current_pose_action_bt_node SHARED plugins/action/get_current_pose_action.cpp)
207+
list(APPEND plugin_libs nav2_get_current_pose_action_bt_node)
208+
188209
add_library(nav2_pipeline_sequence_bt_node SHARED plugins/control/pipeline_sequence.cpp)
189210
list(APPEND plugin_libs nav2_pipeline_sequence_bt_node)
190211

@@ -212,6 +233,15 @@ list(APPEND plugin_libs nav2_progress_checker_selector_bt_node)
212233
add_library(nav2_goal_updated_controller_bt_node SHARED plugins/decorator/goal_updated_controller.cpp)
213234
list(APPEND plugin_libs nav2_goal_updated_controller_bt_node)
214235

236+
add_library(nav2_compute_and_track_route_cancel_bt_node SHARED plugins/action/compute_and_track_route_cancel_node.cpp)
237+
list(APPEND plugin_libs nav2_compute_and_track_route_cancel_bt_node)
238+
239+
add_library(nav2_compute_and_track_route_bt_node SHARED plugins/action/compute_and_track_route_action.cpp)
240+
list(APPEND plugin_libs nav2_compute_and_track_route_bt_node)
241+
242+
add_library(nav2_compute_route_bt_node SHARED plugins/action/compute_route_action.cpp)
243+
list(APPEND plugin_libs nav2_compute_route_bt_node)
244+
215245
foreach(bt_plugin ${plugin_libs})
216246
target_include_directories(${bt_plugin}
217247
PRIVATE
Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,56 @@
1+
// Copyright (c) 2025 Open Navigation LLC
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__APPEND_GOAL_POSE_TO_GOALS_ACTION_HPP_
16+
#define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__APPEND_GOAL_POSE_TO_GOALS_ACTION_HPP_
17+
18+
#include <vector>
19+
#include <memory>
20+
#include <string>
21+
22+
#include "nav_msgs/msg/goals.hpp"
23+
#include "nav2_msgs/msg/route.hpp"
24+
#include "geometry_msgs/msg/pose_stamped.hpp"
25+
#include "nav2_util/geometry_utils.hpp"
26+
#include "nav2_util/robot_utils.hpp"
27+
#include "behaviortree_cpp/action_node.h"
28+
29+
namespace nav2_behavior_tree
30+
{
31+
32+
class AppendGoalPoseToGoals : public BT::ActionNodeBase
33+
{
34+
public:
35+
AppendGoalPoseToGoals(
36+
const std::string & xml_tag_name,
37+
const BT::NodeConfiguration & conf);
38+
39+
40+
static BT::PortsList providedPorts()
41+
{
42+
return {
43+
BT::InputPort<geometry_msgs::msg::PoseStamped>("goal_pose", "Goal pose to append"),
44+
BT::InputPort<nav_msgs::msg::Goals>("input_goals", "Input goals to append to"),
45+
BT::OutputPort<nav_msgs::msg::Goals>("output_goals", "Output goals after appending")
46+
};
47+
}
48+
49+
private:
50+
void halt() override {}
51+
BT::NodeStatus tick() override;
52+
};
53+
54+
} // namespace nav2_behavior_tree
55+
56+
#endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__APPEND_GOAL_POSE_TO_GOALS_ACTION_HPP_
Lines changed: 107 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,107 @@
1+
// Copyright (c) 2025 Open Navigation LLC
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_AND_TRACK_ROUTE_ACTION_HPP_
16+
#define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_AND_TRACK_ROUTE_ACTION_HPP_
17+
18+
#include <string>
19+
#include <memory>
20+
21+
#include "nav2_msgs/action/compute_and_track_route.hpp"
22+
#include "nav2_behavior_tree/bt_action_node.hpp"
23+
24+
namespace nav2_behavior_tree
25+
{
26+
27+
/**
28+
* @brief A nav2_behavior_tree::BtActionNode class that wraps nav2_msgs::action::ComputeAndTrackRoute
29+
*/
30+
class ComputeAndTrackRouteAction : public BtActionNode<nav2_msgs::action::ComputeAndTrackRoute>
31+
{
32+
using Action = nav2_msgs::action::ComputeAndTrackRoute;
33+
using ActionResult = Action::Result;
34+
35+
public:
36+
/**
37+
* @brief A constructor for nav2_behavior_tree::ComputeAndTrackRouteAction
38+
* @param xml_tag_name Name for the XML tag for this node
39+
* @param action_name Action name this node creates a client for
40+
* @param conf BT node configuration
41+
*/
42+
ComputeAndTrackRouteAction(
43+
const std::string & xml_tag_name,
44+
const std::string & action_name,
45+
const BT::NodeConfiguration & conf);
46+
47+
/**
48+
* @brief Function to perform some user-defined operation on tick
49+
*/
50+
void on_tick() override;
51+
52+
/**
53+
* @brief Function to perform some user-defined operation upon successful completion of the action
54+
*/
55+
BT::NodeStatus on_success() override;
56+
57+
/**
58+
* @brief Function to perform some user-defined operation upon abortion of the action
59+
*/
60+
BT::NodeStatus on_aborted() override;
61+
62+
/**
63+
* @brief Function to perform some user-defined operation upon cancellation of the action
64+
*/
65+
BT::NodeStatus on_cancelled() override;
66+
67+
/**
68+
* @brief Function to perform some user-defined operation after a timeout
69+
* waiting for a result that hasn't been received yet
70+
* @param feedback shared_ptr to latest feedback message
71+
*/
72+
void on_wait_for_result(
73+
std::shared_ptr<const Action::Feedback> feedback) override;
74+
75+
/**
76+
* @brief Creates list of BT ports
77+
* @return BT::PortsList Containing basic ports along with node-specific ports
78+
*/
79+
static BT::PortsList providedPorts()
80+
{
81+
return providedBasicPorts(
82+
{
83+
BT::InputPort<unsigned int>("start_id", "ID of the start node"),
84+
BT::InputPort<unsigned int>("goal_id", "ID of the goal node"),
85+
BT::InputPort<geometry_msgs::msg::PoseStamped>(
86+
"start",
87+
"Start pose of the path if overriding current robot pose and using poses over IDs"),
88+
BT::InputPort<geometry_msgs::msg::PoseStamped>(
89+
"goal", "Goal pose of the path if using poses over IDs"),
90+
BT::InputPort<bool>(
91+
"use_start", false,
92+
"Whether to use the start pose or the robot's current pose"),
93+
BT::InputPort<bool>(
94+
"use_poses", false, "Whether to use poses or IDs for start and goal"),
95+
BT::OutputPort<builtin_interfaces::msg::Duration>("execution_duration",
96+
"Time taken to compute and track route"),
97+
BT::OutputPort<ActionResult::_error_code_type>(
98+
"error_code_id", "The compute route error code"),
99+
BT::OutputPort<std::string>(
100+
"error_msg", "The compute route error msg"),
101+
});
102+
}
103+
};
104+
105+
} // namespace nav2_behavior_tree
106+
107+
#endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_AND_TRACK_ROUTE_ACTION_HPP_
Lines changed: 61 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,61 @@
1+
// Copyright (c) 2025 Open Navigation LLC
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_AND_TRACK_ROUTE_CANCEL_NODE_HPP_
16+
#define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_AND_TRACK_ROUTE_CANCEL_NODE_HPP_
17+
18+
#include <memory>
19+
#include <string>
20+
21+
#include "nav2_msgs/action/compute_and_track_route.hpp"
22+
23+
#include "nav2_behavior_tree/bt_cancel_action_node.hpp"
24+
25+
namespace nav2_behavior_tree
26+
{
27+
28+
/**
29+
* @brief A nav2_behavior_tree::BtActionNode class
30+
* that wraps nav2_msgs::action::ComputeAndTrackRoute cancellation
31+
*/
32+
class ComputeAndTrackRouteCancel
33+
: public BtCancelActionNode<nav2_msgs::action::ComputeAndTrackRoute>
34+
{
35+
public:
36+
/**
37+
* @brief A constructor for nav2_behavior_tree::ComputeAndTrackRouteCancel
38+
* @param xml_tag_name Name for the XML tag for this node
39+
* @param action_name Action name this node creates a client for
40+
* @param conf BT node configuration
41+
*/
42+
ComputeAndTrackRouteCancel(
43+
const std::string & xml_tag_name,
44+
const std::string & action_name,
45+
const BT::NodeConfiguration & conf);
46+
47+
/**
48+
* @brief Creates list of BT ports
49+
* @return BT::PortsList Containing basic ports along with node-specific ports
50+
*/
51+
static BT::PortsList providedPorts()
52+
{
53+
return providedBasicPorts(
54+
{
55+
});
56+
}
57+
};
58+
59+
} // namespace nav2_behavior_tree
60+
61+
#endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_AND_TRACK_ROUTE_CANCEL_NODE_HPP_

0 commit comments

Comments
 (0)