39 #ifndef TWIST_RECOVERY_TWIST_RECOVERY_H    40 #define TWIST_RECOVERY_TWIST_RECOVERY_H    45 #include <geometry_msgs/Pose2D.h>    75   geometry_msgs::Twist 
transformTwist (
const geometry_msgs::Pose2D& pose) 
const;
   104 #endif // include guard geometry_msgs::Twist scaleGivenAccelerationLimits(const geometry_msgs::Twist &twist, const double time_remaining) const 
double linear_acceleration_limit_
void runBehavior()
Run the behavior. 
double normalizedPoseCost(const geometry_msgs::Pose2D &pose) const 
Return the cost of a pose, modified so that -1 does not equal infinity; instead 1e9 does...
geometry_msgs::Twist transformTwist(const geometry_msgs::Pose2D &pose) const 
base_local_planner::CostmapModel * world_model_
double controller_frequency_
geometry_msgs::Twist base_frame_twist_
costmap_2d::Costmap2DROS * global_costmap_
double nonincreasingCostInterval(const geometry_msgs::Pose2D ¤t, const geometry_msgs::Twist &twist) const 
double angular_acceleration_limit_
TwistRecovery()
Doesn't do anything: initialize is where the actual work happens. 
double linear_speed_limit_
tf::TransformListener * tf_
costmap_2d::Costmap2DROS * local_costmap_
double angular_speed_limit_
geometry_msgs::Pose2D getCurrentLocalPose() const 
void initialize(std::string n, tf::TransformListener *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
Initialize the parameters of the behavior.