$search

hector_exploration_planner::HectorExplorationPlanner Class Reference

#include <hector_exploration_planner.h>

List of all members.

Public Member Functions

float angleDifferenceWall (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal)
bool doAlternativeExploration (const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &oldplan)
bool doExploration (const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > &plan)
bool doInnerExploration (const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > &plan)
bool exploreWalls (const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > &goals)
bool findFrontiers (std::vector< geometry_msgs::PoseStamped > &frontiers)
bool findFrontiers (std::vector< geometry_msgs::PoseStamped > &frontiers, std::vector< geometry_msgs::PoseStamped > &noFrontiers)
bool findInnerFrontier (std::vector< geometry_msgs::PoseStamped > &innerFrontier)
 HectorExplorationPlanner (std::string name, costmap_2d::Costmap2DROS *costmap_ros)
 HectorExplorationPlanner ()
void initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros)
bool makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
 ~HectorExplorationPlanner ()

Private Member Functions

unsigned int angleDanger (float angle)
float angleDifference (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal)
bool buildexploration_trans_array_ (const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > goals, bool useAnglePenalty)
bool buildobstacle_trans_array_ ()
unsigned int cellDanger (int point)
void clearFrontiers ()
void deleteMapData ()
int down (int point)
int downleft (int point)
int downright (int point)
void getAdjacentPoints (int point, int points[])
void getDiagonalPoints (int point, int points[])
float getDistanceWeight (const geometry_msgs::PoseStamped &point1, const geometry_msgs::PoseStamped &point2)
void getStraightPoints (int point, int points[])
bool getTrajectory (const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > goals, std::vector< geometry_msgs::PoseStamped > &plan)
double getYawToUnknown (int point)
bool isFree (int point)
bool isFrontier (int point)
bool isFrontierReached (int point)
bool isSameFrontier (int frontier_point1, int frontier_point2)
bool isValid (int point)
int left (int point)
bool recoveryMakePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
void resetMaps ()
int right (int point)
void saveMaps (std::string path)
void setupMapData ()
int up (int point)
int upleft (int point)
int upright (int point)

Private Attributes

costmap_2d::Costmap2D costmap_
costmap_2d::Costmap2DROScostmap_ros_
unsigned int * exploration_trans_array_
int * frontier_map_array_
bool initialized_
bool * is_goal_array_
unsigned int map_height_
unsigned int map_width_
std::string name
unsigned int num_map_cells_
unsigned int * obstacle_trans_array_
const unsigned char * occupancy_grid_array_
double p_alpha_
double p_dist_for_goal_reached_
int p_goal_angle_penalty_
int p_min_frontier_size_
int p_min_obstacle_dist_
bool p_plan_in_unknown_
double p_same_frontier_dist_
bool p_use_inflated_obs_
ros::ServiceClient path_service_client_
int previous_goal_
ros::Publisher visualization_pub_

Detailed Description

Definition at line 39 of file hector_exploration_planner.h.


Constructor & Destructor Documentation

HectorExplorationPlanner::HectorExplorationPlanner (  ) 

Definition at line 40 of file hector_exploration_planner.cpp.

HectorExplorationPlanner::~HectorExplorationPlanner (  ) 

Definition at line 53 of file hector_exploration_planner.cpp.

HectorExplorationPlanner::HectorExplorationPlanner ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
)

Definition at line 57 of file hector_exploration_planner.cpp.


Member Function Documentation

unsigned int HectorExplorationPlanner::angleDanger ( float  angle  )  [private]

M_PI;

Definition at line 1226 of file hector_exploration_planner.cpp.

float HectorExplorationPlanner::angleDifference ( const geometry_msgs::PoseStamped start,
const geometry_msgs::PoseStamped goal 
) [private]

Definition at line 1170 of file hector_exploration_planner.cpp.

float HectorExplorationPlanner::angleDifferenceWall ( const geometry_msgs::PoseStamped start,
const geometry_msgs::PoseStamped goal 
)

Definition at line 282 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::buildexploration_trans_array_ ( const geometry_msgs::PoseStamped start,
std::vector< geometry_msgs::PoseStamped goals,
bool  useAnglePenalty 
) [private]

Definition at line 539 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::buildobstacle_trans_array_ (  )  [private]

Definition at line 632 of file hector_exploration_planner.cpp.

unsigned int HectorExplorationPlanner::cellDanger ( int  point  )  [inline, private]

Definition at line 1162 of file hector_exploration_planner.cpp.

void HectorExplorationPlanner::clearFrontiers (  )  [private]

Definition at line 1086 of file hector_exploration_planner.cpp.

void HectorExplorationPlanner::deleteMapData (  )  [private]

Definition at line 518 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::doAlternativeExploration ( const geometry_msgs::PoseStamped start,
std::vector< geometry_msgs::PoseStamped > &  plan,
std::vector< geometry_msgs::PoseStamped > &  oldplan 
)

Definition at line 242 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::doExploration ( const geometry_msgs::PoseStamped start,
std::vector< geometry_msgs::PoseStamped > &  plan 
)

Given a start point, finds a frontier between known and unknown space and generates a plan to go there

Parameters:
start The start point
plan The plan to explore into unknown space

Definition at line 144 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::doInnerExploration ( const geometry_msgs::PoseStamped start,
std::vector< geometry_msgs::PoseStamped > &  plan 
)

This can be used if there are no frontiers to unknown space left in the map. The robot will retrieve it's path travelled so far via a service and try to go to places having a large distance to this path.

Parameters:
start The start point
plan The plan to explore into unknown space

Definition at line 192 of file hector_exploration_planner.cpp.

int HectorExplorationPlanner::down ( int  point  )  [inline, private]

Definition at line 1316 of file hector_exploration_planner.cpp.

int HectorExplorationPlanner::downleft ( int  point  )  [inline, private]

Definition at line 1323 of file hector_exploration_planner.cpp.

int HectorExplorationPlanner::downright ( int  point  )  [inline, private]

Definition at line 1309 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::exploreWalls ( const geometry_msgs::PoseStamped start,
std::vector< geometry_msgs::PoseStamped > &  goals 
)

Definition at line 306 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::findFrontiers ( std::vector< geometry_msgs::PoseStamped > &  frontiers  ) 

Definition at line 766 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::findFrontiers ( std::vector< geometry_msgs::PoseStamped > &  frontiers,
std::vector< geometry_msgs::PoseStamped > &  noFrontiers 
)

Definition at line 775 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::findInnerFrontier ( std::vector< geometry_msgs::PoseStamped > &  innerFrontier  ) 

Definition at line 924 of file hector_exploration_planner.cpp.

void HectorExplorationPlanner::getAdjacentPoints ( int  point,
int  points[] 
) [inline, private]

Definition at line 1263 of file hector_exploration_planner.cpp.

void HectorExplorationPlanner::getDiagonalPoints ( int  point,
int  points[] 
) [inline, private]

Definition at line 1254 of file hector_exploration_planner.cpp.

float HectorExplorationPlanner::getDistanceWeight ( const geometry_msgs::PoseStamped point1,
const geometry_msgs::PoseStamped point2 
) [private]

Definition at line 1232 of file hector_exploration_planner.cpp.

void HectorExplorationPlanner::getStraightPoints ( int  point,
int  points[] 
) [inline, private]

Definition at line 1245 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::getTrajectory ( const geometry_msgs::PoseStamped start,
std::vector< geometry_msgs::PoseStamped goals,
std::vector< geometry_msgs::PoseStamped > &  plan 
) [private]

Definition at line 692 of file hector_exploration_planner.cpp.

double HectorExplorationPlanner::getYawToUnknown ( int  point  )  [private]

Definition at line 1198 of file hector_exploration_planner.cpp.

void HectorExplorationPlanner::initialize ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
)

Definition at line 62 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::isFree ( int  point  )  [private]

Definition at line 1094 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::isFrontier ( int  point  )  [private]

Definition at line 1049 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::isFrontierReached ( int  point  )  [private]

Definition at line 1117 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::isSameFrontier ( int  frontier_point1,
int  frontier_point2 
) [private]

Definition at line 1143 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::isValid ( int  point  )  [inline, private]

Definition at line 1090 of file hector_exploration_planner.cpp.

int HectorExplorationPlanner::left ( int  point  )  [inline, private]

Definition at line 1276 of file hector_exploration_planner.cpp.

bool HectorExplorationPlanner::makePlan ( const geometry_msgs::PoseStamped start,
const geometry_msgs::PoseStamped goal,
std::vector< geometry_msgs::PoseStamped > &  plan 
)

Plans from start to given goal. If orientation quaternion of goal is all zeros, calls exploration instead. This is a hacky workaround that has to be refactored.

Parameters:
start The start point
goal The goal point (Use orientation quaternion all 0 to let exploration find goal point)
plan The generated plan

Definition at line 101 of file hector_exploration_planner.cpp.

bool hector_exploration_planner::HectorExplorationPlanner::recoveryMakePlan ( const geometry_msgs::PoseStamped start,
const geometry_msgs::PoseStamped goal,
std::vector< geometry_msgs::PoseStamped > &  plan 
) [private]
void HectorExplorationPlanner::resetMaps (  )  [private]

Definition at line 1080 of file hector_exploration_planner.cpp.

int HectorExplorationPlanner::right ( int  point  )  [inline, private]

Definition at line 1302 of file hector_exploration_planner.cpp.

void hector_exploration_planner::HectorExplorationPlanner::saveMaps ( std::string  path  )  [private]
void HectorExplorationPlanner::setupMapData (  )  [private]

Updates costmap data and resizes internal data structures if costmap size has changed. Should be called once before every planning command

Definition at line 494 of file hector_exploration_planner.cpp.

int HectorExplorationPlanner::up ( int  point  )  [inline, private]

Definition at line 1290 of file hector_exploration_planner.cpp.

int HectorExplorationPlanner::upleft ( int  point  )  [inline, private]

Definition at line 1283 of file hector_exploration_planner.cpp.

int HectorExplorationPlanner::upright ( int  point  )  [inline, private]

Definition at line 1296 of file hector_exploration_planner.cpp.


Member Data Documentation

Definition at line 118 of file hector_exploration_planner.h.

Definition at line 117 of file hector_exploration_planner.h.

Definition at line 121 of file hector_exploration_planner.h.

Definition at line 123 of file hector_exploration_planner.h.

Definition at line 126 of file hector_exploration_planner.h.

Definition at line 124 of file hector_exploration_planner.h.

Definition at line 131 of file hector_exploration_planner.h.

Definition at line 130 of file hector_exploration_planner.h.

Definition at line 129 of file hector_exploration_planner.h.

Definition at line 132 of file hector_exploration_planner.h.

Definition at line 122 of file hector_exploration_planner.h.

Definition at line 120 of file hector_exploration_planner.h.

Definition at line 140 of file hector_exploration_planner.h.

Definition at line 141 of file hector_exploration_planner.h.

Definition at line 137 of file hector_exploration_planner.h.

Definition at line 139 of file hector_exploration_planner.h.

Definition at line 138 of file hector_exploration_planner.h.

Definition at line 135 of file hector_exploration_planner.h.

Definition at line 142 of file hector_exploration_planner.h.

Definition at line 136 of file hector_exploration_planner.h.

Definition at line 116 of file hector_exploration_planner.h.

Definition at line 127 of file hector_exploration_planner.h.

Definition at line 115 of file hector_exploration_planner.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


hector_exploration_planner
Author(s): Mark Sollweck, Stefan Kohlbrecher, Florian Berz
autogenerated on Tue Mar 5 13:02:02 2013