Public Member Functions | Private Member Functions | Private Attributes
twist_recovery::TwistRecovery Class Reference

#include <twist_recovery.h>

Inheritance diagram for twist_recovery::TwistRecovery:
Inheritance graph
[legend]

List of all members.

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.
void runBehavior ()
 Run the behavior.
 TwistRecovery ()
 Doesn't do anything: initialize is where the actual work happens.
 ~TwistRecovery ()

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.
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_
costmap_2d::Costmap2D costmap_
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_

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

Doesn't do anything: initialize is where the actual work happens.

Definition at line 55 of file twist_recovery.cpp.

Definition at line 59 of file twist_recovery.cpp.


Member Function Documentation

Definition at line 181 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 64 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 139 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 122 of file twist_recovery.cpp.

Run the behavior.

Implements nav_core::RecoveryBehavior.

Definition at line 192 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 167 of file twist_recovery.cpp.

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

Member Data Documentation

Definition at line 96 of file twist_recovery.h.

Definition at line 94 of file twist_recovery.h.

geometry_msgs::Twist twist_recovery::TwistRecovery::base_frame_twist_ [private]

Definition at line 90 of file twist_recovery.h.

Definition at line 97 of file twist_recovery.h.

Definition at line 80 of file twist_recovery.h.

Definition at line 92 of file twist_recovery.h.

Definition at line 78 of file twist_recovery.h.

Definition at line 84 of file twist_recovery.h.

Definition at line 95 of file twist_recovery.h.

Definition at line 93 of file twist_recovery.h.

Definition at line 79 of file twist_recovery.h.

std::string twist_recovery::TwistRecovery::name_ [private]

Definition at line 81 of file twist_recovery.h.

Definition at line 77 of file twist_recovery.h.

Definition at line 83 of file twist_recovery.h.

Definition at line 98 of file twist_recovery.h.

Definition at line 82 of file twist_recovery.h.

Definition at line 88 of file twist_recovery.h.


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


twist_recovery
Author(s): Bhaskara Marthi
autogenerated on Tue Jan 7 2014 11:09:49