From 6f04608e49ede993387e93274faae6bec294274c Mon Sep 17 00:00:00 2001 From: Alan Xue Date: Thu, 28 Mar 2024 13:39:33 +0000 Subject: [PATCH 1/7] Refactor the plugin names for bt_navigator to use double colons --- configuration/packages/configuring-bt-navigator.rst | 4 ++-- plugin_tutorials/docs/writing_new_navigator_plugin.rst | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/configuration/packages/configuring-bt-navigator.rst b/configuration/packages/configuring-bt-navigator.rst index 233c04be2..322cd4167 100644 --- a/configuration/packages/configuring-bt-navigator.rst +++ b/configuration/packages/configuring-bt-navigator.rst @@ -246,9 +246,9 @@ Example path_blackboard_id: path navigators: ['navigate_to_pose', 'navigate_through_poses'] navigate_to_pose: - plugin: "nav2_bt_navigator/NavigateToPoseNavigator" + plugin: "nav2_bt_navigator::NavigateToPoseNavigator" navigate_through_poses: - plugin: "nav2_bt_navigator/NavigateThroughPosesNavigator" + plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator" plugin_lib_names: - nav2_compute_path_to_pose_action_bt_node - nav2_follow_path_action_bt_node diff --git a/plugin_tutorials/docs/writing_new_navigator_plugin.rst b/plugin_tutorials/docs/writing_new_navigator_plugin.rst index 516382b33..859557ddb 100644 --- a/plugin_tutorials/docs/writing_new_navigator_plugin.rst +++ b/plugin_tutorials/docs/writing_new_navigator_plugin.rst @@ -332,12 +332,12 @@ To enable the plugin, we need to modify the ``nav2_params.yaml`` file as below path_blackboard_id: path navigators: ['navigate_to_pose', 'navigate_through_poses'] navigate_to_pose: - plugin: "nav2_bt_navigator/NavigateToPoseNavigator" + plugin: "nav2_bt_navigator::NavigateToPoseNavigator" navigate_through_poses: - plugin: "nav2_bt_navigator/NavigateThroughPosesNavigator" + plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator" -In the above snippet, you can observe the mapping of our ``nav2_bt_navigator/NavigateToPoseNavigator`` plugin to its id ``navigate_to_pose``. +In the above snippet, you can observe the mapping of our ``nav2_bt_navigator::NavigateToPoseNavigator`` plugin to its id ``navigate_to_pose``. To pass plugin-specific parameters we have used ``.``. 4- Run plugin From 976239ef5771547110ffd6e8264c7acbd67dfe3b Mon Sep 17 00:00:00 2001 From: Alan Xue Date: Thu, 28 Mar 2024 13:45:37 +0000 Subject: [PATCH 2/7] Refactor the plugin names for planner_server to use double colons Signed-off-by: Alan Xue --- configuration/packages/configuring-navfn.rst | 2 +- configuration/packages/configuring-planner-server.rst | 6 +++--- configuration/packages/configuring-thetastar.rst | 2 +- configuration/packages/smac/configuring-smac-2d.rst | 2 +- configuration/packages/smac/configuring-smac-hybrid.rst | 2 +- configuration/packages/smac/configuring-smac-lattice.rst | 2 +- plugin_tutorials/docs/writing_new_nav2planner_plugin.rst | 2 +- setup_guides/algorithm/select_algorithm.rst | 2 +- 8 files changed, 10 insertions(+), 10 deletions(-) diff --git a/configuration/packages/configuring-navfn.rst b/configuration/packages/configuring-navfn.rst index 114a51ff5..d8c92e40c 100644 --- a/configuration/packages/configuring-navfn.rst +++ b/configuration/packages/configuring-navfn.rst @@ -66,7 +66,7 @@ Example ros__parameters: planner_plugins: ['GridBased'] GridBased: - plugin: 'nav2_navfn_planner/NavfnPlanner' + plugin: 'nav2_navfn_planner::NavfnPlanner' use_astar: True allow_unknown: True tolerance: 1.0 diff --git a/configuration/packages/configuring-planner-server.rst b/configuration/packages/configuring-planner-server.rst index 1cac857de..27d27d1b8 100644 --- a/configuration/packages/configuring-planner-server.rst +++ b/configuration/packages/configuring-planner-server.rst @@ -36,7 +36,7 @@ Parameters ros__parameters: planner_plugins: ["GridBased"] GridBased: - plugin: "nav2_navfn_planner/NavfnPlanner" + plugin: "nav2_navfn_planner::NavfnPlanner" .. :expected_planner_frequency: @@ -72,7 +72,7 @@ When the :code:`planner_plugins` parameter is not overridden, the following defa ================= ===================================================== Namespace Plugin ----------------- ----------------------------------------------------- - "GridBased" "nav2_navfn_planner/NavfnPlanner" + "GridBased" "nav2_navfn_planner::NavfnPlanner" ================= ===================================================== Example @@ -84,4 +84,4 @@ Example expected_planner_frequency: 20.0 planner_plugins: ['GridBased'] GridBased: - plugin: 'nav2_navfn_planner/NavfnPlanner' + plugin: 'nav2_navfn_planner::NavfnPlanner' diff --git a/configuration/packages/configuring-thetastar.rst b/configuration/packages/configuring-thetastar.rst index b1c2219fd..d61fcc24f 100644 --- a/configuration/packages/configuring-thetastar.rst +++ b/configuration/packages/configuring-thetastar.rst @@ -107,7 +107,7 @@ Example use_sim_time: True planner_plugins: ["GridBased"] GridBased: - plugin: "nav2_theta_star_planner/ThetaStarPlanner" + plugin: "nav2_theta_star_planner::ThetaStarPlanner" how_many_corners: 8 w_euc_cost: 1.0 w_traversal_cost: 2.0 diff --git a/configuration/packages/smac/configuring-smac-2d.rst b/configuration/packages/smac/configuring-smac-2d.rst index f14a28c85..1186fe19e 100644 --- a/configuration/packages/smac/configuring-smac-2d.rst +++ b/configuration/packages/smac/configuring-smac-2d.rst @@ -179,7 +179,7 @@ Example use_sim_time: True GridBased: - plugin: "nav2_smac_planner/SmacPlanner2D" + plugin: "nav2_smac_planner::SmacPlanner2D" tolerance: 0.125 # tolerance for planning if unable to reach exact pose, in meters downsample_costmap: false # whether or not to downsample the map downsampling_factor: 1 # multiplier for the resolution of the costmap layer (e.g. 2 on a 5cm costmap would be 10cm) diff --git a/configuration/packages/smac/configuring-smac-hybrid.rst b/configuration/packages/smac/configuring-smac-hybrid.rst index 14ff036da..94a0d2dd8 100644 --- a/configuration/packages/smac/configuring-smac-hybrid.rst +++ b/configuration/packages/smac/configuring-smac-hybrid.rst @@ -388,7 +388,7 @@ Example use_sim_time: True GridBased: - plugin: "nav2_smac_planner/SmacPlannerHybrid" + plugin: "nav2_smac_planner::SmacPlannerHybrid" downsample_costmap: false # whether or not to downsample the map downsampling_factor: 1 # multiplier for the resolution of the costmap layer (e.g. 2 on a 5cm costmap would be 10cm) tolerance: 0.25 # dist-to-goal heuristic cost (distance) for valid tolerance endpoints if exact goal cannot be found. diff --git a/configuration/packages/smac/configuring-smac-lattice.rst b/configuration/packages/smac/configuring-smac-lattice.rst index b195a9cb3..8b003b58b 100644 --- a/configuration/packages/smac/configuring-smac-lattice.rst +++ b/configuration/packages/smac/configuring-smac-lattice.rst @@ -338,7 +338,7 @@ Example use_sim_time: True GridBased: - plugin: "nav2_smac_planner/SmacPlannerLattice" + plugin: "nav2_smac_planner::SmacPlannerLattice" allow_unknown: true # Allow traveling in unknown space tolerance: 0.25 # dist-to-goal heuristic cost (distance) for valid tolerance endpoints if exact goal cannot be found. max_iterations: 1000000 # Maximum total iterations to search for before failing (in case unreachable), set to -1 to disable diff --git a/plugin_tutorials/docs/writing_new_nav2planner_plugin.rst b/plugin_tutorials/docs/writing_new_nav2planner_plugin.rst index 19429ac09..564551a75 100644 --- a/plugin_tutorials/docs/writing_new_nav2planner_plugin.rst +++ b/plugin_tutorials/docs/writing_new_nav2planner_plugin.rst @@ -200,7 +200,7 @@ To enable the plugin, we need to modify the ``nav2_params.yaml`` file as below t plugins: ["GridBased"] use_sim_time: True GridBased: - plugin: "nav2_navfn_planner/NavfnPlanner" # For Foxy and later + plugin: "nav2_navfn_planner::NavfnPlanner" # For Foxy and later tolerance: 2.0 use_astar: false allow_unknown: true diff --git a/setup_guides/algorithm/select_algorithm.rst b/setup_guides/algorithm/select_algorithm.rst index 774aeabfe..1c7b61224 100644 --- a/setup_guides/algorithm/select_algorithm.rst +++ b/setup_guides/algorithm/select_algorithm.rst @@ -66,7 +66,7 @@ Example Configuration ros__parameters: planner_plugins: ['GridBased'] GridBased: - plugin: 'nav2_navfn_planner/NavfnPlanner' + plugin: 'nav2_navfn_planner::NavfnPlanner' An example configuration of the planner server is shown above. The ``planner_plugins`` parameter accepts a list of mapped planner plugin names. For each plugin namespace defined in ``planner_plugins`` (``GridBased`` in our example), we specify the type of plugin to be loaded in the ``plugin`` parameter. Additional configurations must then be specified in this namespace based on the algorithm to be used. Please see the `Configuration Guide `_ for more details. From 3976355ca6cfedcbb8766207b673a45f9f9a3a71 Mon Sep 17 00:00:00 2001 From: Alan Xue Date: Thu, 28 Mar 2024 13:49:13 +0000 Subject: [PATCH 3/7] Refactor the plugin names for behavior_server to use double colons Signed-off-by: Alan Xue --- .../packages/configuring-behavior-server.rst | 26 +++++++++---------- .../docs/writing_new_behavior_plugin.rst | 12 ++++----- 2 files changed, 19 insertions(+), 19 deletions(-) diff --git a/configuration/packages/configuring-behavior-server.rst b/configuration/packages/configuring-behavior-server.rst index 9342122c1..edfabe286 100644 --- a/configuration/packages/configuring-behavior-server.rst +++ b/configuration/packages/configuring-behavior-server.rst @@ -151,13 +151,13 @@ Behavior Server Parameters ros__parameters: behavior_plugins: ["spin", "backup", "drive_on_heading", "wait"] spin: - plugin: "nav2_behaviors/Spin" + plugin: "nav2_behaviors::Spin" backup: - plugin: "nav2_behaviors/BackUp" + plugin: "nav2_behaviors::BackUp" drive_on_heading: - plugin: "nav2_behaviors/DriveOnHeading" + plugin: "nav2_behaviors::DriveOnHeading" wait: - plugin: "nav2_behaviors/Wait" + plugin: "nav2_behaviors::Wait" .. Default Plugins @@ -168,13 +168,13 @@ When the :code:`behavior_plugins` parameter is not overridden, the following def ================== ===================================================== Namespace Plugin ------------------ ----------------------------------------------------- - "spin" "nav2_behaviors/Spin" + "spin" "nav2_behaviors::Spin" ------------------ ----------------------------------------------------- - "backup" "nav2_behaviors/BackUp" + "backup" "nav2_behaviors::BackUp" ------------------ ----------------------------------------------------- - "drive_on_heading" "nav2_behaviors/DriveOnHeading" + "drive_on_heading" "nav2_behaviors::DriveOnHeading" ------------------ ----------------------------------------------------- - "wait" "nav2_behaviors/Wait" + "wait" "nav2_behaviors::Wait" ================== ===================================================== Spin Behavior Parameters @@ -359,15 +359,15 @@ Example cycle_frequency: 10.0 behavior_plugins: ["spin", "backup", "drive_on_heading", "wait", "assisted_teleop"] spin: - plugin: "nav2_behaviors/Spin" + plugin: "nav2_behaviors::Spin" backup: - plugin: "nav2_behaviors/BackUp" + plugin: "nav2_behaviors::BackUp" drive_on_heading: - plugin: "nav2_behaviors/DriveOnHeading" + plugin: "nav2_behaviors::DriveOnHeading" wait: - plugin: "nav2_behaviors/Wait" + plugin: "nav2_behaviors::Wait" assisted_teleop: - plugin: "nav2_behaviors/AssistedTeleop" + plugin: "nav2_behaviors::AssistedTeleop" local_frame: odom global_frame: map robot_base_frame: base_link diff --git a/plugin_tutorials/docs/writing_new_behavior_plugin.rst b/plugin_tutorials/docs/writing_new_behavior_plugin.rst index 21f6070cf..678e463f5 100644 --- a/plugin_tutorials/docs/writing_new_behavior_plugin.rst +++ b/plugin_tutorials/docs/writing_new_behavior_plugin.rst @@ -211,11 +211,11 @@ To enable the plugin, we need to modify the ``nav2_params.yaml`` file as below t behavior_plugins: ["spin", "backup", "wait"] # Humble and later recovery_plugins: ["spin", "backup", "wait"] # Galactic and earlier spin: - plugin: "nav2_behaviors/Spin" + plugin: "nav2_behaviors::Spin" backup: - plugin: "nav2_behaviors/BackUp" + plugin: "nav2_behaviors::BackUp" wait: - plugin: "nav2_behaviors/Wait" + plugin: "nav2_behaviors::Wait" global_frame: odom robot_base_frame: base_link transform_timeout: 0.1 @@ -240,11 +240,11 @@ with behavior_plugins: ["spin", "backup", "wait","send_sms"] # Humble and newer recovery_plugins: ["spin", "backup", "wait","send_sms"] # Galactic and earlier spin: - plugin: "nav2_behaviors/Spin" + plugin: "nav2_behaviors::Spin" backup: - plugin: "nav2_behaviors/BackUp" + plugin: "nav2_behaviors::BackUp" wait: - plugin: "nav2_behaviors/Wait" + plugin: "nav2_behaviors::Wait" send_sms: plugin: "nav2_sms_behavior/SendSms" account_sid: ... # your sid From da8a203a622d1b7ac42c5ae399127b6d9f5eaeb9 Mon Sep 17 00:00:00 2001 From: Alan Xue Date: Thu, 28 Mar 2024 14:23:19 +0000 Subject: [PATCH 4/7] Refactor the section of plugin tutorials to use double colons Signed-off-by: Alan Xue --- plugin_tutorials/docs/writing_new_behavior_plugin.rst | 4 ++-- plugin_tutorials/docs/writing_new_costmap2d_plugin.rst | 6 +++--- plugin_tutorials/docs/writing_new_nav2controller_plugin.rst | 2 +- plugin_tutorials/docs/writing_new_nav2planner_plugin.rst | 6 +++--- 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/plugin_tutorials/docs/writing_new_behavior_plugin.rst b/plugin_tutorials/docs/writing_new_behavior_plugin.rst index 678e463f5..4ab8f8ba0 100644 --- a/plugin_tutorials/docs/writing_new_behavior_plugin.rst +++ b/plugin_tutorials/docs/writing_new_behavior_plugin.rst @@ -172,7 +172,7 @@ It is good practice to place these lines at the end of the file but technically, .. code-block:: xml - + This is an example plugin which produces an SMS text message recovery. @@ -246,7 +246,7 @@ with wait: plugin: "nav2_behaviors::Wait" send_sms: - plugin: "nav2_sms_behavior/SendSms" + plugin: "nav2_sms_behavior::SendSms" account_sid: ... # your sid auth_token: ... # your token from_number: ... # your number diff --git a/plugin_tutorials/docs/writing_new_costmap2d_plugin.rst b/plugin_tutorials/docs/writing_new_costmap2d_plugin.rst index 919a62b1a..94ca09250 100644 --- a/plugin_tutorials/docs/writing_new_costmap2d_plugin.rst +++ b/plugin_tutorials/docs/writing_new_costmap2d_plugin.rst @@ -152,7 +152,7 @@ This part is usually placed at the end of cpp-file where the plugin class was wr .. code-block:: xml - + This is an example plugin which puts repeating costs gradients to costmap @@ -223,11 +223,11 @@ In this case each plugin object will be handled by its own parameters tree in a .. code-block:: text gradient_layer_1: - plugin: nav2_gradient_costmap_plugin/GradientLayer + plugin: nav2_gradient_costmap_plugin::GradientLayer enabled: True ... gradient_layer_2: - plugin: nav2_gradient_costmap_plugin/GradientLayer + plugin: nav2_gradient_costmap_plugin::GradientLayer enabled: False ... diff --git a/plugin_tutorials/docs/writing_new_nav2controller_plugin.rst b/plugin_tutorials/docs/writing_new_nav2controller_plugin.rst index 8ed3f70cc..2e2368fd6 100644 --- a/plugin_tutorials/docs/writing_new_nav2controller_plugin.rst +++ b/plugin_tutorials/docs/writing_new_nav2controller_plugin.rst @@ -272,7 +272,7 @@ To enable the plugin, we need to modify the ``nav2_params.yaml`` file as below max_angular_vel: 1.0 transform_tolerance: 1.0 -In the above snippet, you can observe the mapping of our ``nav2_pure_pursuit_controller/PurePursuitController`` controller to its id ``FollowPath``. +In the above snippet, you can observe the mapping of our ``nav2_pure_pursuit_controller::PurePursuitController`` controller to its id ``FollowPath``. To pass plugin-specific parameters we have used ``.``. 4- Run Pure Pursuit Controller plugin diff --git a/plugin_tutorials/docs/writing_new_nav2planner_plugin.rst b/plugin_tutorials/docs/writing_new_nav2planner_plugin.rst index 564551a75..6a6c75d18 100644 --- a/plugin_tutorials/docs/writing_new_nav2planner_plugin.rst +++ b/plugin_tutorials/docs/writing_new_nav2planner_plugin.rst @@ -162,7 +162,7 @@ It is good practice to place these lines at the end of the file, but technically .. code-block:: xml - + This is an example plugin which produces straight path. @@ -214,10 +214,10 @@ with plugins: ["GridBased"] use_sim_time: True GridBased: - plugin: "nav2_straightline_planner/StraightLine" + plugin: "nav2_straightline_planner::StraightLine" interpolation_resolution: 0.1 -In the above snippet, you can observe the mapping of our ``nav2_straightline_planner/StraightLine`` planner to its id ``GridBased``. To pass plugin-specific parameters, we have used ``.``. +In the above snippet, you can observe the mapping of our ``nav2_straightline_planner::StraightLine`` planner to its id ``GridBased``. To pass plugin-specific parameters, we have used ``.``. 4- Run StraightLine plugin --------------------------- From adfbc177e77df63d2a3ff3b1c42276f65702d787 Mon Sep 17 00:00:00 2001 From: Alan Xue Date: Thu, 28 Mar 2024 14:39:57 +0000 Subject: [PATCH 5/7] Update the migration guide from Iron to Jazzy to include the standardization of plugin naming using double colons (::). Signed-off-by: Alan Xue --- migration/Iron.rst | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/migration/Iron.rst b/migration/Iron.rst index d2b43bdac..6f8265b94 100644 --- a/migration/Iron.rst +++ b/migration/Iron.rst @@ -304,3 +304,7 @@ New graceful cancellation API for Controllers ********************************************* `PR #4136 `_ introduces a new graceful cancellation API for controllers. Previously when a goal was canceled, the controller would stop the robot immediately. This API allows the controller to stop the robot in a more graceful way. The new API is implemented in the ``RegulatedPurePursuitController`` by adding a new parameter ``cancel_deceleration``. So when the goal is canceled, a constant deceleration will be used while continuing to track the path to stop the robot instead of stopping immediately. This API can be should be added to all controllers that have acceleration limits. + +Standardization of Plugin Naming with Double Colons (::) +******************************************************** +`PR #4220 `_ standardizes plugin naming to use double colons (::), replacing the previous mixed use of slashes (/) and double colons. From 08d699a116045841f9cf27dfb7e364a9f4ae0e91 Mon Sep 17 00:00:00 2001 From: Alan Xue Date: Fri, 29 Mar 2024 04:24:07 +0000 Subject: [PATCH 6/7] Add comment on '/' to '::' syntax change in example YAML files --- .../packages/configuring-behavior-server.rst | 20 ++++++++++--------- .../packages/configuring-bt-navigator.rst | 4 ++-- configuration/packages/configuring-navfn.rst | 2 +- .../packages/configuring-planner-server.rst | 4 ++-- .../packages/configuring-thetastar.rst | 2 +- .../packages/smac/configuring-smac-2d.rst | 2 +- .../packages/smac/configuring-smac-hybrid.rst | 2 +- .../smac/configuring-smac-lattice.rst | 2 +- .../docs/writing_new_behavior_plugin.rst | 14 ++++++------- .../docs/writing_new_costmap2d_plugin.rst | 4 ++-- .../writing_new_nav2controller_plugin.rst | 2 +- .../docs/writing_new_nav2planner_plugin.rst | 2 +- .../docs/writing_new_navigator_plugin.rst | 4 ++-- setup_guides/algorithm/select_algorithm.rst | 2 +- 14 files changed, 34 insertions(+), 32 deletions(-) diff --git a/configuration/packages/configuring-behavior-server.rst b/configuration/packages/configuring-behavior-server.rst index edfabe286..3df9487de 100644 --- a/configuration/packages/configuring-behavior-server.rst +++ b/configuration/packages/configuring-behavior-server.rst @@ -151,17 +151,19 @@ Behavior Server Parameters ros__parameters: behavior_plugins: ["spin", "backup", "drive_on_heading", "wait"] spin: - plugin: "nav2_behaviors::Spin" + plugin: "nav2_behaviors::Spin" # In Iron and older versions, "/" was used instead of "::" backup: - plugin: "nav2_behaviors::BackUp" + plugin: "nav2_behaviors::BackUp" # In Iron and older versions, "/" was used instead of "::" drive_on_heading: - plugin: "nav2_behaviors::DriveOnHeading" + plugin: "nav2_behaviors::DriveOnHeading" # In Iron and older versions, "/" was used instead of "::" wait: - plugin: "nav2_behaviors::Wait" + plugin: "nav2_behaviors::Wait" # In Iron and older versions, "/" was used instead of "::" .. Default Plugins *************** +.. note:: + In Iron and older versions, "/" was used instead of "::". When the :code:`behavior_plugins` parameter is not overridden, the following default plugins are loaded: @@ -359,15 +361,15 @@ Example cycle_frequency: 10.0 behavior_plugins: ["spin", "backup", "drive_on_heading", "wait", "assisted_teleop"] spin: - plugin: "nav2_behaviors::Spin" + plugin: "nav2_behaviors::Spin" # In Iron and older versions, "/" was used instead of "::" backup: - plugin: "nav2_behaviors::BackUp" + plugin: "nav2_behaviors::BackUp" # In Iron and older versions, "/" was used instead of "::" drive_on_heading: - plugin: "nav2_behaviors::DriveOnHeading" + plugin: "nav2_behaviors::DriveOnHeading" # In Iron and older versions, "/" was used instead of "::" wait: - plugin: "nav2_behaviors::Wait" + plugin: "nav2_behaviors::Wait" # In Iron and older versions, "/" was used instead of "::" assisted_teleop: - plugin: "nav2_behaviors::AssistedTeleop" + plugin: "nav2_behaviors::AssistedTeleop" # In Iron and older versions, "/" was used instead of "::" local_frame: odom global_frame: map robot_base_frame: base_link diff --git a/configuration/packages/configuring-bt-navigator.rst b/configuration/packages/configuring-bt-navigator.rst index 322cd4167..8788ce91e 100644 --- a/configuration/packages/configuring-bt-navigator.rst +++ b/configuration/packages/configuring-bt-navigator.rst @@ -246,9 +246,9 @@ Example path_blackboard_id: path navigators: ['navigate_to_pose', 'navigate_through_poses'] navigate_to_pose: - plugin: "nav2_bt_navigator::NavigateToPoseNavigator" + plugin: "nav2_bt_navigator::NavigateToPoseNavigator" # In Iron and older versions, "/" was used instead of "::" navigate_through_poses: - plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator" + plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator" # In Iron and older versions, "/" was used instead of "::" plugin_lib_names: - nav2_compute_path_to_pose_action_bt_node - nav2_follow_path_action_bt_node diff --git a/configuration/packages/configuring-navfn.rst b/configuration/packages/configuring-navfn.rst index d8c92e40c..517fad4e4 100644 --- a/configuration/packages/configuring-navfn.rst +++ b/configuration/packages/configuring-navfn.rst @@ -66,7 +66,7 @@ Example ros__parameters: planner_plugins: ['GridBased'] GridBased: - plugin: 'nav2_navfn_planner::NavfnPlanner' + plugin: 'nav2_navfn_planner::NavfnPlanner' # In Iron and older versions, "/" was used instead of "::" use_astar: True allow_unknown: True tolerance: 1.0 diff --git a/configuration/packages/configuring-planner-server.rst b/configuration/packages/configuring-planner-server.rst index 27d27d1b8..487d4e630 100644 --- a/configuration/packages/configuring-planner-server.rst +++ b/configuration/packages/configuring-planner-server.rst @@ -36,7 +36,7 @@ Parameters ros__parameters: planner_plugins: ["GridBased"] GridBased: - plugin: "nav2_navfn_planner::NavfnPlanner" + plugin: "nav2_navfn_planner::NavfnPlanner" # In Iron and older versions, "/" was used instead of "::" .. :expected_planner_frequency: @@ -84,4 +84,4 @@ Example expected_planner_frequency: 20.0 planner_plugins: ['GridBased'] GridBased: - plugin: 'nav2_navfn_planner::NavfnPlanner' + plugin: 'nav2_navfn_planner::NavfnPlanner' # In Iron and older versions, "/" was used instead of "::" diff --git a/configuration/packages/configuring-thetastar.rst b/configuration/packages/configuring-thetastar.rst index d61fcc24f..1e8405fbe 100644 --- a/configuration/packages/configuring-thetastar.rst +++ b/configuration/packages/configuring-thetastar.rst @@ -107,7 +107,7 @@ Example use_sim_time: True planner_plugins: ["GridBased"] GridBased: - plugin: "nav2_theta_star_planner::ThetaStarPlanner" + plugin: "nav2_theta_star_planner::ThetaStarPlanner" # In Iron and older versions, "/" was used instead of "::" how_many_corners: 8 w_euc_cost: 1.0 w_traversal_cost: 2.0 diff --git a/configuration/packages/smac/configuring-smac-2d.rst b/configuration/packages/smac/configuring-smac-2d.rst index 1186fe19e..fa2e6256a 100644 --- a/configuration/packages/smac/configuring-smac-2d.rst +++ b/configuration/packages/smac/configuring-smac-2d.rst @@ -179,7 +179,7 @@ Example use_sim_time: True GridBased: - plugin: "nav2_smac_planner::SmacPlanner2D" + plugin: "nav2_smac_planner::SmacPlanner2D" # In Iron and older versions, "/" was used instead of "::" tolerance: 0.125 # tolerance for planning if unable to reach exact pose, in meters downsample_costmap: false # whether or not to downsample the map downsampling_factor: 1 # multiplier for the resolution of the costmap layer (e.g. 2 on a 5cm costmap would be 10cm) diff --git a/configuration/packages/smac/configuring-smac-hybrid.rst b/configuration/packages/smac/configuring-smac-hybrid.rst index 94a0d2dd8..6619c6803 100644 --- a/configuration/packages/smac/configuring-smac-hybrid.rst +++ b/configuration/packages/smac/configuring-smac-hybrid.rst @@ -388,7 +388,7 @@ Example use_sim_time: True GridBased: - plugin: "nav2_smac_planner::SmacPlannerHybrid" + plugin: "nav2_smac_planner::SmacPlannerHybrid" # In Iron and older versions, "/" was used instead of "::" downsample_costmap: false # whether or not to downsample the map downsampling_factor: 1 # multiplier for the resolution of the costmap layer (e.g. 2 on a 5cm costmap would be 10cm) tolerance: 0.25 # dist-to-goal heuristic cost (distance) for valid tolerance endpoints if exact goal cannot be found. diff --git a/configuration/packages/smac/configuring-smac-lattice.rst b/configuration/packages/smac/configuring-smac-lattice.rst index 8b003b58b..33d88535c 100644 --- a/configuration/packages/smac/configuring-smac-lattice.rst +++ b/configuration/packages/smac/configuring-smac-lattice.rst @@ -338,7 +338,7 @@ Example use_sim_time: True GridBased: - plugin: "nav2_smac_planner::SmacPlannerLattice" + plugin: "nav2_smac_planner::SmacPlannerLattice" # In Iron and older versions, "/" was used instead of "::" allow_unknown: true # Allow traveling in unknown space tolerance: 0.25 # dist-to-goal heuristic cost (distance) for valid tolerance endpoints if exact goal cannot be found. max_iterations: 1000000 # Maximum total iterations to search for before failing (in case unreachable), set to -1 to disable diff --git a/plugin_tutorials/docs/writing_new_behavior_plugin.rst b/plugin_tutorials/docs/writing_new_behavior_plugin.rst index 4ab8f8ba0..d08efdfc9 100644 --- a/plugin_tutorials/docs/writing_new_behavior_plugin.rst +++ b/plugin_tutorials/docs/writing_new_behavior_plugin.rst @@ -211,11 +211,11 @@ To enable the plugin, we need to modify the ``nav2_params.yaml`` file as below t behavior_plugins: ["spin", "backup", "wait"] # Humble and later recovery_plugins: ["spin", "backup", "wait"] # Galactic and earlier spin: - plugin: "nav2_behaviors::Spin" + plugin: "nav2_behaviors::Spin" # In Iron and older versions, "/" was used instead of "::" backup: - plugin: "nav2_behaviors::BackUp" + plugin: "nav2_behaviors::BackUp" # In Iron and older versions, "/" was used instead of "::" wait: - plugin: "nav2_behaviors::Wait" + plugin: "nav2_behaviors::Wait" # In Iron and older versions, "/" was used instead of "::" global_frame: odom robot_base_frame: base_link transform_timeout: 0.1 @@ -240,13 +240,13 @@ with behavior_plugins: ["spin", "backup", "wait","send_sms"] # Humble and newer recovery_plugins: ["spin", "backup", "wait","send_sms"] # Galactic and earlier spin: - plugin: "nav2_behaviors::Spin" + plugin: "nav2_behaviors::Spin" # In Iron and older versions, "/" was used instead of "::" backup: - plugin: "nav2_behaviors::BackUp" + plugin: "nav2_behaviors::BackUp" # In Iron and older versions, "/" was used instead of "::" wait: - plugin: "nav2_behaviors::Wait" + plugin: "nav2_behaviors::Wait" # In Iron and older versions, "/" was used instead of "::" send_sms: - plugin: "nav2_sms_behavior::SendSms" + plugin: "nav2_sms_behavior::SendSms" # In Iron and older versions, "/" was used instead of "::" account_sid: ... # your sid auth_token: ... # your token from_number: ... # your number diff --git a/plugin_tutorials/docs/writing_new_costmap2d_plugin.rst b/plugin_tutorials/docs/writing_new_costmap2d_plugin.rst index 94ca09250..d74926636 100644 --- a/plugin_tutorials/docs/writing_new_costmap2d_plugin.rst +++ b/plugin_tutorials/docs/writing_new_costmap2d_plugin.rst @@ -223,11 +223,11 @@ In this case each plugin object will be handled by its own parameters tree in a .. code-block:: text gradient_layer_1: - plugin: nav2_gradient_costmap_plugin::GradientLayer + plugin: nav2_gradient_costmap_plugin::GradientLayer # In Iron and older versions, "/" was used instead of "::" enabled: True ... gradient_layer_2: - plugin: nav2_gradient_costmap_plugin::GradientLayer + plugin: nav2_gradient_costmap_plugin::GradientLayer # In Iron and older versions, "/" was used instead of "::" enabled: False ... diff --git a/plugin_tutorials/docs/writing_new_nav2controller_plugin.rst b/plugin_tutorials/docs/writing_new_nav2controller_plugin.rst index 2e2368fd6..56eaad958 100644 --- a/plugin_tutorials/docs/writing_new_nav2controller_plugin.rst +++ b/plugin_tutorials/docs/writing_new_nav2controller_plugin.rst @@ -265,7 +265,7 @@ To enable the plugin, we need to modify the ``nav2_params.yaml`` file as below controller_plugins: ["FollowPath"] FollowPath: - plugin: "nav2_pure_pursuit_controller::PurePursuitController" + plugin: "nav2_pure_pursuit_controller::PurePursuitController" # In Iron and older versions, "/" was used instead of "::" debug_trajectory_details: True desired_linear_vel: 0.2 lookahead_dist: 0.4 diff --git a/plugin_tutorials/docs/writing_new_nav2planner_plugin.rst b/plugin_tutorials/docs/writing_new_nav2planner_plugin.rst index 6a6c75d18..48c8722da 100644 --- a/plugin_tutorials/docs/writing_new_nav2planner_plugin.rst +++ b/plugin_tutorials/docs/writing_new_nav2planner_plugin.rst @@ -200,7 +200,7 @@ To enable the plugin, we need to modify the ``nav2_params.yaml`` file as below t plugins: ["GridBased"] use_sim_time: True GridBased: - plugin: "nav2_navfn_planner::NavfnPlanner" # For Foxy and later + plugin: "nav2_navfn_planner::NavfnPlanner" # For Foxy and later. In Iron and older versions, "/" was used instead of "::" tolerance: 2.0 use_astar: false allow_unknown: true diff --git a/plugin_tutorials/docs/writing_new_navigator_plugin.rst b/plugin_tutorials/docs/writing_new_navigator_plugin.rst index 859557ddb..c5b92eb84 100644 --- a/plugin_tutorials/docs/writing_new_navigator_plugin.rst +++ b/plugin_tutorials/docs/writing_new_navigator_plugin.rst @@ -332,9 +332,9 @@ To enable the plugin, we need to modify the ``nav2_params.yaml`` file as below path_blackboard_id: path navigators: ['navigate_to_pose', 'navigate_through_poses'] navigate_to_pose: - plugin: "nav2_bt_navigator::NavigateToPoseNavigator" + plugin: "nav2_bt_navigator::NavigateToPoseNavigator" # In Iron and older versions, "/" was used instead of "::" navigate_through_poses: - plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator" + plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator" # In Iron and older versions, "/" was used instead of "::" In the above snippet, you can observe the mapping of our ``nav2_bt_navigator::NavigateToPoseNavigator`` plugin to its id ``navigate_to_pose``. diff --git a/setup_guides/algorithm/select_algorithm.rst b/setup_guides/algorithm/select_algorithm.rst index 1c7b61224..7d8f082ea 100644 --- a/setup_guides/algorithm/select_algorithm.rst +++ b/setup_guides/algorithm/select_algorithm.rst @@ -66,7 +66,7 @@ Example Configuration ros__parameters: planner_plugins: ['GridBased'] GridBased: - plugin: 'nav2_navfn_planner::NavfnPlanner' + plugin: 'nav2_navfn_planner::NavfnPlanner' # In Iron and older versions, "/" was used instead of "::" An example configuration of the planner server is shown above. The ``planner_plugins`` parameter accepts a list of mapped planner plugin names. For each plugin namespace defined in ``planner_plugins`` (``GridBased`` in our example), we specify the type of plugin to be loaded in the ``plugin`` parameter. Additional configurations must then be specified in this namespace based on the algorithm to be used. Please see the `Configuration Guide `_ for more details. From fa054d54824ceb628d046c00fb1c11eb46e83b92 Mon Sep 17 00:00:00 2001 From: Alan Xue Date: Sat, 30 Mar 2024 02:09:30 +0000 Subject: [PATCH 7/7] List of Plugins Affected by Naming Standardization --- migration/Iron.rst | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/migration/Iron.rst b/migration/Iron.rst index 6f8265b94..8017796c3 100644 --- a/migration/Iron.rst +++ b/migration/Iron.rst @@ -307,4 +307,11 @@ New graceful cancellation API for Controllers Standardization of Plugin Naming with Double Colons (::) ******************************************************** -`PR #4220 `_ standardizes plugin naming to use double colons (::), replacing the previous mixed use of slashes (/) and double colons. + +`PR #4220`_ standardizes plugin naming across the Navigation2 package to use double colons (::), replacing the previous mixed use of slashes (/) and double colons. Affected plugins include: + +- Behavior Server: ``nav2_behaviors::Spin``, ``nav2_behaviors::BackUp``, ``nav2_behaviors::DriveOnHeading``, ``nav2_behaviors::Wait``, ``nav2_behaviors::AssistedTeleop`` +- Planner Server: ``nav2_navfn_planner::NavfnPlanner``, ``nav2_smac_planner::SmacPlanner2D``, ``nav2_smac_planner::SmacPlannerHybrid``, ``nav2_theta_star_planner::ThetaStarPlanner`` +- Controller Server: ``nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController``, ``nav2_dwb_controller::DWBLocalPlanner`` +- BT Navigator: ``nav2_bt_navigator::NavigateToPoseNavigator``, ``nav2_bt_navigator::NavigateThroughPosesNavigator`` +