Skip to content

Commit

Permalink
Selector plugin for selecting the planner and the controller (#4091)
Browse files Browse the repository at this point in the history
* initial commit

Signed-off-by: PRP <[email protected]>

* now dynamic reconfigurability also be achieved

Signed-off-by: PRP <[email protected]>

* updating the changes

Signed-off-by: PRP <[email protected]>

* fixing the mistake

Signed-off-by: PRP <[email protected]>

* adding default values for the selector

Signed-off-by: PRP <[email protected]>

* updating the plugin description

Signed-off-by: PRP <[email protected]>

* setting default in combox and removing after selected

Signed-off-by: PRP <[email protected]>

* minor

Signed-off-by: PRP <[email protected]>

* adding goal checker and smoother selectors to the plugins

Signed-off-by: PRP <[email protected]>

* updating all the relevant BTs

Signed-off-by: PRP <[email protected]>

* updating to 2x2 version

Signed-off-by: PRP <[email protected]>

* updating the bringup too

Signed-off-by: PRP <[email protected]>

* fixing the race condition

Signed-off-by: PRP <[email protected]>

* adding progress checker to the selector plugin

Signed-off-by: PRP <[email protected]>

* fixing CI

Signed-off-by: PRP <[email protected]>

* updating the cache version

Signed-off-by: PRP <[email protected]>

---------

Signed-off-by: PRP <[email protected]>
  • Loading branch information
padhupradheep authored Feb 9, 2024
1 parent 0cdabca commit 70dc1f9
Show file tree
Hide file tree
Showing 26 changed files with 421 additions and 27 deletions.
6 changes: 3 additions & 3 deletions .circleci/config.yml
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,12 @@ _commands:
- restore_cache:
name: Restore Cache << parameters.key >>
keys:
- "<< parameters.key >>-v19\
- "<< parameters.key >>-v20\
-{{ arch }}\
-{{ .Branch }}\
-{{ .Environment.CIRCLE_PR_NUMBER }}\
-{{ checksum \"<< parameters.workspace >>/lockfile.txt\" }}"
- "<< parameters.key >>-v19\
- "<< parameters.key >>-v20\
-{{ arch }}\
-main\
-<no value>\
Expand All @@ -58,7 +58,7 @@ _commands:
steps:
- save_cache:
name: Save Cache << parameters.key >>
key: "<< parameters.key >>-v19\
key: "<< parameters.key >>-v20\
-{{ arch }}\
-{{ .Branch }}\
-{{ .Environment.CIRCLE_PR_NUMBER }}\
Expand Down
2 changes: 2 additions & 0 deletions nav2_bringup/params/nav2_multirobot_params_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,8 @@ bt_navigator:
- nav2_assisted_teleop_cancel_bt_node
- nav2_drive_on_heading_cancel_bt_node
- nav2_is_battery_charging_condition_bt_node
- nav2_progress_checker_selector_bt_node
- nav2_smoother_selector_bt_node
error_code_names:
- compute_path_error_code
- follow_path_error_code
Expand Down
2 changes: 2 additions & 0 deletions nav2_bringup/params/nav2_multirobot_params_2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,8 @@ bt_navigator:
- nav2_assisted_teleop_cancel_bt_node
- nav2_drive_on_heading_cancel_bt_node
- nav2_is_battery_charging_condition_bt_node
- nav2_progress_checker_selector_bt_node
- nav2_smoother_selector_bt_node
error_code_names:
- compute_path_error_code
- follow_path_error_code
Expand Down
2 changes: 2 additions & 0 deletions nav2_bringup/params/nav2_multirobot_params_all.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,8 @@ bt_navigator:
- nav2_assisted_teleop_cancel_bt_node
- nav2_drive_on_heading_cancel_bt_node
- nav2_is_battery_charging_condition_bt_node
- nav2_progress_checker_selector_bt_node
- nav2_smoother_selector_bt_node
error_code_names:
- compute_path_error_code
- follow_path_error_code
Expand Down
2 changes: 2 additions & 0 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,8 @@ bt_navigator:
- nav2_assisted_teleop_cancel_bt_node
- nav2_drive_on_heading_cancel_bt_node
- nav2_is_battery_charging_condition_bt_node
- nav2_progress_checker_selector_bt_node
- nav2_smoother_selector_bt_node
error_code_names:
- compute_path_error_code
- follow_path_error_code
Expand Down
4 changes: 3 additions & 1 deletion nav2_bringup/rviz/nav2_default_view.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,11 @@ Panels:
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
Splitter Ratio: 0.3333333432674408
- Class: nav2_rviz_plugins/Navigation 2
Name: Navigation 2
- Class: nav2_rviz_plugins/Selector
Name: Selector
Visualization Manager:
Class: ""
Displays:
Expand Down
6 changes: 4 additions & 2 deletions nav2_bt_navigator/behavior_trees/follow_point.xml
Original file line number Diff line number Diff line change
Expand Up @@ -5,16 +5,18 @@
<root main_tree_to_execute="MainTree">
<BehaviorTree ID="MainTree">
<PipelineSequence name="NavigateWithReplanning">
<ControllerSelector selected_controller="{selected_controller}" default_controller="FollowPath" topic_name="controller_selector"/>
<PlannerSelector selected_planner="{selected_planner}" default_planner="GridBased" topic_name="planner_selector"/>
<RateController hz="1.0">
<Sequence>
<GoalUpdater input_goal="{goal}" output_goal="{updated_goal}">
<ComputePathToPose goal="{updated_goal}" path="{path}" planner_id="GridBased" error_code_id="{compute_path_error_code}"/>
<ComputePathToPose goal="{updated_goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
</GoalUpdater>
<TruncatePath distance="1.0" input_path="{path}" output_path="{truncated_path}"/>
</Sequence>
</RateController>
<KeepRunningUntilFailure>
<FollowPath path="{truncated_path}" controller_id="FollowPath" error_code_id="{follow_path_error_code}"/>
<FollowPath path="{truncated_path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
</KeepRunningUntilFailure>
</PipelineSequence>
</BehaviorTree>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@
<BehaviorTree ID="MainTree">
<RecoveryNode number_of_retries="6" name="NavigateRecovery">
<PipelineSequence name="NavigateWithReplanning">
<ControllerSelector selected_controller="{selected_controller}" default_controller="FollowPath" topic_name="controller_selector"/>
<PlannerSelector selected_planner="{selected_planner}" default_planner="GridBased" topic_name="planner_selector"/>
<RateController hz="2.0">
<RecoveryNode number_of_retries="1" name="ComputePathToPose">
<Fallback>
Expand All @@ -19,13 +21,13 @@
</Inverter>
<IsPathValid path="{path}"/>
</ReactiveSequence>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased" error_code_id="{compute_path_error_code}"/>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
</Fallback>
<ClearEntireCostmap name="ClearGlobalCostmap-Context" service_name="global_costmap/clear_entirely_global_costmap"/>
</RecoveryNode>
</RateController>
<RecoveryNode number_of_retries="1" name="FollowPath">
<FollowPath path="{path}" controller_id="FollowPath" error_code_id="{follow_path_error_code}"/>
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
<ClearEntireCostmap name="ClearLocalCostmap-Context" service_name="local_costmap/clear_entirely_local_costmap"/>
</RecoveryNode>
</PipelineSequence>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,11 +7,13 @@
<BehaviorTree ID="MainTree">
<RecoveryNode number_of_retries="6" name="NavigateRecovery">
<PipelineSequence name="NavigateWithReplanning">
<ControllerSelector selected_controller="{selected_controller}" default_controller="FollowPath" topic_name="controller_selector"/>
<PlannerSelector selected_planner="{selected_planner}" default_planner="GridBased" topic_name="planner_selector"/>
<RateController hz="0.333">
<RecoveryNode number_of_retries="1" name="ComputePathThroughPoses">
<ReactiveSequence>
<RemovePassedGoals input_goals="{goals}" output_goals="{goals}" radius="0.7"/>
<ComputePathThroughPoses goals="{goals}" path="{path}" planner_id="GridBased" error_code_id="{compute_path_error_code}"/>
<ComputePathThroughPoses goals="{goals}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
</ReactiveSequence>
<Sequence>
<WouldAPlannerRecoveryHelp error_code="{compute_path_error_code}"/>
Expand All @@ -20,7 +22,7 @@
</RecoveryNode>
</RateController>
<RecoveryNode number_of_retries="1" name="FollowPath">
<FollowPath path="{path}" controller_id="FollowPath" error_code_id="{follow_path_error_code}"/>
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
<Sequence>
<WouldAControllerRecoveryHelp error_code="{follow_path_error_code}"/>
<ClearEntireCostmap name="ClearLocalCostmap-Context" service_name="local_costmap/clear_entirely_local_costmap"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,17 +8,19 @@
<BehaviorTree ID="MainTree">
<RecoveryNode number_of_retries="6" name="NavigateRecovery">
<PipelineSequence name="NavigateWithReplanning">
<ControllerSelector selected_controller="{selected_controller}" default_controller="FollowPath" topic_name="controller_selector"/>
<PlannerSelector selected_planner="{selected_planner}" default_planner="GridBased" topic_name="planner_selector"/>
<RateController hz="1.0">
<RecoveryNode number_of_retries="1" name="ComputePathToPose">
<ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased" error_code_id="{compute_path_error_code}"/>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
<Sequence>
<WouldAPlannerRecoveryHelp error_code="{compute_path_error_code}"/>
<ClearEntireCostmap name="ClearGlobalCostmap-Context" service_name="global_costmap/clear_entirely_global_costmap"/>
</Sequence>
</RecoveryNode>
</RateController>
<RecoveryNode number_of_retries="1" name="FollowPath">
<FollowPath path="{path}" controller_id="FollowPath" error_code_id="{follow_path_error_code}"/>
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
<Sequence>
<WouldAControllerRecoveryHelp error_code="{follow_path_error_code}"/>
<ClearEntireCostmap name="ClearLocalCostmap-Context" service_name="local_costmap/clear_entirely_local_costmap"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,11 @@
<BehaviorTree ID="MainTree">
<RecoveryNode number_of_retries="6" name="NavigateRecovery">
<PipelineSequence name="NavigateWithReplanning">
<ControllerSelector selected_controller="{selected_controller}" default_controller="FollowPath" topic_name="controller_selector"/>
<PlannerSelector selected_planner="{selected_planner}" default_planner="GridBased" topic_name="planner_selector"/>
<RateController hz="1.0">
<RecoveryNode number_of_retries="1" name="ComputePathToPose">
<ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased" error_code_id="{compute_path_error_code}"/>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
<ClearEntireCostmap name="ClearGlobalCostmap-Context" service_name="global_costmap/clear_entirely_global_costmap"/>
</RecoveryNode>
</RateController>
Expand All @@ -25,7 +27,7 @@
</RetryUntilSuccessful>
</PathLongerOnApproach>
<RecoveryNode number_of_retries="1" name="FollowPath">
<FollowPath path="{path}" controller_id="FollowPath" error_code_id="{follow_path_error_code}"/>
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
<ClearEntireCostmap name="ClearLocalCostmap-Context" service_name="local_costmap/clear_entirely_local_costmap"/>
</RecoveryNode>
</ReactiveSequence>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@
<BehaviorTree ID="MainTree">
<RecoveryNode number_of_retries="6" name="NavigateRecovery">
<PipelineSequence>
<ControllerSelector selected_controller="{selected_controller}" default_controller="FollowPath" topic_name="controller_selector"/>
<PlannerSelector selected_planner="{selected_planner}" default_planner="GridBased" topic_name="planner_selector"/>
<RateController hz="1.0" name="RateControllerComputePathToPose">
<RecoveryNode number_of_retries="1" name="RecoveryComputePathToPose">
<Fallback name="FallbackComputePathToPose">
Expand All @@ -17,13 +19,13 @@
</Inverter>
<IsPathValid path="{path}"/>
</ReactiveSequence>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased" error_code_id="{compute_path_error_code}"/>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
</Fallback>
<ClearEntireCostmap name="ClearGlobalCostmap-Context" service_name="global_costmap/clear_entirely_global_costmap"/>
</RecoveryNode>
</RateController>
<RecoveryNode number_of_retries="1" name="RecoveryFollowPath">
<FollowPath path="{path}" controller_id="FollowPath" error_code_id="{follow_path_error_code}"/>
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
<ClearEntireCostmap name="ClearLocalCostmap-Context" service_name="local_costmap/clear_entirely_local_costmap"/>
</RecoveryNode>
</PipelineSequence>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,12 @@
<root main_tree_to_execute="MainTree">
<BehaviorTree ID="MainTree">
<PipelineSequence name="NavigateWithReplanning">
<ControllerSelector selected_controller="{selected_controller}" default_controller="FollowPath" topic_name="controller_selector"/>
<PlannerSelector selected_planner="{selected_planner}" default_planner="GridBased" topic_name="planner_selector"/>
<DistanceController distance="1.0">
<ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased" error_code_id="{compute_path_error_code}"/>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
</DistanceController>
<FollowPath path="{path}" controller_id="FollowPath" error_code_id="{follow_path_error_code}"/>
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
</PipelineSequence>
</BehaviorTree>
</root>
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,12 @@
<root main_tree_to_execute="MainTree">
<BehaviorTree ID="MainTree">
<PipelineSequence name="NavigateWithReplanning">
<ControllerSelector selected_controller="{selected_controller}" default_controller="FollowPath" topic_name="controller_selector"/>
<PlannerSelector selected_planner="{selected_planner}" default_planner="GridBased" topic_name="planner_selector"/>
<GoalUpdatedController>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased" error_code_id="{compute_path_error_code}"/>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
</GoalUpdatedController>
<FollowPath path="{path}" controller_id="FollowPath" error_code_id="{follow_path_error_code}"/>
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
</PipelineSequence>
</BehaviorTree>
</root>
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
<root main_tree_to_execute="MainTree">
<BehaviorTree ID="MainTree">
<PipelineSequence name="NavigateWithReplanning">
<ControllerSelector selected_controller="{selected_controller}" default_controller="FollowPath" topic_name="controller_selector"/>
<PlannerSelector selected_planner="{selected_planner}" default_planner="GridBased" topic_name="planner_selector"/>
<RateController hz="1.0">
<Fallback>
<ReactiveSequence>
Expand All @@ -12,10 +14,10 @@
</Inverter>
<IsPathValid path="{path}"/>
</ReactiveSequence>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased" error_code_id="{compute_path_error_code}"/>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
</Fallback>
</RateController>
<FollowPath path="{path}" controller_id="FollowPath" error_code_id="{follow_path_error_code}"/>
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
</PipelineSequence>
</BehaviorTree>
</root>
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,12 @@
<root main_tree_to_execute="MainTree">
<BehaviorTree ID="MainTree">
<PipelineSequence name="NavigateWithReplanning">
<ControllerSelector selected_controller="{selected_controller}" default_controller="FollowPath" topic_name="controller_selector"/>
<PlannerSelector selected_planner="{selected_planner}" default_planner="GridBased" topic_name="planner_selector"/>
<SpeedController min_rate="0.1" max_rate="1.0" min_speed="0.0" max_speed="0.26">
<ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased" error_code_id="{compute_path_error_code}"/>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
</SpeedController>
<FollowPath path="{path}" controller_id="FollowPath" error_code_id="{follow_path_error_code}"/>
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
</PipelineSequence>
</BehaviorTree>
</root>
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,12 @@
<root main_tree_to_execute="MainTree">
<BehaviorTree ID="MainTree">
<PipelineSequence name="NavigateWithReplanning">
<ControllerSelector selected_controller="{selected_controller}" default_controller="FollowPath" topic_name="controller_selector"/>
<PlannerSelector selected_planner="{selected_planner}" default_planner="GridBased" topic_name="planner_selector"/>
<RateController hz="1.0">
<ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased" error_code_id="{compute_path_error_code}"/>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
</RateController>
<FollowPath path="{path}" controller_id="FollowPath" error_code_id="{follow_path_error_code}"/>
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
</PipelineSequence>
</BehaviorTree>
</root>
4 changes: 3 additions & 1 deletion nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,9 @@ BtNavigator::BtNavigator(rclcpp::NodeOptions options)
"nav2_assisted_teleop_cancel_bt_node",
"nav2_back_up_cancel_bt_node",
"nav2_drive_on_heading_cancel_bt_node",
"nav2_is_battery_charging_condition_bt_node"
"nav2_is_battery_charging_condition_bt_node",
"nav2_progress_checker_selector_bt_node",
"nav2_smoother_selector_bt_node"
};

declare_parameter_if_not_declared(
Expand Down
2 changes: 2 additions & 0 deletions nav2_rviz_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ set(nav2_rviz_plugins_headers_to_moc
include/nav2_rviz_plugins/goal_common.hpp
include/nav2_rviz_plugins/goal_tool.hpp
include/nav2_rviz_plugins/nav2_panel.hpp
include/nav2_rviz_plugins/selector.hpp
include/nav2_rviz_plugins/particle_cloud_display/flat_weighted_arrows_array.hpp
include/nav2_rviz_plugins/particle_cloud_display/particle_cloud_display.hpp
)
Expand All @@ -51,6 +52,7 @@ set(library_name ${PROJECT_NAME})
add_library(${library_name} SHARED
src/goal_tool.cpp
src/nav2_panel.cpp
src/selector.cpp
src/particle_cloud_display/flat_weighted_arrows_array.cpp
src/particle_cloud_display/particle_cloud_display.cpp
${nav2_rviz_plugins_headers_to_moc}
Expand Down
Loading

0 comments on commit 70dc1f9

Please sign in to comment.