Skip to content

Commit

Permalink
Refactor the plugin names for planner_server to use double colons
Browse files Browse the repository at this point in the history
  • Loading branch information
alanxuefei committed Mar 27, 2024
1 parent cd6fc03 commit 00913b3
Show file tree
Hide file tree
Showing 17 changed files with 61 additions and 61 deletions.
2 changes: 1 addition & 1 deletion nav2_bringup/params/nav2_multirobot_params_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/params/nav2_multirobot_params_2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/params/nav2_multirobot_params_all.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -231,7 +231,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
Expand Down
2 changes: 1 addition & 1 deletion nav2_navfn_planner/global_planner_plugin.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<library path="nav2_navfn_planner">
<class name="nav2_navfn_planner/NavfnPlanner" type="nav2_navfn_planner::NavfnPlanner" base_class_type="nav2_core::GlobalPlanner">
<class name=type="nav2_navfn_planner::NavfnPlanner" base_class_type="nav2_core::GlobalPlanner">
<description></description>
</class>
</library>
2 changes: 1 addition & 1 deletion nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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");
Expand Down
2 changes: 1 addition & 1 deletion nav2_smac_planner/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion nav2_system_tests/src/costmap_filters/keepout_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
70 changes: 35 additions & 35 deletions nav2_system_tests/src/planning/test_planner_plugins.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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");
}


Expand Down
14 changes: 7 additions & 7 deletions nav2_system_tests/src/system/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand All @@ -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
Expand All @@ -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
Expand All @@ -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
Expand All @@ -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
Expand All @@ -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
# )
2 changes: 1 addition & 1 deletion nav2_theta_star_planner/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion nav2_theta_star_planner/theta_star_planner.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<library path="nav2_theta_star_planner">
<class name="nav2_theta_star_planner/ThetaStarPlanner" type="nav2_theta_star_planner::ThetaStarPlanner" base_class_type="nav2_core::GlobalPlanner">
<class type="nav2_theta_star_planner::ThetaStarPlanner" base_class_type="nav2_core::GlobalPlanner">
<description>An implementation of the Theta* Algorithm</description>
</class>
</library>
Loading

0 comments on commit 00913b3

Please sign in to comment.