#include <twist_recovery.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. More... | |
void | runBehavior () |
Run the behavior. More... | |
TwistRecovery () | |
Doesn't do anything: initialize is where the actual work happens. More... | |
~TwistRecovery () | |
Public Member Functions inherited from nav_core::RecoveryBehavior | |
virtual | ~RecoveryBehavior () |
Private Member Functions | |
geometry_msgs::Pose2D | getCurrentLocalPose () const |
double | nonincreasingCostInterval (const geometry_msgs::Pose2D ¤t, const geometry_msgs::Twist &twist) const |
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. More... | |
geometry_msgs::Twist | scaleGivenAccelerationLimits (const geometry_msgs::Twist &twist, const double time_remaining) const |
geometry_msgs::Twist | transformTwist (const geometry_msgs::Pose2D &pose) const |
Private Attributes | |
double | angular_acceleration_limit_ |
double | angular_speed_limit_ |
geometry_msgs::Twist | base_frame_twist_ |
double | controller_frequency_ |
double | duration_ |
costmap_2d::Costmap2DROS * | global_costmap_ |
bool | initialized_ |
double | linear_acceleration_limit_ |
double | linear_speed_limit_ |
costmap_2d::Costmap2DROS * | local_costmap_ |
std::string | name_ |
ros::NodeHandle | nh_ |
ros::Publisher | pub_ |
double | simulation_inc_ |
tf::TransformListener * | tf_ |
base_local_planner::CostmapModel * | world_model_ |
Additional Inherited Members | |
Protected Member Functions inherited from nav_core::RecoveryBehavior | |
RecoveryBehavior () | |
Recovery behavior that takes a given twist and tries to execute it for up to d seconds, or until reaching an obstacle.
Definition at line 52 of file twist_recovery.h.
twist_recovery::TwistRecovery::TwistRecovery | ( | ) |
Doesn't do anything: initialize is where the actual work happens.
Definition at line 54 of file twist_recovery.cpp.
twist_recovery::TwistRecovery::~TwistRecovery | ( | ) |
Definition at line 58 of file twist_recovery.cpp.
|
private |
Definition at line 173 of file twist_recovery.cpp.
|
virtual |
Initialize the parameters of the behavior.
Implements nav_core::RecoveryBehavior.
Definition at line 63 of file twist_recovery.cpp.
|
private |
Return the maximum d <= duration_ such that starting at the current pose, the cost is nonincreasing for d seconds if we follow twist It might also be good to have a threshold such that we're allowed to have lethal cost for at most the first k of those d seconds, but this is not done
Definition at line 131 of file twist_recovery.cpp.
|
private |
Return the cost of a pose, modified so that -1 does not equal infinity; instead 1e9 does.
Definition at line 120 of file twist_recovery.cpp.
|
virtual |
Run the behavior.
Implements nav_core::RecoveryBehavior.
Definition at line 184 of file twist_recovery.cpp.
|
private |
Definition at line 159 of file twist_recovery.cpp.
|
private |
|
private |
Definition at line 95 of file twist_recovery.h.
|
private |
Definition at line 93 of file twist_recovery.h.
|
private |
Definition at line 89 of file twist_recovery.h.
|
private |
Definition at line 96 of file twist_recovery.h.
|
private |
Definition at line 91 of file twist_recovery.h.
|
private |
Definition at line 78 of file twist_recovery.h.
|
private |
Definition at line 83 of file twist_recovery.h.
|
private |
Definition at line 94 of file twist_recovery.h.
|
private |
Definition at line 92 of file twist_recovery.h.
|
private |
Definition at line 79 of file twist_recovery.h.
|
private |
Definition at line 80 of file twist_recovery.h.
|
private |
Definition at line 77 of file twist_recovery.h.
|
private |
Definition at line 82 of file twist_recovery.h.
|
private |
Definition at line 97 of file twist_recovery.h.
|
private |
Definition at line 81 of file twist_recovery.h.
|
mutableprivate |
Definition at line 87 of file twist_recovery.h.