A recovery behavior for move_base which when executed backs off to create moveable space.
~backoff_distance(double, default:0.2)
Amount of distance robot should backoff to create space.
~vel(double, default:0.1)
At what velocity to move while backing off.
clone and build the package within your workspace,
Verify the availability of the package,
rospack plugins --attrib=plugin nav_core
Following line should be present within the response with path to your workspace,
backoff_recovery /<path_to_ws>/src/backoff_recovery/backoff_plugin.xml
Move base needs to be registered to use this plugin, a list containing recovery behaviors to be used should be passed as a parameter. To set the params within the WaitRecovery behavior a .yaml
file can be loaded.
<launch>
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<!-- Other ros params and remaps -->
<rosparam file="$(find <your_package>)/param/recovery_params.yaml" command="load" />
<param name="recovery_behaviors" value="[
{name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery},
{name: wait, type: wait_recovery/WaitRecovery},
{name: backoff, type: backoff_recovery/BackoffRecovery}
]" type="yaml" />
</node>
</launch>
Contents within the .yaml
file,
# Backoff
backoff_distance: 0.5
vel: 0.2
Not always will the robot be able to find valid local path by performing rotate in place recovery. The robot must backoff a little bit to follow a valid trajectory generated by local planner.