Public Member Functions | Private Member Functions | Private Attributes | List of all members
move_slow_and_clear::MoveSlowAndClear Class Reference

#include <move_slow_and_clear.h>

Inheritance diagram for move_slow_and_clear::MoveSlowAndClear:
Inheritance graph
[legend]

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. More...
 
 MoveSlowAndClear ()
 
void runBehavior ()
 Run the behavior. More...
 
 ~MoveSlowAndClear ()
 
- Public Member Functions inherited from nav_core::RecoveryBehavior
virtual ~RecoveryBehavior ()
 

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::Costmap2DROSglobal_costmap_
 
bool initialized_
 
bool limit_set_
 
double limited_distance_
 
double limited_rot_speed_
 
double limited_trans_speed_
 
costmap_2d::Costmap2DROSlocal_costmap_
 
boost::mutex mutex_
 
double old_rot_speed_
 
double old_trans_speed_
 
ros::ServiceClient planner_dynamic_reconfigure_service_
 
ros::NodeHandle planner_nh_
 
ros::NodeHandle private_nh_
 
boost::thread * remove_limit_thread_
 
tf::Stamped< tf::Posespeed_limit_pose_
 

Additional Inherited Members

- Protected Member Functions inherited from nav_core::RecoveryBehavior
 RecoveryBehavior ()
 

Detailed Description

Definition at line 48 of file move_slow_and_clear.h.

Constructor & Destructor Documentation

move_slow_and_clear::MoveSlowAndClear::MoveSlowAndClear ( )

Definition at line 45 of file move_slow_and_clear.cpp.

move_slow_and_clear::MoveSlowAndClear::~MoveSlowAndClear ( )

Definition at line 48 of file move_slow_and_clear.cpp.

Member Function Documentation

void move_slow_and_clear::MoveSlowAndClear::distanceCheck ( const ros::TimerEvent e)
private

Definition at line 167 of file move_slow_and_clear.cpp.

double move_slow_and_clear::MoveSlowAndClear::getSqDistance ( )
private

Definition at line 154 of file move_slow_and_clear.cpp.

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.

Definition at line 53 of file move_slow_and_clear.cpp.

void move_slow_and_clear::MoveSlowAndClear::removeSpeedLimit ( )
private

Definition at line 184 of file move_slow_and_clear.cpp.

void move_slow_and_clear::MoveSlowAndClear::runBehavior ( )
virtual

Run the behavior.

Implements nav_core::RecoveryBehavior.

Definition at line 73 of file move_slow_and_clear.cpp.

void move_slow_and_clear::MoveSlowAndClear::setRobotSpeed ( double  trans_speed,
double  rot_speed 
)
private

Definition at line 191 of file move_slow_and_clear.cpp.

Member Data Documentation

double move_slow_and_clear::MoveSlowAndClear::clearing_distance_
private

Definition at line 73 of file move_slow_and_clear.h.

ros::Timer move_slow_and_clear::MoveSlowAndClear::distance_check_timer_
private

Definition at line 75 of file move_slow_and_clear.h.

costmap_2d::Costmap2DROS* move_slow_and_clear::MoveSlowAndClear::global_costmap_
private

Definition at line 70 of file move_slow_and_clear.h.

bool move_slow_and_clear::MoveSlowAndClear::initialized_
private

Definition at line 72 of file move_slow_and_clear.h.

bool move_slow_and_clear::MoveSlowAndClear::limit_set_
private

Definition at line 79 of file move_slow_and_clear.h.

double move_slow_and_clear::MoveSlowAndClear::limited_distance_
private

Definition at line 73 of file move_slow_and_clear.h.

double move_slow_and_clear::MoveSlowAndClear::limited_rot_speed_
private

Definition at line 74 of file move_slow_and_clear.h.

double move_slow_and_clear::MoveSlowAndClear::limited_trans_speed_
private

Definition at line 74 of file move_slow_and_clear.h.

costmap_2d::Costmap2DROS* move_slow_and_clear::MoveSlowAndClear::local_costmap_
private

Definition at line 71 of file move_slow_and_clear.h.

boost::mutex move_slow_and_clear::MoveSlowAndClear::mutex_
private

Definition at line 78 of file move_slow_and_clear.h.

double move_slow_and_clear::MoveSlowAndClear::old_rot_speed_
private

Definition at line 74 of file move_slow_and_clear.h.

double move_slow_and_clear::MoveSlowAndClear::old_trans_speed_
private

Definition at line 74 of file move_slow_and_clear.h.

ros::ServiceClient move_slow_and_clear::MoveSlowAndClear::planner_dynamic_reconfigure_service_
private

Definition at line 80 of file move_slow_and_clear.h.

ros::NodeHandle move_slow_and_clear::MoveSlowAndClear::planner_nh_
private

Definition at line 69 of file move_slow_and_clear.h.

ros::NodeHandle move_slow_and_clear::MoveSlowAndClear::private_nh_
private

Definition at line 69 of file move_slow_and_clear.h.

boost::thread* move_slow_and_clear::MoveSlowAndClear::remove_limit_thread_
private

Definition at line 77 of file move_slow_and_clear.h.

tf::Stamped<tf::Pose> move_slow_and_clear::MoveSlowAndClear::speed_limit_pose_
private

Definition at line 76 of file move_slow_and_clear.h.


The documentation for this class was generated from the following files:


move_slow_and_clear
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:06:01