Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes
SBPLPlanner2D Class Reference

#include <SBPLPlanner2D.h>

List of all members.

Public Member Functions

const nav_msgs::Path & getPath () const
void goalCallback (const geometry_msgs::PoseStampedConstPtr &goal)
 Set goal and plan when start was already set.
void mapCallback (const nav_msgs::OccupancyGridConstPtr &occupancy_map)
 calls updateMap()
bool plan (const geometry_msgs::Pose &start, const geometry_msgs::Pose &goal)
 SBPLPlanner2D ()
void startCallback (const geometry_msgs::PoseWithCovarianceStampedConstPtr &start)
 Set start and plan when goal was already set.
bool updateMap (gridmap_2d::GridMap2DPtr map)
 Setup the internal map representation and initialize the SBPL planning environment.
virtual ~SBPLPlanner2D ()

Protected Member Functions

bool plan ()
void setPlanner ()
 (re)sets the planner

Protected Attributes

double allocated_time_
bool forward_search_
geometry_msgs::Pose goal_pose_
bool goal_received_
ros::Subscriber goal_sub_
double initial_epsilon_
gridmap_2d::GridMap2DPtr map_
ros::Subscriber map_sub_
ros::NodeHandle nh_
nav_msgs::Path path_
ros::Publisher path_pub_
boost::shared_ptr< SBPLPlanner > planner_
boost::shared_ptr
< EnvironmentNAV2D > 
planner_environment_
std::string planner_type_
double robot_radius_
bool search_until_first_solution_
geometry_msgs::Pose start_pose_
bool start_received_
ros::Subscriber start_sub_

Static Protected Attributes

static const unsigned char OBSTACLE_COST = 20

Detailed Description

Definition at line 41 of file SBPLPlanner2D.h.


Constructor & Destructor Documentation

Definition at line 31 of file SBPLPlanner2D.cpp.

Definition at line 50 of file SBPLPlanner2D.cpp.


Member Function Documentation

const nav_msgs::Path& SBPLPlanner2D::getPath ( ) const [inline]

Definition at line 64 of file SBPLPlanner2D.h.

void SBPLPlanner2D::goalCallback ( const geometry_msgs::PoseStampedConstPtr &  goal)

Set goal and plan when start was already set.

Definition at line 54 of file SBPLPlanner2D.cpp.

void SBPLPlanner2D::mapCallback ( const nav_msgs::OccupancyGridConstPtr &  occupancy_map)

calls updateMap()

Definition at line 164 of file SBPLPlanner2D.cpp.

bool SBPLPlanner2D::plan ( const geometry_msgs::Pose start,
const geometry_msgs::Pose goal 
)

Plans from start to goal, assuming that the map was set with updateMap(). When successful, you can retrieve the path with getPath().

Parameters:
start
goal
Returns:
success of planning

Definition at line 84 of file SBPLPlanner2D.cpp.

bool SBPLPlanner2D::plan ( ) [protected]

Definition at line 94 of file SBPLPlanner2D.cpp.

void SBPLPlanner2D::setPlanner ( ) [protected]

(re)sets the planner

Definition at line 194 of file SBPLPlanner2D.cpp.

void SBPLPlanner2D::startCallback ( const geometry_msgs::PoseWithCovarianceStampedConstPtr &  start)

Set start and plan when goal was already set.

Definition at line 69 of file SBPLPlanner2D.cpp.

Setup the internal map representation and initialize the SBPL planning environment.

Definition at line 169 of file SBPLPlanner2D.cpp.


Member Data Documentation

double SBPLPlanner2D::allocated_time_ [protected]

Definition at line 77 of file SBPLPlanner2D.h.

Definition at line 80 of file SBPLPlanner2D.h.

Definition at line 84 of file SBPLPlanner2D.h.

Definition at line 83 of file SBPLPlanner2D.h.

Definition at line 70 of file SBPLPlanner2D.h.

double SBPLPlanner2D::initial_epsilon_ [protected]

Definition at line 78 of file SBPLPlanner2D.h.

Definition at line 74 of file SBPLPlanner2D.h.

Definition at line 70 of file SBPLPlanner2D.h.

Definition at line 69 of file SBPLPlanner2D.h.

const unsigned char SBPLPlanner2D::OBSTACLE_COST = 20 [static, protected]

Definition at line 87 of file SBPLPlanner2D.h.

nav_msgs::Path SBPLPlanner2D::path_ [protected]

Definition at line 85 of file SBPLPlanner2D.h.

Definition at line 71 of file SBPLPlanner2D.h.

boost::shared_ptr<SBPLPlanner> SBPLPlanner2D::planner_ [protected]

Definition at line 72 of file SBPLPlanner2D.h.

boost::shared_ptr<EnvironmentNAV2D> SBPLPlanner2D::planner_environment_ [protected]

Definition at line 73 of file SBPLPlanner2D.h.

std::string SBPLPlanner2D::planner_type_ [protected]

Definition at line 76 of file SBPLPlanner2D.h.

double SBPLPlanner2D::robot_radius_ [protected]

Definition at line 81 of file SBPLPlanner2D.h.

Definition at line 79 of file SBPLPlanner2D.h.

Definition at line 84 of file SBPLPlanner2D.h.

Definition at line 83 of file SBPLPlanner2D.h.

Definition at line 70 of file SBPLPlanner2D.h.


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


humanoid_planner_2d
Author(s): Armin Hornung
autogenerated on Mon Oct 6 2014 00:42:04