Public Member Functions | Private Member Functions | Private Attributes
straf_recovery::StrafRecovery Class Reference

#include <straf_recovery.h>

Inheritance diagram for straf_recovery::StrafRecovery:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void initialize (std::string, tf::TransformListener *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
void runBehavior ()
 This recovery behavior will translate away from the nearest obstacle in the local costmap. This is done by finding the nearest points, calculating a tangent, and then finding the normal to that tangent. The robot moves along that tangent line until all of the following conditions are true:
 StrafRecovery ()

Private Member Functions

void goalCallback (const geometry_msgs::PoseStamped &msg)
 uses move_base_simple/goal
void reconfigureCB (StrafRecoveryConfig &config, uint32_t level)
 callback for reconfigure
void strafInDiretionOfPose (tf::Stamped< tf::Pose > current_pose, tf::Vector3 direction_pose, bool away=true)
 straf in the direction of a point, given in the odom frame

Private Attributes

int cycles_
ros::Publisher cycles_pub_
dynamic_reconfigure::Server
< StrafRecoveryConfig > * 
dsrv_
bool enabled_
double frequency_
costmap_2d::Costmap2DROSglobal_costmap_
double go_to_goal_distance_threshold_
ros::Subscriber goal_sub_
bool initialized_
geometry_msgs::PoseStamped last_goal_
costmap_2d::Costmap2DROSlocal_costmap_
base_local_planner::CostmapModellocal_costmap_model_
double maximum_translate_distance_
double minimum_translate_distance_
std::string name_
ros::Publisher obstacle_pub_
tf::TransformListenertf_
int timeout_
double vel_
ros::Publisher vel_pub_
double xy_goal_tolerance_

Detailed Description

Definition at line 13 of file straf_recovery.h.


Constructor & Destructor Documentation

Definition at line 13 of file straf_recovery.cpp.


Member Function Documentation

void straf_recovery::StrafRecovery::goalCallback ( const geometry_msgs::PoseStamped &  msg) [private]

uses move_base_simple/goal

Definition at line 211 of file straf_recovery.cpp.

void straf_recovery::StrafRecovery::initialize ( std::string  name,
tf::TransformListener tf,
costmap_2d::Costmap2DROS global_costmap,
costmap_2d::Costmap2DROS local_costmap 
) [virtual]

Implements nav_core::RecoveryBehavior.

Definition at line 17 of file straf_recovery.cpp.

void straf_recovery::StrafRecovery::reconfigureCB ( StrafRecoveryConfig &  config,
uint32_t  level 
) [private]

callback for reconfigure

Definition at line 217 of file straf_recovery.cpp.

This recovery behavior will translate away from the nearest obstacle in the local costmap. This is done by finding the nearest points, calculating a tangent, and then finding the normal to that tangent. The robot moves along that tangent line until all of the following conditions are true:

  • The robot has moved at least the distance specified by min_distance (via parameter server)
  • The robot has moved no more than the distance specified by max_distance (via parameter server)
  • The robot is able to spin freely (IE, rotate recovery would work now)
  • The robot is no closer to any other obstacle than it was when it began translating

Implements nav_core::RecoveryBehavior.

Definition at line 74 of file straf_recovery.cpp.

void straf_recovery::StrafRecovery::strafInDiretionOfPose ( tf::Stamped< tf::Pose current_pose,
tf::Vector3  direction_pose,
bool  away = true 
) [private]

straf in the direction of a point, given in the odom frame

Definition at line 176 of file straf_recovery.cpp.


Member Data Documentation

Definition at line 40 of file straf_recovery.h.

Definition at line 46 of file straf_recovery.h.

dynamic_reconfigure::Server<StrafRecoveryConfig>* straf_recovery::StrafRecovery::dsrv_ [private]

Definition at line 42 of file straf_recovery.h.

Definition at line 32 of file straf_recovery.h.

Definition at line 33 of file straf_recovery.h.

Definition at line 44 of file straf_recovery.h.

Definition at line 36 of file straf_recovery.h.

Definition at line 49 of file straf_recovery.h.

Definition at line 31 of file straf_recovery.h.

geometry_msgs::PoseStamped straf_recovery::StrafRecovery::last_goal_ [private]

Definition at line 45 of file straf_recovery.h.

Definition at line 43 of file straf_recovery.h.

Definition at line 41 of file straf_recovery.h.

Definition at line 34 of file straf_recovery.h.

Definition at line 35 of file straf_recovery.h.

std::string straf_recovery::StrafRecovery::name_ [private]

Definition at line 50 of file straf_recovery.h.

Definition at line 47 of file straf_recovery.h.

Definition at line 51 of file straf_recovery.h.

Definition at line 39 of file straf_recovery.h.

Definition at line 38 of file straf_recovery.h.

Definition at line 48 of file straf_recovery.h.

Definition at line 37 of file straf_recovery.h.


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


straf_recovery
Author(s):
autogenerated on Sat Jun 8 2019 20:37:23