#include <move_slow_and_clear.h>

Public Member Functions | |
| void | initialize (std::string n, tf::TransformListener *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap) | 
| Initialize the parameters of the behavior.   | |
| MoveSlowAndClear () | |
| void | runBehavior () | 
| Run the behavior.   | |
| ~MoveSlowAndClear () | |
Private Member Functions | |
| void | distanceCheck (const ros::TimerEvent &e) | 
| double | getSqDistance () | 
| void | removeSpeedLimit () | 
| void | setRobotSpeed (double trans_speed, double rot_speed) | 
Private Attributes | |
| double | clearing_distance_ | 
| ros::Timer | distance_check_timer_ | 
| costmap_2d::Costmap2DROS * | global_costmap_ | 
| bool | initialized_ | 
| bool | limit_set_ | 
| double | limited_distance_ | 
| double | limited_rot_speed_ | 
| double | limited_trans_speed_ | 
| costmap_2d::Costmap2DROS * | local_costmap_ | 
| boost::mutex | mutex_ | 
| double | old_rot_speed_ | 
| double | old_trans_speed_ | 
| ros::NodeHandle | planner_nh_ | 
| ros::NodeHandle | private_nh_ | 
| boost::thread * | remove_limit_thread_ | 
| tf::Stamped< tf::Pose > | speed_limit_pose_ | 
Definition at line 47 of file move_slow_and_clear.h.
| void move_slow_and_clear::MoveSlowAndClear::distanceCheck | ( | const ros::TimerEvent & | e | ) |  [private] | 
        
| double move_slow_and_clear::MoveSlowAndClear::getSqDistance | ( | ) |  [private] | 
        
| void move_slow_and_clear::MoveSlowAndClear::initialize | ( | std::string | n, | 
| tf::TransformListener * | tf, | ||
| costmap_2d::Costmap2DROS * | global_costmap, | ||
| costmap_2d::Costmap2DROS * | local_costmap | ||
| ) |  [virtual] | 
        
Initialize the parameters of the behavior.
Implements nav_core::RecoveryBehavior.
| void move_slow_and_clear::MoveSlowAndClear::removeSpeedLimit | ( | ) |  [private] | 
        
| void move_slow_and_clear::MoveSlowAndClear::runBehavior | ( | ) |  [virtual] | 
        
Run the behavior.
Implements nav_core::RecoveryBehavior.
| void move_slow_and_clear::MoveSlowAndClear::setRobotSpeed | ( | double | trans_speed, | 
| double | rot_speed | ||
| ) |  [private] | 
        
double move_slow_and_clear::MoveSlowAndClear::clearing_distance_ [private] | 
        
Definition at line 72 of file move_slow_and_clear.h.
Definition at line 74 of file move_slow_and_clear.h.
Definition at line 69 of file move_slow_and_clear.h.
bool move_slow_and_clear::MoveSlowAndClear::initialized_ [private] | 
        
Definition at line 71 of file move_slow_and_clear.h.
bool move_slow_and_clear::MoveSlowAndClear::limit_set_ [private] | 
        
Definition at line 78 of file move_slow_and_clear.h.
double move_slow_and_clear::MoveSlowAndClear::limited_distance_ [private] | 
        
Definition at line 72 of file move_slow_and_clear.h.
double move_slow_and_clear::MoveSlowAndClear::limited_rot_speed_ [private] | 
        
Definition at line 73 of file move_slow_and_clear.h.
double move_slow_and_clear::MoveSlowAndClear::limited_trans_speed_ [private] | 
        
Definition at line 73 of file move_slow_and_clear.h.
Definition at line 70 of file move_slow_and_clear.h.
boost::mutex move_slow_and_clear::MoveSlowAndClear::mutex_ [private] | 
        
Definition at line 77 of file move_slow_and_clear.h.
double move_slow_and_clear::MoveSlowAndClear::old_rot_speed_ [private] | 
        
Definition at line 73 of file move_slow_and_clear.h.
double move_slow_and_clear::MoveSlowAndClear::old_trans_speed_ [private] | 
        
Definition at line 73 of file move_slow_and_clear.h.
Definition at line 68 of file move_slow_and_clear.h.
Definition at line 68 of file move_slow_and_clear.h.
boost::thread* move_slow_and_clear::MoveSlowAndClear::remove_limit_thread_ [private] | 
        
Definition at line 76 of file move_slow_and_clear.h.
Definition at line 75 of file move_slow_and_clear.h.