Show EOL distros: 

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

Package Summary

This package provides a recovery behavior for the navigation stack that attempts to clear space by performing a 360 degree rotation of the robot.

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

Package Summary

This package provides a recovery behavior for the navigation stack that attempts to clear space by performing a 360 degree rotation of the robot.

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

Package Summary

This package provides a recovery behavior for the navigation stack that attempts to clear space by performing a 360 degree rotation of the robot.

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

Package Summary

This package provides a recovery behavior for the navigation stack that attempts to clear space by performing a 360 degree rotation of the robot.

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

This package provides a recovery behavior for the navigation stack that attempts to clear space by performing a 360 degree rotation of the robot.

  • 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

This package provides a recovery behavior for the navigation stack that attempts to clear space by performing a 360 degree rotation of the robot.

  • 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

This package provides a recovery behavior for the navigation stack that attempts to clear space by performing a 360 degree rotation of the robot.

  • 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

This package provides a recovery behavior for the navigation stack that attempts to clear space by performing a 360 degree rotation of the robot.

  • 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

This package provides a recovery behavior for the navigation stack that attempts to clear space by performing a 360 degree rotation of the robot.

  • 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

This package provides a recovery behavior for the navigation stack that attempts to clear space by performing a 360 degree rotation of the robot.

  • 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

This package provides a recovery behavior for the navigation stack that attempts to clear space by performing a 360 degree rotation of the robot.

  • 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 rotate_recovery::RotateRecovery is a simple recovery behavior that attempts to clear out space in the navigation stack's costmaps by rotating the robot 360 degrees if local obstacles allow. It adheres to the nav_core::RecoveryBehavior interface found in the nav_core package and can be used as a recovery behavior plugin for the move_base node.

RotateRecovery

The rotate_recovery::RotateRecovery 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.

Example creation of a rotate_recovery::RotateRecovery object:

   1 #include <tf/transform_listener.h>
   2 #include <costmap_2d/costmap_2d_ros.h>
   3 #include <rotate_recovery/rotate_recovery.h>
   4 
   5 ...
   6 tf::TransformListener tf(ros::Duration(10));
   7 costmap_2d::Costmap2DROS global_costmap("global_costmap", tf);
   8 costmap_2d::Costmap2DROS local_costmap("local_costmap", tf);
   9 
  10 rotate_recovery::RotateRecovery rr;
  11 rr.initialize("my_rotate_recovery", &tf, &global_costmap, &local_costmap);
  12 
  13 rr.runBehavior();

API Stability

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

ROS Parameters

The rotate_recovery::RotateRecovery object assumes that the local planner used by the move_base node is the base_local_planner::TrajectoryPlannerROS documented in the base_local_planner package and reads some of its parameters accordingly. It will work on its own, but this requires the user to specify additional parameters.

RotateRecovery Parameters

~<name>/sim_granularity (double, default: 0.017)

  • The distance in radians between checks for obstacles when checking if an in-place rotation is safe. Defaults to 1 degree.
~<name>/frequency (double, default: 20.0)
  • The frequency in HZ at which to send velocity commands to the mobile base.

TrajectoryPlannerROS Parameters

These parameters are already set when using the base_local_planner::TrajectoryPlannerROS local planner, they only need to be set explicitly for the rotate_recovery::RotateRecovery recovery behavior if a different local planne is used with the navigation stack.

~TrajectoryPlannerROS/yaw_goal_tolerance (double, default: 0.05)

  • The tolerance in radians for the controller in yaw/rotation when achieving its goal
~TrajectoryPlannerROS/acc_lim_th (double, default: 3.2)
  • The rotational acceleration limit of the robot in radians/sec^2
~TrajectoryPlannerROS/max_rotational_vel (double, default: 1.0)
  • The maximum rotational velocity allowed for the base in radians/sec
~TrajectoryPlannerROS/min_in_place_rotational_vel (double, default: 0.4)
  • The minimum rotational velocity allowed for the base while performing in-place rotations in radians/sec

C++ API

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

Wiki: rotate_recovery (last edited 2019-11-04 12:41:19 by ArvidNorlander)