-
Notifications
You must be signed in to change notification settings - Fork 2
7. Interface to Move Base Flex
This page describes how to integrate BTs with Move Base Flex using ROS action interface. It allows us to navigate with the robot using global path planning and local navigation (obstacle avoidance).
Move Base Flex offers three action interfaces:
- get_path
mbf_msgs/GetPath.action
- exe_path
mbf_msgs/ExePath.action
- recovery
mbf_msgs/Recovery.action
And we have created the corresponding BTs actions to interface with them on fkie_bt_move_base_actions. A typical Behavior Tree for robot navigation looks like:
Defined by the following XML tree:
<root main_tree_to_execute="bt_navigation">
<BehaviorTree ID="bt_navigation">
<SwitchClientStop name="mbf">
<Sequence name="Main loop">
<Fallback name="Goal Definition">
<Condition ID="ValidPose" name="ValidPose" target_pose="{target_pose}"/>
<Action ID="PoseReceived" name="mbf_goal" target_pose="{target_pose}"/>
</Fallback>
<Sequence name="Navigation">
<Action ID="ServiceEmptyAction" name="clear_costmap"/>
<Action ID="MoveBase_GetPath" name="Global planner" planner="GlobalPlanner" target_pose="{target_pose}" path="{path}"/>
<Fallback>
<Action ID="MoveBase_ExePathSync" name="Local planner" controller="dwa" path="{path}" target_pose="{target_pose}"/>
<Action ID="MoveBase_Recovery" name="Recovery" strategy="move_slow_and_clear_fkie"/>
</Fallback>
</Sequence>
</Sequence>
</SwitchClientStop>
</BehaviorTree>
</root>
Now we want to briefly explain how the most relevant actions are working in this tree:
The action is defined in GetPath.h and offers the following ports:
BT::BidirectionalPort<Pose2D>("target_pose"),
BT::InputPort<Pose2D>("planner"),
BT::OutputPort<nav_msgs::Path>("path")
This action expects a Pose2D
called target_pose
, and a constant string with the name of the global path planner planner
. In our example, we use planner="GlobalPlanner"
. The BT action calls the MBF
action mbf_msgs/GetPath.action
for generating a path between the current robot position and the target_pose
. If succeeded, the path is saved into the output port path
.
The action is defined on ExePathSync.h and offers the following ports:
BT::BidirectionalPort<Pose2D>("target_pose"),
BT::BidirectionalPort<nav_msgs::Path>("path"),
BT::InputPort<std::string>("controller")
It expects a nav_msgs::Path
on port path
, and a controller (such as dwa_local_planner or teb_local_planner) on port controller
.
This action will block the execution of the tree until the robot reaches the target_pose
. It also resets target_pose
when the goal has been reached.
If an application demands for an asynchronous BT for navigation, check out this BT action ExePathAsync.h.
The action is defined on Recovery.h and offers the following port:
BT::InputPort<std::string>("strategy")
It uses the behavior defined in port strategy
for recovering the robot after failing during navigation. More recoveries can be added in the fallback to increase the chances of un-stucking a robot during autonomous navigation.
We use a Fallback
for checking if we have a valid goal using the condition ValidPose
, or a new goal pose is available using PoseReceived
action.
<Fallback name="Goal Definition">
<Condition ID="ValidPose" name="ValidPose" target_pose="{target_pose}"/>
<Action ID="PoseReceived" name="mbf_goal" target_pose="{target_pose}"/>
</Fallback>