Public Member Functions | Private Member Functions | Private Attributes | List of all members
twist_recovery::TwistRecovery Class Reference

#include <twist_recovery.h>

Inheritance diagram for twist_recovery::TwistRecovery:
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...
 
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 &current, 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::Costmap2DROSglobal_costmap_
 
bool initialized_
 
double linear_acceleration_limit_
 
double linear_speed_limit_
 
costmap_2d::Costmap2DROSlocal_costmap_
 
std::string name_
 
ros::NodeHandle nh_
 
ros::Publisher pub_
 
double simulation_inc_
 
tf::TransformListenertf_
 
base_local_planner::CostmapModelworld_model_
 

Additional Inherited Members

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

Detailed Description

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.

Constructor & Destructor Documentation

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.

Member Function Documentation

gm::Pose2D twist_recovery::TwistRecovery::getCurrentLocalPose ( ) const
private

Definition at line 173 of file twist_recovery.cpp.

void twist_recovery::TwistRecovery::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 63 of file twist_recovery.cpp.

double twist_recovery::TwistRecovery::nonincreasingCostInterval ( const geometry_msgs::Pose2D &  current,
const geometry_msgs::Twist &  twist 
) const
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.

double twist_recovery::TwistRecovery::normalizedPoseCost ( const geometry_msgs::Pose2D &  pose) const
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.

void twist_recovery::TwistRecovery::runBehavior ( )
virtual

Run the behavior.

Implements nav_core::RecoveryBehavior.

Definition at line 184 of file twist_recovery.cpp.

gm::Twist twist_recovery::TwistRecovery::scaleGivenAccelerationLimits ( const geometry_msgs::Twist &  twist,
const double  time_remaining 
) const
private

Definition at line 159 of file twist_recovery.cpp.

geometry_msgs::Twist twist_recovery::TwistRecovery::transformTwist ( const geometry_msgs::Pose2D &  pose) const
private

Member Data Documentation

double twist_recovery::TwistRecovery::angular_acceleration_limit_
private

Definition at line 95 of file twist_recovery.h.

double twist_recovery::TwistRecovery::angular_speed_limit_
private

Definition at line 93 of file twist_recovery.h.

geometry_msgs::Twist twist_recovery::TwistRecovery::base_frame_twist_
private

Definition at line 89 of file twist_recovery.h.

double twist_recovery::TwistRecovery::controller_frequency_
private

Definition at line 96 of file twist_recovery.h.

double twist_recovery::TwistRecovery::duration_
private

Definition at line 91 of file twist_recovery.h.

costmap_2d::Costmap2DROS* twist_recovery::TwistRecovery::global_costmap_
private

Definition at line 78 of file twist_recovery.h.

bool twist_recovery::TwistRecovery::initialized_
private

Definition at line 83 of file twist_recovery.h.

double twist_recovery::TwistRecovery::linear_acceleration_limit_
private

Definition at line 94 of file twist_recovery.h.

double twist_recovery::TwistRecovery::linear_speed_limit_
private

Definition at line 92 of file twist_recovery.h.

costmap_2d::Costmap2DROS* twist_recovery::TwistRecovery::local_costmap_
private

Definition at line 79 of file twist_recovery.h.

std::string twist_recovery::TwistRecovery::name_
private

Definition at line 80 of file twist_recovery.h.

ros::NodeHandle twist_recovery::TwistRecovery::nh_
private

Definition at line 77 of file twist_recovery.h.

ros::Publisher twist_recovery::TwistRecovery::pub_
private

Definition at line 82 of file twist_recovery.h.

double twist_recovery::TwistRecovery::simulation_inc_
private

Definition at line 97 of file twist_recovery.h.

tf::TransformListener* twist_recovery::TwistRecovery::tf_
private

Definition at line 81 of file twist_recovery.h.

base_local_planner::CostmapModel* twist_recovery::TwistRecovery::world_model_
mutableprivate

Definition at line 87 of file twist_recovery.h.


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


twist_recovery
Author(s): Bhaskara Marthi
autogenerated on Mon Jun 22 2020 03:18:22