Skip to content

Commit

Permalink
Refactor plugins to use double colons for consistency (ros-navigation…
Browse files Browse the repository at this point in the history
…#4220)

* Refactor the plugin names for bt_navigator to use double colons

Signed-off-by: Alan Xue <[email protected]>

* Refactor the plugin names for planner_server to use double colons

Signed-off-by: Alan Xue <[email protected]>

* Refactor the plugin names for behavior_server to use double colons

Signed-off-by: Alan Xue <[email protected]>

---------

Signed-off-by: Alan Xue <[email protected]>
  • Loading branch information
alanxuefei authored Apr 2, 2024
1 parent 2ecc91e commit b0e6d3d
Show file tree
Hide file tree
Showing 24 changed files with 120 additions and 122 deletions.
10 changes: 5 additions & 5 deletions nav2_behaviors/behavior_plugin.xml
Original file line number Diff line number Diff line change
@@ -1,30 +1,30 @@
<class_libraries>
<library path="nav2_spin_behavior">
<class name="nav2_behaviors/Spin" type="nav2_behaviors::Spin" base_class_type="nav2_core::Behavior">
<class type="nav2_behaviors::Spin" base_class_type="nav2_core::Behavior">
<description></description>
</class>
</library>

<library path="nav2_back_up_behavior">
<class name="nav2_behaviors/BackUp" type="nav2_behaviors::BackUp" base_class_type="nav2_core::Behavior">
<class type="nav2_behaviors::BackUp" base_class_type="nav2_core::Behavior">
<description></description>
</class>
</library>

<library path="nav2_drive_on_heading_behavior">
<class name="nav2_behaviors/DriveOnHeading" type="nav2_behaviors::DriveOnHeading&lt;&gt;" base_class_type="nav2_core::Behavior">
<class name="nav2_behaviors::DriveOnHeading" type="nav2_behaviors::DriveOnHeading&lt;&gt;" base_class_type="nav2_core::Behavior">
<description></description>
</class>
</library>

<library path="nav2_wait_behavior">
<class name="nav2_behaviors/Wait" type="nav2_behaviors::Wait" base_class_type="nav2_core::Behavior">
<class type="nav2_behaviors::Wait" base_class_type="nav2_core::Behavior">
<description></description>
</class>
</library>

<library path="nav2_assisted_teleop_behavior">
<class name="nav2_behaviors/AssistedTeleop" type="nav2_behaviors::AssistedTeleop" base_class_type="nav2_core::Behavior">
<class type="nav2_behaviors::AssistedTeleop" base_class_type="nav2_core::Behavior">
<description></description>
</class>
</library>
Expand Down
8 changes: 4 additions & 4 deletions nav2_behaviors/src/behavior_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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",
Expand Down
14 changes: 7 additions & 7 deletions nav2_bringup/params/nav2_multirobot_params_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down 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 All @@ -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
Expand Down
14 changes: 7 additions & 7 deletions nav2_bringup/params/nav2_multirobot_params_2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down 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 All @@ -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
Expand Down
16 changes: 8 additions & 8 deletions nav2_bringup/params/nav2_multirobot_params_all.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down 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 All @@ -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
Expand Down
16 changes: 8 additions & 8 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand All @@ -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
Expand Down
2 changes: 0 additions & 2 deletions nav2_bt_navigator/navigator_plugins.xml
Original file line number Diff line number Diff line change
@@ -1,15 +1,13 @@
<class_libraries>
<library path="nav2_navigate_to_pose_navigator">
<class
name="nav2_bt_navigator/NavigateToPoseNavigator"
type="nav2_bt_navigator::NavigateToPoseNavigator"
base_class_type="nav2_core::NavigatorBase">
<description>Navigate to Pose Navigator</description>
</class>
</library>
<library path="nav2_navigate_through_poses">
<class
name="nav2_bt_navigator/NavigateThroughPosesNavigator"
type="nav2_bt_navigator::NavigateThroughPosesNavigator"
base_class_type="nav2_core::NavigatorBase">
<description>Navigate through Poses Navigator</description>
Expand Down
4 changes: 2 additions & 2 deletions nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,8 +98,8 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/)
"navigate_through_poses"
};
const std::vector<std::string> default_navigator_types = {
"nav2_bt_navigator/NavigateToPoseNavigator",
"nav2_bt_navigator/NavigateThroughPosesNavigator"
"nav2_bt_navigator::NavigateToPoseNavigator",
"nav2_bt_navigator::NavigateThroughPosesNavigator"
};

std::vector<std::string> navigator_ids;
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 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_smac_planner/smac_plugin_2d.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<library path="nav2_smac_planner_2d">
<class name="nav2_smac_planner/SmacPlanner2D" type="nav2_smac_planner::SmacPlanner2D" base_class_type="nav2_core::GlobalPlanner">
<class type="nav2_smac_planner::SmacPlanner2D" base_class_type="nav2_core::GlobalPlanner">
<description>2D A* SMAC Planner</description>
</class>
</library>
2 changes: 1 addition & 1 deletion nav2_smac_planner/smac_plugin_hybrid.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<library path="nav2_smac_planner">
<class name="nav2_smac_planner/SmacPlannerHybrid" type="nav2_smac_planner::SmacPlannerHybrid" base_class_type="nav2_core::GlobalPlanner">
<class type="nav2_smac_planner::SmacPlannerHybrid" base_class_type="nav2_core::GlobalPlanner">
<description>Hybrid-A* SMAC planner</description>
</class>
</library>
2 changes: 1 addition & 1 deletion nav2_smac_planner/smac_plugin_lattice.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<library path="nav2_smac_planner_lattice">
<class name="nav2_smac_planner/SmacPlannerLattice" type="nav2_smac_planner::SmacPlannerLattice" base_class_type="nav2_core::GlobalPlanner">
<class type="nav2_smac_planner::SmacPlannerLattice" base_class_type="nav2_core::GlobalPlanner">
<description>State Lattice SMAC planner</description>
</class>
</library>
10 changes: 5 additions & 5 deletions 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 All @@ -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
Expand Down
10 changes: 5 additions & 5 deletions nav2_system_tests/src/costmap_filters/speed_global_params.yaml
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 All @@ -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
Expand Down
10 changes: 5 additions & 5 deletions nav2_system_tests/src/costmap_filters/speed_local_params.yaml
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 All @@ -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
Expand Down
Loading

0 comments on commit b0e6d3d

Please sign in to comment.