New in navigation ROS Diamondback, navigation_experimental ROS CTurtle

  Show EOL distros: 

navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

move_slow_and_clear

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mferguson AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: hydro-devel)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

move_slow_and_clear

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mfergs7 AT gmail DOT com>, Aaron Hoy <ahoy AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: indigo-devel)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

move_slow_and_clear

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mferguson AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: jade-devel)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

move_slow_and_clear

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mfergs7 AT gmail DOT com>, Aaron Hoy <ahoy AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: kinetic-devel)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

move_slow_and_clear

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mfergs7 AT gmail DOT com>, Aaron Hoy <ahoy AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: lunar)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | rotate_recovery | voxel_grid

Package Summary

move_slow_and_clear

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mfergs7 AT gmail DOT com>, Aaron Hoy <ahoy AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: melodic-devel)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | rotate_recovery | voxel_grid

Package Summary

move_slow_and_clear

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mfergs7 AT gmail DOT com>, Aaron Hoy <ahoy AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: noetic-devel)

Overview

The move_slow_and_clear::MoveSlowAndClear is a simple recovery behavior that clears information in the costmap and then limits the speed of the robot. Note, this recovery behavior is not truly safe, the robot may hit things, it'll just happen at a user-specified speed. Also, this recovery behavior is only compatible with local planners that allow maximum speeds to be set via dynamic_reconfigure such as the dwa_local_planner.

MoveSlowAndClear

The move_slow_and_clear::MoveSlowAndClear object exposes its functionality as a C++ ROS Wrapper. It operates within a ROS namespace (assumed to be name from here on) specified on initialization. It adheres to the nav_core::RecoveryBehavior interface found in the nav_core package.

API Stability

  • The C++ API is stable.
  • The ROS API is stable.

ROS Parameters

~<name>/clearing_distance (double, default: 0.5)

  • The radius away from the robot in meters inside of which obstacles will be cleared.
~<name>/limited_trans_speed (double, default: 0.25)
  • The translational speed in meters/second the robot will be limited to while executing this recovery behavior.
~<name>/limited_rot_speed (double, default: 0.25)
  • The rotational speed in radians/second the robot will be limited to while executing this recovery behavior.
~<name>/limited_distance (double, default: 0.3)
  • The distance in meters the robot must move before the speed restrictions are lifted.
~<name>/planner_namespace (string, default: "DWAPlannerROS")
  • The name of the planner to reconfigure parameters on. Specifically the max_trans_vel and max_rot_vel parameters will be reconfigured within this namespace.

C++ API

The C++ move_slow_and_clear::MoveSlowAndClear class adheres to the nav_core::RecoveryBehavior interface found in the nav_core package. For detailed documentation, please see MoveSlowAndClear Documentation.

Implementation

To use move_slow_and_clear, add the following lines in your move base yaml file:

recovery_behaviors:

  - name: 'move_slow_and_clear'

    type: 'move_slow_and_clear/MoveSlowAndClear'

Wiki: move_slow_and_clear (last edited 2021-09-14 12:21:01 by JashMota)