How to use planner selector and controller selector actions?
rajeshAnt opened this issue · 2 comments
- Operating System:
- Ubuntu 22.04.4
- ROS2 Version:
- Humble
- DDS implementation:
- CycloneDDS
Hi, i am new to the nav2 architecture and I am trying to use different planners at different stages of my robot navigation.
bt_navigator and planner_server parms from my nav_params.yaml file looks like this.
bt_navigator:
ros__parameters:
global_frame: map
robot_base_frame: base_link
odom_topic: /odometry/filtered
bt_loop_duration: 10
default_server_timeout: 20
navigators: ["navigate_to_pose", "navigate_through_poses"]
navigate_to_pose:
plugin: "nav2_bt_navigator::NavigateToPoseNavigator"
navigate_through_poses:
plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator"
default_bt_xml: "my_path/config/navigate_to_pose_w_replanning_and_recovery.xml"
# '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
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
# plugin_lib_names is used to add custom BT plugins to the executor (vector of strings).
# Built-in plugins are added automatically
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_compute_path_through_poses_action_bt_node
- nav2_follow_path_action_bt_node
- nav2_back_up_action_bt_node
- nav2_spin_action_bt_node
- nav2_wait_action_bt_node
- nav2_clear_costmap_service_bt_node
- nav2_is_stuck_condition_bt_node
- nav2_goal_reached_condition_bt_node
- nav2_goal_updated_condition_bt_node
- nav2_initial_pose_received_condition_bt_node
- nav2_reinitialize_global_localization_service_bt_node
- nav2_rate_controller_bt_node
- nav2_distance_controller_bt_node
- nav2_speed_controller_bt_node
- nav2_truncate_path_action_bt_node
- nav2_goal_updater_node_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
- nav2_time_expired_condition_bt_node
- nav2_distance_traveled_condition_bt_node
- nav2_single_trigger_bt_node
- nav2_goal_updated_controller_bt_node
- nav2_is_battery_low_condition_bt_node
- nav2_navigate_through_poses_action_bt_node
- nav2_navigate_to_pose_action_bt_node
- nav2_remove_passed_goals_action_bt_node
- nav2_planner_selector_bt_node
- nav2_controller_selector_bt_node
- nav2_goal_checker_selector_bt_node
error_code_names:
- compute_path_error_code
- follow_path_error_code
bt_navigator_rclcpp_node:
ros__parameters:
use_sim_time: False
planner_server:
ros__parameters:
expected_planner_frequency: 10.0
use_sim_time: False
planner_plugins: ["GridBased_navfn", "GridBased_smac"]
GridBased_navfn:
plugin: "nav2_navfn_planner/NavfnPlanner"
GridBased_smac:
plugin: "nav2_smac_planner/SmacPlannerHybrid"
The navigate_to_pose_w_replanning_and_recovery.xml is
<!--
This Behavior Tree replans the global path periodically at 1 Hz and it also has
recovery actions specific to planning / control as well as general system issues.
This will be continuous if a kinematically valid planner is selected.
-->
<root BTCPP_format="4" main_tree_to_execute="MainTree">
<BehaviorTree ID="MainTree">
<RecoveryNode number_of_retries="6" name="NavigateRecovery">
<PipelineSequence name="NavigateWithReplanning">
<ControllerSelector selected_controller="{selected_controller}" default_controller="FollowPath_DWB" topic_name="controller_selector"/>
<PlannerSelector selected_planner="{selected_planner}" default_planner="GridBased_navfn" topic_name="planner_selector"/>
<RateController hz="1.0">
<RecoveryNode number_of_retries="1" name="ComputePathToPose">
<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="{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"/>
</Sequence>
</RecoveryNode>
</PipelineSequence>
<Sequence>
<Fallback>
<WouldAControllerRecoveryHelp error_code="{follow_path_error_code}"/>
<WouldAPlannerRecoveryHelp error_code="{compute_path_error_code}"/>
</Fallback>
<ReactiveFallback name="RecoveryFallback">
<GoalUpdated/>
<RoundRobin name="RecoveryActions">
<Sequence name="ClearingActions">
<ClearEntireCostmap name="ClearLocalCostmap-Subtree" service_name="local_costmap/clear_entirely_local_costmap"/>
<ClearEntireCostmap name="ClearGlobalCostmap-Subtree" service_name="global_costmap/clear_entirely_global_costmap"/>
</Sequence>
<Spin spin_dist="1.57" error_code_id="{spin_error_code}"/>
<Wait wait_duration="5.0"/>
<BackUp backup_dist="0.30" backup_speed="0.15" error_code_id="{backup_code_id}"/>
</RoundRobin>
</ReactiveFallback>
</Sequence>
</RecoveryNode>
</BehaviorTree>
</root>
I couldn't see the planner_selector topic when I do ros2 topic list. Is there any steps that i am missing in configuring the planner selector.
Thanks in advance :)
Sometimes transient local QoS topics don't appear off hand in the CLI (nothing we can do about that in Nav2), but I'm sure if you did a ros2 topic info
on it you'd see it. Try publishing to it and I think you'll see it works fine - we have unit tests for this so I know it works :-) Just make sure to use the right QoS settings
Hi, thanks for your reply. I was able to make the planner selector work but I had to do the following changes.
I had to replace the parameter name to default_nav_to_pose_bt_xml
and not the default_bt_xml: "my_path/config/navigate_to_pose_w_replanning_and_recovery.xml"
. And I used the behavior tree from the Humble branch as the base and added the planner and controller selector actions.