diff --git a/nav2_behaviors/behavior_plugin.xml b/nav2_behaviors/behavior_plugin.xml index cd20ae7aa9..8d206e79b8 100644 --- a/nav2_behaviors/behavior_plugin.xml +++ b/nav2_behaviors/behavior_plugin.xml @@ -1,30 +1,30 @@ - + - + - + - + - + diff --git a/nav2_behaviors/src/behavior_server.cpp b/nav2_behaviors/src/behavior_server.cpp index c7beffd786..706055161b 100644 --- a/nav2_behaviors/src/behavior_server.cpp +++ b/nav2_behaviors/src/behavior_server.cpp @@ -26,10 +26,10 @@ BehaviorServer::BehaviorServer(const rclcpp::NodeOptions & options) : LifecycleNode("behavior_server", "", options), plugin_loader_("nav2_core", "nav2_core::Behavior"), default_ids_{"spin", "backup", "drive_on_heading", "wait"}, - default_types_{"nav2_behaviors/Spin", - "nav2_behaviors/BackUp", - "nav2_behaviors/DriveOnHeading", - "nav2_behaviors/Wait"} + default_types_{"nav2_behaviors::Spin", + "nav2_behaviors::BackUp", + "nav2_behaviors::DriveOnHeading", + "nav2_behaviors::Wait"} { declare_parameter( "local_costmap_topic", diff --git a/nav2_bringup/params/nav2_multirobot_params_1.yaml b/nav2_bringup/params/nav2_multirobot_params_1.yaml index 91401fc21f..85be4769c4 100644 --- a/nav2_bringup/params/nav2_multirobot_params_1.yaml +++ b/nav2_bringup/params/nav2_multirobot_params_1.yaml @@ -49,9 +49,9 @@ bt_navigator: action_server_result_timeout: 900.0 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" # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml @@ -201,7 +201,7 @@ planner_server: ros__parameters: planner_plugins: ["GridBased"] GridBased: - plugin: "nav2_navfn_planner/NavfnPlanner" + plugin: "nav2_navfn_planner::NavfnPlanner" tolerance: 0.5 use_astar: false allow_unknown: true @@ -213,13 +213,13 @@ behavior_server: cycle_frequency: 10.0 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" global_frame: odom robot_base_frame: base_link transform_tolerance: 0.1 diff --git a/nav2_bringup/params/nav2_multirobot_params_2.yaml b/nav2_bringup/params/nav2_multirobot_params_2.yaml index 732fa24eb1..7ab3d0e335 100644 --- a/nav2_bringup/params/nav2_multirobot_params_2.yaml +++ b/nav2_bringup/params/nav2_multirobot_params_2.yaml @@ -49,9 +49,9 @@ bt_navigator: action_server_result_timeout: 900.0 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" # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml @@ -200,7 +200,7 @@ planner_server: ros__parameters: planner_plugins: ["GridBased"] GridBased: - plugin: "nav2_navfn_planner/NavfnPlanner" + plugin: "nav2_navfn_planner::NavfnPlanner" tolerance: 0.5 use_astar: false allow_unknown: true @@ -212,13 +212,13 @@ behavior_server: cycle_frequency: 10.0 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" global_frame: odom robot_base_frame: base_link transform_tolerance: 0.1 diff --git a/nav2_bringup/params/nav2_multirobot_params_all.yaml b/nav2_bringup/params/nav2_multirobot_params_all.yaml index bb812d276b..a61faf1d21 100644 --- a/nav2_bringup/params/nav2_multirobot_params_all.yaml +++ b/nav2_bringup/params/nav2_multirobot_params_all.yaml @@ -49,9 +49,9 @@ bt_navigator: action_server_result_timeout: 900.0 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" # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml @@ -234,7 +234,7 @@ planner_server: expected_planner_frequency: 20.0 planner_plugins: ["GridBased"] GridBased: - plugin: "nav2_navfn_planner/NavfnPlanner" + plugin: "nav2_navfn_planner::NavfnPlanner" tolerance: 0.5 use_astar: false allow_unknown: true @@ -257,15 +257,15 @@ behavior_server: cycle_frequency: 10.0 behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "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" assisted_teleop: - plugin: "nav2_behaviors/AssistedTeleop" + plugin: "nav2_behaviors::AssistedTeleop" local_frame: odom global_frame: map robot_base_frame: base_link diff --git a/nav2_bringup/params/nav2_params.yaml b/nav2_bringup/params/nav2_params.yaml index 703151959a..3ac25d13bb 100644 --- a/nav2_bringup/params/nav2_params.yaml +++ b/nav2_bringup/params/nav2_params.yaml @@ -49,9 +49,9 @@ bt_navigator: action_server_result_timeout: 900.0 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" # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml @@ -273,7 +273,7 @@ planner_server: expected_planner_frequency: 20.0 planner_plugins: ["GridBased"] GridBased: - plugin: "nav2_navfn_planner/NavfnPlanner" + plugin: "nav2_navfn_planner::NavfnPlanner" tolerance: 0.5 use_astar: false allow_unknown: true @@ -296,15 +296,15 @@ behavior_server: cycle_frequency: 10.0 behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "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" assisted_teleop: - plugin: "nav2_behaviors/AssistedTeleop" + plugin: "nav2_behaviors::AssistedTeleop" local_frame: odom global_frame: map robot_base_frame: base_link diff --git a/nav2_bt_navigator/navigator_plugins.xml b/nav2_bt_navigator/navigator_plugins.xml index e00a0c2969..65fa3b6141 100644 --- a/nav2_bt_navigator/navigator_plugins.xml +++ b/nav2_bt_navigator/navigator_plugins.xml @@ -1,7 +1,6 @@ Navigate to Pose Navigator @@ -9,7 +8,6 @@ Navigate through Poses Navigator diff --git a/nav2_bt_navigator/src/bt_navigator.cpp b/nav2_bt_navigator/src/bt_navigator.cpp index 4c1b4f47bc..8025a5e278 100644 --- a/nav2_bt_navigator/src/bt_navigator.cpp +++ b/nav2_bt_navigator/src/bt_navigator.cpp @@ -98,8 +98,8 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/) "navigate_through_poses" }; const std::vector default_navigator_types = { - "nav2_bt_navigator/NavigateToPoseNavigator", - "nav2_bt_navigator/NavigateThroughPosesNavigator" + "nav2_bt_navigator::NavigateToPoseNavigator", + "nav2_bt_navigator::NavigateThroughPosesNavigator" }; std::vector navigator_ids; diff --git a/nav2_navfn_planner/global_planner_plugin.xml b/nav2_navfn_planner/global_planner_plugin.xml index 25bb27e09f..55523dce4c 100644 --- a/nav2_navfn_planner/global_planner_plugin.xml +++ b/nav2_navfn_planner/global_planner_plugin.xml @@ -1,5 +1,5 @@ - + diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index 1933d38cb6..c5234d8d44 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -44,7 +44,7 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options) : nav2_util::LifecycleNode("planner_server", "", options), gp_loader_("nav2_core", "nav2_core::GlobalPlanner"), default_ids_{"GridBased"}, - default_types_{"nav2_navfn_planner/NavfnPlanner"}, + default_types_{"nav2_navfn_planner::NavfnPlanner"}, costmap_(nullptr) { RCLCPP_INFO(get_logger(), "Creating"); diff --git a/nav2_smac_planner/README.md b/nav2_smac_planner/README.md index a9f59c4e6a..78adee940b 100644 --- a/nav2_smac_planner/README.md +++ b/nav2_smac_planner/README.md @@ -102,7 +102,7 @@ planner_server: planner_plugins: ["GridBased"] GridBased: - plugin: "nav2_smac_planner/SmacPlannerHybrid" + plugin: "nav2_smac_planner::SmacPlannerHybrid" tolerance: 0.5 # 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/nav2_smac_planner/smac_plugin_2d.xml b/nav2_smac_planner/smac_plugin_2d.xml index 5bae687472..05c6bdb816 100644 --- a/nav2_smac_planner/smac_plugin_2d.xml +++ b/nav2_smac_planner/smac_plugin_2d.xml @@ -1,5 +1,5 @@ - + 2D A* SMAC Planner diff --git a/nav2_smac_planner/smac_plugin_hybrid.xml b/nav2_smac_planner/smac_plugin_hybrid.xml index 7b52bb24d7..dec7fd1b7f 100644 --- a/nav2_smac_planner/smac_plugin_hybrid.xml +++ b/nav2_smac_planner/smac_plugin_hybrid.xml @@ -1,5 +1,5 @@ - + Hybrid-A* SMAC planner diff --git a/nav2_smac_planner/smac_plugin_lattice.xml b/nav2_smac_planner/smac_plugin_lattice.xml index 34149230f4..0cfe8c70c3 100644 --- a/nav2_smac_planner/smac_plugin_lattice.xml +++ b/nav2_smac_planner/smac_plugin_lattice.xml @@ -1,5 +1,5 @@ - + State Lattice SMAC planner diff --git a/nav2_system_tests/src/costmap_filters/keepout_params.yaml b/nav2_system_tests/src/costmap_filters/keepout_params.yaml index 9f9bdd33de..3fbc48f3c0 100644 --- a/nav2_system_tests/src/costmap_filters/keepout_params.yaml +++ b/nav2_system_tests/src/costmap_filters/keepout_params.yaml @@ -216,7 +216,7 @@ planner_server: expected_planner_frequency: 20.0 planner_plugins: ["GridBased"] GridBased: - plugin: "nav2_navfn_planner/NavfnPlanner" + plugin: "nav2_navfn_planner::NavfnPlanner" tolerance: 0.5 use_astar: False allow_unknown: True @@ -228,13 +228,13 @@ behavior_server: cycle_frequency: 10.0 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" global_frame: odom robot_base_frame: base_link transform_tolerance: 0.1 diff --git a/nav2_system_tests/src/costmap_filters/speed_global_params.yaml b/nav2_system_tests/src/costmap_filters/speed_global_params.yaml index 10040d8798..47494a296d 100644 --- a/nav2_system_tests/src/costmap_filters/speed_global_params.yaml +++ b/nav2_system_tests/src/costmap_filters/speed_global_params.yaml @@ -206,7 +206,7 @@ planner_server: expected_planner_frequency: 20.0 planner_plugins: ["GridBased"] GridBased: - plugin: "nav2_navfn_planner/NavfnPlanner" + plugin: "nav2_navfn_planner::NavfnPlanner" tolerance: 0.5 use_astar: False allow_unknown: True @@ -218,13 +218,13 @@ behavior_server: cycle_frequency: 10.0 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" global_frame: odom robot_base_frame: base_link transform_tolerance: 0.1 diff --git a/nav2_system_tests/src/costmap_filters/speed_local_params.yaml b/nav2_system_tests/src/costmap_filters/speed_local_params.yaml index b50108a13f..b0903c9a33 100644 --- a/nav2_system_tests/src/costmap_filters/speed_local_params.yaml +++ b/nav2_system_tests/src/costmap_filters/speed_local_params.yaml @@ -206,7 +206,7 @@ planner_server: expected_planner_frequency: 20.0 planner_plugins: ["GridBased"] GridBased: - plugin: "nav2_navfn_planner/NavfnPlanner" + plugin: "nav2_navfn_planner::NavfnPlanner" tolerance: 0.5 use_astar: False allow_unknown: True @@ -218,13 +218,13 @@ behavior_server: cycle_frequency: 10.0 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" global_frame: odom robot_base_frame: base_link transform_tolerance: 0.1 diff --git a/nav2_system_tests/src/gps_navigation/nav2_no_map_params.yaml b/nav2_system_tests/src/gps_navigation/nav2_no_map_params.yaml index 6e9f3f490b..96dc593d82 100644 --- a/nav2_system_tests/src/gps_navigation/nav2_no_map_params.yaml +++ b/nav2_system_tests/src/gps_navigation/nav2_no_map_params.yaml @@ -8,9 +8,9 @@ bt_navigator: wait_for_service_timeout: 1000 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" # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml @@ -195,7 +195,7 @@ planner_server: expected_planner_frequency: 20.0 planner_plugins: ["GridBased"] GridBased: - plugin: "nav2_navfn_planner/NavfnPlanner" + plugin: "nav2_navfn_planner::NavfnPlanner" tolerance: 0.5 use_astar: false allow_unknown: true @@ -218,15 +218,15 @@ behavior_server: cycle_frequency: 10.0 behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "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" assisted_teleop: - plugin: "nav2_behaviors/AssistedTeleop" + plugin: "nav2_behaviors::AssistedTeleop" local_frame: odom global_frame: map robot_base_frame: base_link diff --git a/nav2_system_tests/src/planning/test_planner_plugins.cpp b/nav2_system_tests/src/planning/test_planner_plugins.cpp index 01d264006a..0ae08f4fa9 100644 --- a/nav2_system_tests/src/planning/test_planner_plugins.cpp +++ b/nav2_system_tests/src/planning/test_planner_plugins.cpp @@ -180,177 +180,177 @@ TEST(testPluginMap, Failures) TEST(testPluginMap, Smac2dEqualStartGoal) { - testSmallPathValidityAndOrientation("nav2_smac_planner/SmacPlanner2D", 0.0); + testSmallPathValidityAndOrientation("nav2_smac_planner::SmacPlanner2D", 0.0); } TEST(testPluginMap, Smac2dEqualStartGoalN) { - testSmallPathValidityAndNoOrientation("nav2_smac_planner/SmacPlanner2D", 0.0); + testSmallPathValidityAndNoOrientation("nav2_smac_planner::SmacPlanner2D", 0.0); } TEST(testPluginMap, Smac2dVerySmallPath) { - testSmallPathValidityAndOrientation("nav2_smac_planner/SmacPlanner2D", 0.00001); + testSmallPathValidityAndOrientation("nav2_smac_planner::SmacPlanner2D", 0.00001); } TEST(testPluginMap, Smac2dVerySmallPathN) { - testSmallPathValidityAndNoOrientation("nav2_smac_planner/SmacPlanner2D", 0.00001); + testSmallPathValidityAndNoOrientation("nav2_smac_planner::SmacPlanner2D", 0.00001); } TEST(testPluginMap, Smac2dBelowCostmapResolution) { - testSmallPathValidityAndOrientation("nav2_smac_planner/SmacPlanner2D", 0.09); + testSmallPathValidityAndOrientation("nav2_smac_planner::SmacPlanner2D", 0.09); } TEST(testPluginMap, Smac2dBelowCostmapResolutionN) { - testSmallPathValidityAndNoOrientation("nav2_smac_planner/SmacPlanner2D", 0.09); + testSmallPathValidityAndNoOrientation("nav2_smac_planner::SmacPlanner2D", 0.09); } TEST(testPluginMap, Smac2dJustAboveCostmapResolution) { - testSmallPathValidityAndOrientation("nav2_smac_planner/SmacPlanner2D", 0.102); + testSmallPathValidityAndOrientation("nav2_smac_planner::SmacPlanner2D", 0.102); } TEST(testPluginMap, Smac2dJustAboveCostmapResolutionN) { - testSmallPathValidityAndNoOrientation("nav2_smac_planner/SmacPlanner2D", 0.102); + testSmallPathValidityAndNoOrientation("nav2_smac_planner::SmacPlanner2D", 0.102); } TEST(testPluginMap, Smac2dAboveCostmapResolution) { - testSmallPathValidityAndOrientation("nav2_smac_planner/SmacPlanner2D", 1.5); + testSmallPathValidityAndOrientation("nav2_smac_planner::SmacPlanner2D", 1.5); } TEST(testPluginMap, Smac2dAboveCostmapResolutionN) { - testSmallPathValidityAndNoOrientation("nav2_smac_planner/SmacPlanner2D", 1.5); + testSmallPathValidityAndNoOrientation("nav2_smac_planner::SmacPlanner2D", 1.5); } TEST(testPluginMap, NavFnEqualStartGoal) { - testSmallPathValidityAndOrientation("nav2_navfn_planner/NavfnPlanner", 0.0); + testSmallPathValidityAndOrientation("nav2_navfn_planner::NavfnPlanner", 0.0); } TEST(testPluginMap, NavFnEqualStartGoalN) { - testSmallPathValidityAndNoOrientation("nav2_navfn_planner/NavfnPlanner", 0.0); + testSmallPathValidityAndNoOrientation("nav2_navfn_planner::NavfnPlanner", 0.0); } TEST(testPluginMap, NavFnVerySmallPath) { - testSmallPathValidityAndOrientation("nav2_navfn_planner/NavfnPlanner", 0.00001); + testSmallPathValidityAndOrientation("nav2_navfn_planner::NavfnPlanner", 0.00001); } TEST(testPluginMap, NavFnVerySmallPathN) { - testSmallPathValidityAndNoOrientation("nav2_navfn_planner/NavfnPlanner", 0.00001); + testSmallPathValidityAndNoOrientation("nav2_navfn_planner::NavfnPlanner", 0.00001); } TEST(testPluginMap, NavFnBelowCostmapResolution) { - testSmallPathValidityAndOrientation("nav2_navfn_planner/NavfnPlanner", 0.09); + testSmallPathValidityAndOrientation("nav2_navfn_planner::NavfnPlanner", 0.09); } TEST(testPluginMap, NavFnBelowCostmapResolutionN) { - testSmallPathValidityAndNoOrientation("nav2_navfn_planner/NavfnPlanner", 0.09); + testSmallPathValidityAndNoOrientation("nav2_navfn_planner::NavfnPlanner", 0.09); } TEST(testPluginMap, NavFnJustAboveCostmapResolution) { - testSmallPathValidityAndOrientation("nav2_navfn_planner/NavfnPlanner", 0.102); + testSmallPathValidityAndOrientation("nav2_navfn_planner::NavfnPlanner", 0.102); } TEST(testPluginMap, NavFnJustAboveCostmapResolutionN) { - testSmallPathValidityAndNoOrientation("nav2_navfn_planner/NavfnPlanner", 0.102); + testSmallPathValidityAndNoOrientation("nav2_navfn_planner::NavfnPlanner", 0.102); } TEST(testPluginMap, NavFnAboveCostmapResolution) { - testSmallPathValidityAndOrientation("nav2_navfn_planner/NavfnPlanner", 1.5); + testSmallPathValidityAndOrientation("nav2_navfn_planner::NavfnPlanner", 1.5); } TEST(testPluginMap, NavFnAboveCostmapResolutionN) { - testSmallPathValidityAndNoOrientation("nav2_navfn_planner/NavfnPlanner", 1.5); + testSmallPathValidityAndNoOrientation("nav2_navfn_planner::NavfnPlanner", 1.5); } TEST(testPluginMap, ThetaStarEqualStartGoal) { - testSmallPathValidityAndOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.0); + testSmallPathValidityAndOrientation("nav2_theta_star_planner::ThetaStarPlanner", 0.0); } TEST(testPluginMap, ThetaStarEqualStartGoalN) { - testSmallPathValidityAndNoOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.0); + testSmallPathValidityAndNoOrientation("nav2_theta_star_planner::ThetaStarPlanner", 0.0); } TEST(testPluginMap, ThetaStarVerySmallPath) { - testSmallPathValidityAndOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.00001); + testSmallPathValidityAndOrientation("nav2_theta_star_planner::ThetaStarPlanner", 0.00001); } TEST(testPluginMap, ThetaStarVerySmallPathN) { - testSmallPathValidityAndNoOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.00001); + testSmallPathValidityAndNoOrientation("nav2_theta_star_planner::ThetaStarPlanner", 0.00001); } TEST(testPluginMap, ThetaStarBelowCostmapResolution) { - testSmallPathValidityAndOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.09); + testSmallPathValidityAndOrientation("nav2_theta_star_planner::ThetaStarPlanner", 0.09); } TEST(testPluginMap, ThetaStarBelowCostmapResolutionN) { - testSmallPathValidityAndNoOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.09); + testSmallPathValidityAndNoOrientation("nav2_theta_star_planner::ThetaStarPlanner", 0.09); } TEST(testPluginMap, ThetaStarJustAboveCostmapResolution) { - testSmallPathValidityAndOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.102); + testSmallPathValidityAndOrientation("nav2_theta_star_planner::ThetaStarPlanner", 0.102); } TEST(testPluginMap, ThetaStarJustAboveCostmapResolutionN) { - testSmallPathValidityAndNoOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.102); + testSmallPathValidityAndNoOrientation("nav2_theta_star_planner::ThetaStarPlanner", 0.102); } TEST(testPluginMap, ThetaStarAboveCostmapResolution) { - testSmallPathValidityAndOrientation("nav2_theta_star_planner/ThetaStarPlanner", 1.5); + testSmallPathValidityAndOrientation("nav2_theta_star_planner::ThetaStarPlanner", 1.5); } TEST(testPluginMap, ThetaStarAboveCostmapResolutionN) { - testSmallPathValidityAndNoOrientation("nav2_theta_star_planner/ThetaStarPlanner", 1.5); + testSmallPathValidityAndNoOrientation("nav2_theta_star_planner::ThetaStarPlanner", 1.5); } TEST(testPluginMap, NavFnCancel) { - testCancel("nav2_navfn_planner/NavfnPlanner"); + testCancel("nav2_navfn_planner::NavfnPlanner"); } TEST(testPluginMap, ThetaStarCancel) { - testCancel("nav2_theta_star_planner/ThetaStarPlanner"); + testCancel("nav2_theta_star_planner::ThetaStarPlanner"); } TEST(testPluginMap, Smac2dCancel) { - testCancel("nav2_smac_planner/SmacPlanner2D"); + testCancel("nav2_smac_planner::SmacPlanner2D"); } TEST(testPluginMap, SmacLatticeCancel) { - testCancel("nav2_smac_planner/SmacPlannerLattice"); + testCancel("nav2_smac_planner::SmacPlannerLattice"); } TEST(testPluginMap, SmacHybridAStarCancel) { - testCancel("nav2_smac_planner/SmacPlannerHybrid"); + testCancel("nav2_smac_planner::SmacPlannerHybrid"); } diff --git a/nav2_system_tests/src/system/CMakeLists.txt b/nav2_system_tests/src/system/CMakeLists.txt index fdd20a8d2d..39afa461c2 100644 --- a/nav2_system_tests/src/system/CMakeLists.txt +++ b/nav2_system_tests/src/system/CMakeLists.txt @@ -12,7 +12,7 @@ ament_add_test(test_bt_navigator TESTER=nav_to_pose_tester_node.py ASTAR=True CONTROLLER=nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController - PLANNER=nav2_navfn_planner/NavfnPlanner + PLANNER=nav2_navfn_planner::NavfnPlanner ) ament_add_test(test_bt_navigator_with_wrong_init_pose @@ -29,7 +29,7 @@ ament_add_test(test_bt_navigator_with_wrong_init_pose TESTER=nav_to_pose_tester_node.py ASTAR=True CONTROLLER=nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController - PLANNER=nav2_navfn_planner/NavfnPlanner + PLANNER=nav2_navfn_planner::NavfnPlanner ) ament_add_test(test_bt_navigator_with_dijkstra @@ -46,7 +46,7 @@ ament_add_test(test_bt_navigator_with_dijkstra TESTER=nav_to_pose_tester_node.py ASTAR=False CONTROLLER=dwb_core::DWBLocalPlanner - PLANNER=nav2_navfn_planner/NavfnPlanner + PLANNER=nav2_navfn_planner::NavfnPlanner ) ament_add_test(test_bt_navigator_2 @@ -63,7 +63,7 @@ ament_add_test(test_bt_navigator_2 TESTER=nav_to_pose_tester_node.py ASTAR=False CONTROLLER=dwb_core::DWBLocalPlanner - PLANNER=nav2_navfn_planner/NavfnPlanner + PLANNER=nav2_navfn_planner::NavfnPlanner ) ament_add_test(test_dynamic_obstacle @@ -80,7 +80,7 @@ ament_add_test(test_dynamic_obstacle TESTER=nav_to_pose_tester_node.py ASTAR=False CONTROLLER=dwb_core::DWBLocalPlanner - PLANNER=nav2_navfn_planner/NavfnPlanner + PLANNER=nav2_navfn_planner::NavfnPlanner ) ament_add_test(test_nav_through_poses @@ -97,7 +97,7 @@ ament_add_test(test_nav_through_poses TESTER=nav_through_poses_tester_node.py ASTAR=False CONTROLLER=dwb_core::DWBLocalPlanner - PLANNER=nav2_navfn_planner/NavfnPlanner + PLANNER=nav2_navfn_planner::NavfnPlanner ) # ament_add_test(test_multi_robot @@ -113,6 +113,6 @@ ament_add_test(test_nav_through_poses # TEST_SDF=${PROJECT_SOURCE_DIR}/models/turtlebot3_waffle/model.sdf # BT_NAVIGATOR_XML=navigate_to_pose_w_replanning_and_recovery.xml # CONTROLLER=dwb_core::DWBLocalPlanner -# PLANNER=nav2_navfn_planner/NavfnPlanner +# PLANNER=nav2_navfn_planner::NavfnPlanner # TESTER=nav_to_pose_tester_node.py # ) diff --git a/nav2_theta_star_planner/README.md b/nav2_theta_star_planner/README.md index 722957f841..831beebbb3 100644 --- a/nav2_theta_star_planner/README.md +++ b/nav2_theta_star_planner/README.md @@ -57,7 +57,7 @@ Below are the default values of the parameters : ``` planner_server: ros__parameters: - planner_plugin_types: ["nav2_theta_star_planner/ThetaStarPlanner"] + planner_plugin_types: ["nav2_theta_star_planner::ThetaStarPlanner"] planner_plugin_ids: ["GridBased"] GridBased: how_many_corners: 8 diff --git a/nav2_theta_star_planner/theta_star_planner.xml b/nav2_theta_star_planner/theta_star_planner.xml index 1890ab14c3..cea79b06e5 100644 --- a/nav2_theta_star_planner/theta_star_planner.xml +++ b/nav2_theta_star_planner/theta_star_planner.xml @@ -1,5 +1,5 @@ - + An implementation of the Theta* Algorithm diff --git a/tools/planner_benchmarking/README.md b/tools/planner_benchmarking/README.md index 69bc5ca45a..977d217436 100644 --- a/tools/planner_benchmarking/README.md +++ b/tools/planner_benchmarking/README.md @@ -10,15 +10,15 @@ planner_server: expected_planner_frequency: 20.0 planner_plugins: ["SmacHybrid", "Smac2d", "SmacLattice", "Navfn", "ThetaStar"] SmacHybrid: - plugin: "nav2_smac_planner/SmacPlannerHybrid" + plugin: "nav2_smac_planner::SmacPlannerHybrid" Smac2d: - plugin: "nav2_smac_planner/SmacPlanner2D" + plugin: "nav2_smac_planner::SmacPlanner2D" SmacLattice: - plugin: "nav2_smac_planner/SmacPlannerLattice" + plugin: "nav2_smac_planner::SmacPlannerLattice" Navfn: - plugin: "nav2_navfn_planner/NavfnPlanner" + plugin: "nav2_navfn_planner::NavfnPlanner" ThetaStar: - plugin: "nav2_theta_star_planner/ThetaStarPlanner" + plugin: "nav2_theta_star_planner::ThetaStarPlanner" ``` Set global costmap settings to those desired for benchmarking. The global map will be automatically set in the script. Inside of `metrics.py`, you can modify the map or set of planners to use. diff --git a/tools/smoother_benchmarking/README.md b/tools/smoother_benchmarking/README.md index aa9a5c83fe..d5334a51bd 100644 --- a/tools/smoother_benchmarking/README.md +++ b/tools/smoother_benchmarking/README.md @@ -18,7 +18,7 @@ planner_server: expected_planner_frequency: 20.0 planner_plugins: ["SmacHybrid"] SmacHybrid: - plugin: "nav2_smac_planner/SmacPlannerHybrid" + plugin: "nav2_smac_planner::SmacPlannerHybrid" tolerance: 0.5 motion_model_for_search: "DUBIN" # default, non-reverse motion smooth_path: false # should be disabled for experiment