Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
global_planner::GlobalPlanner Class Reference

#include <planner_core.h>

Inheritance diagram for global_planner::GlobalPlanner:
Inheritance graph
[legend]

Public Member Functions

bool computePotential (const geometry_msgs::Point &world_point)
 Computes the full navigation function for the map given a point in the world to start from. More...
 
bool getPlanFromPotential (double start_x, double start_y, double end_x, double end_y, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
 Compute a plan to a goal after the potential for a start point has already been computed (Note: You should call computePotential first) More...
 
double getPointPotential (const geometry_msgs::Point &world_point)
 Get the potential, or naviagation cost, at a given point in the world (Note: You should call computePotential first) More...
 
 GlobalPlanner ()
 Default constructor for the PlannerCore object. More...
 
 GlobalPlanner (std::string name, costmap_2d::Costmap2D *costmap, std::string frame_id)
 Constructor for the PlannerCore object. More...
 
void initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros)
 Initialization function for the PlannerCore object. More...
 
void initialize (std::string name, costmap_2d::Costmap2D *costmap, std::string frame_id)
 
bool makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
 Given a goal pose in the world, compute a plan. More...
 
bool makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance, std::vector< geometry_msgs::PoseStamped > &plan)
 Given a goal pose in the world, compute a plan. More...
 
bool makePlanService (nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp)
 
void publishPlan (const std::vector< geometry_msgs::PoseStamped > &path)
 Publish a path for visualization purposes. More...
 
bool validPointPotential (const geometry_msgs::Point &world_point)
 Check for a valid potential value at a given point in the world (Note: You should call computePotential first) More...
 
bool validPointPotential (const geometry_msgs::Point &world_point, double tolerance)
 Check for a valid potential value at a given point in the world (Note: You should call computePotential first) More...
 
 ~GlobalPlanner ()
 Default deconstructor for the PlannerCore object. More...
 
- Public Member Functions inherited from nav_core::BaseGlobalPlanner
virtual bool makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan, double &cost)
 
virtual ~BaseGlobalPlanner ()
 

Protected Attributes

bool allow_unknown_
 
costmap_2d::Costmap2Dcostmap_
 Store a copy of the current costmap in costmap. Called by makePlan. More...
 
std::string frame_id_
 
bool initialized_
 
ros::Publisher plan_pub_
 

Private Member Functions

void clearRobotCell (const tf::Stamped< tf::Pose > &global_pose, unsigned int mx, unsigned int my)
 
void mapToWorld (double mx, double my, double &wx, double &wy)
 
void outlineMap (unsigned char *costarr, int nx, int ny, unsigned char value)
 
void publishPotential (float *potential)
 
void reconfigureCB (global_planner::GlobalPlannerConfig &config, uint32_t level)
 
bool worldToMap (double wx, double wy, double &mx, double &my)
 

Private Attributes

float convert_offset_
 
double default_tolerance_
 
dynamic_reconfigure::Server< global_planner::GlobalPlannerConfig > * dsrv_
 
unsigned int end_x_
 
unsigned int end_y_
 
ros::ServiceServer make_plan_srv_
 
boost::mutex mutex_
 
bool old_navfn_behavior_
 
OrientationFilterorientation_filter_
 
PotentialCalculatorp_calc_
 
Tracebackpath_maker_
 
Expanderplanner_
 
double planner_window_x_
 
double planner_window_y_
 
float * potential_array_
 
ros::Publisher potential_pub_
 
bool publish_potential_
 
int publish_scale_
 
unsigned int start_x_
 
unsigned int start_y_
 
std::string tf_prefix_
 

Additional Inherited Members

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

Detailed Description

Definition at line 67 of file planner_core.h.

Constructor & Destructor Documentation

global_planner::GlobalPlanner::GlobalPlanner ( )

Default constructor for the PlannerCore object.

Definition at line 70 of file planner_core.cpp.

global_planner::GlobalPlanner::GlobalPlanner ( std::string  name,
costmap_2d::Costmap2D costmap,
std::string  frame_id 
)

Constructor for the PlannerCore object.

Parameters
nameThe name of this planner
costmapA pointer to the costmap to use
frame_idFrame of the costmap

Definition at line 76 of file planner_core.cpp.

global_planner::GlobalPlanner::~GlobalPlanner ( )

Default deconstructor for the PlannerCore object.

Definition at line 84 of file planner_core.cpp.

Member Function Documentation

void global_planner::GlobalPlanner::clearRobotCell ( const tf::Stamped< tf::Pose > &  global_pose,
unsigned int  mx,
unsigned int  my 
)
private

Definition at line 178 of file planner_core.cpp.

bool global_planner::GlobalPlanner::computePotential ( const geometry_msgs::Point world_point)

Computes the full navigation function for the map given a point in the world to start from.

Parameters
world_pointThe point to use for seeding the navigation function
Returns
True if the navigation function was computed successfully, false otherwise
bool global_planner::GlobalPlanner::getPlanFromPotential ( double  start_x,
double  start_y,
double  end_x,
double  end_y,
const geometry_msgs::PoseStamped &  goal,
std::vector< geometry_msgs::PoseStamped > &  plan 
)

Compute a plan to a goal after the potential for a start point has already been computed (Note: You should call computePotential first)

Parameters
start_x
start_y
end_x
end_y
goalThe goal pose to create a plan to
planThe plan... filled by the planner
Returns
True if a valid plan was found, false otherwise

Definition at line 353 of file planner_core.cpp.

double global_planner::GlobalPlanner::getPointPotential ( const geometry_msgs::Point world_point)

Get the potential, or naviagation cost, at a given point in the world (Note: You should call computePotential first)

Parameters
world_pointThe point to get the potential for
Returns
The navigation function's value at that point in the world
void global_planner::GlobalPlanner::initialize ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
)
virtual

Initialization function for the PlannerCore object.

Parameters
nameThe name of this planner
costmap_rosA pointer to the ROS wrapper of the costmap to use for planning

Implements nav_core::BaseGlobalPlanner.

Definition at line 95 of file planner_core.cpp.

void global_planner::GlobalPlanner::initialize ( std::string  name,
costmap_2d::Costmap2D costmap,
std::string  frame_id 
)

Definition at line 99 of file planner_core.cpp.

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

Given a goal pose in the world, compute a plan.

Parameters
startThe start pose
goalThe goal pose
planThe plan... filled by the planner
Returns
True if a valid plan was found, false otherwise

Implements nav_core::BaseGlobalPlanner.

Definition at line 219 of file planner_core.cpp.

bool global_planner::GlobalPlanner::makePlan ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
double  tolerance,
std::vector< geometry_msgs::PoseStamped > &  plan 
)

Given a goal pose in the world, compute a plan.

Parameters
startThe start pose
goalThe goal pose
toleranceThe tolerance on the goal point for the planner
planThe plan... filled by the planner
Returns
True if a valid plan was found, false otherwise

Definition at line 224 of file planner_core.cpp.

bool global_planner::GlobalPlanner::makePlanService ( nav_msgs::GetPlan::Request &  req,
nav_msgs::GetPlan::Response &  resp 
)

Definition at line 189 of file planner_core.cpp.

void global_planner::GlobalPlanner::mapToWorld ( double  mx,
double  my,
double &  wx,
double &  wy 
)
private

Definition at line 198 of file planner_core.cpp.

void global_planner::GlobalPlanner::outlineMap ( unsigned char *  costarr,
int  nx,
int  ny,
unsigned char  value 
)
private

Definition at line 55 of file planner_core.cpp.

void global_planner::GlobalPlanner::publishPlan ( const std::vector< geometry_msgs::PoseStamped > &  path)

Publish a path for visualization purposes.

Definition at line 331 of file planner_core.cpp.

void global_planner::GlobalPlanner::publishPotential ( float *  potential)
private

Definition at line 399 of file planner_core.cpp.

void global_planner::GlobalPlanner::reconfigureCB ( global_planner::GlobalPlannerConfig &  config,
uint32_t  level 
)
private

Definition at line 168 of file planner_core.cpp.

bool global_planner::GlobalPlanner::validPointPotential ( const geometry_msgs::Point world_point)

Check for a valid potential value at a given point in the world (Note: You should call computePotential first)

Parameters
world_pointThe point to get the potential for
Returns
True if the navigation function is valid at that point in the world, false otherwise
bool global_planner::GlobalPlanner::validPointPotential ( const geometry_msgs::Point world_point,
double  tolerance 
)

Check for a valid potential value at a given point in the world (Note: You should call computePotential first)

Parameters
world_pointThe point to get the potential for
toleranceThe tolerance on searching around the world_point specified
Returns
True if the navigation function is valid at that point in the world, false otherwise
bool global_planner::GlobalPlanner::worldToMap ( double  wx,
double  wy,
double &  mx,
double &  my 
)
private

Definition at line 203 of file planner_core.cpp.

Member Data Documentation

bool global_planner::GlobalPlanner::allow_unknown_
protected

Definition at line 175 of file planner_core.h.

float global_planner::GlobalPlanner::convert_offset_
private

Definition at line 203 of file planner_core.h.

costmap_2d::Costmap2D* global_planner::GlobalPlanner::costmap_
protected

Store a copy of the current costmap in costmap. Called by makePlan.

Definition at line 172 of file planner_core.h.

double global_planner::GlobalPlanner::default_tolerance_
private

Definition at line 183 of file planner_core.h.

dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig>* global_planner::GlobalPlanner::dsrv_
private

Definition at line 205 of file planner_core.h.

unsigned int global_planner::GlobalPlanner::end_x_
private

Definition at line 200 of file planner_core.h.

unsigned int global_planner::GlobalPlanner::end_y_
private

Definition at line 200 of file planner_core.h.

std::string global_planner::GlobalPlanner::frame_id_
protected

Definition at line 173 of file planner_core.h.

bool global_planner::GlobalPlanner::initialized_
protected

Definition at line 175 of file planner_core.h.

ros::ServiceServer global_planner::GlobalPlanner::make_plan_srv_
private

Definition at line 186 of file planner_core.h.

boost::mutex global_planner::GlobalPlanner::mutex_
private

Definition at line 185 of file planner_core.h.

bool global_planner::GlobalPlanner::old_navfn_behavior_
private

Definition at line 202 of file planner_core.h.

OrientationFilter* global_planner::GlobalPlanner::orientation_filter_
private

Definition at line 191 of file planner_core.h.

PotentialCalculator* global_planner::GlobalPlanner::p_calc_
private

Definition at line 188 of file planner_core.h.

Traceback* global_planner::GlobalPlanner::path_maker_
private

Definition at line 190 of file planner_core.h.

ros::Publisher global_planner::GlobalPlanner::plan_pub_
protected

Definition at line 174 of file planner_core.h.

Expander* global_planner::GlobalPlanner::planner_
private

Definition at line 189 of file planner_core.h.

double global_planner::GlobalPlanner::planner_window_x_
private

Definition at line 183 of file planner_core.h.

double global_planner::GlobalPlanner::planner_window_y_
private

Definition at line 183 of file planner_core.h.

float* global_planner::GlobalPlanner::potential_array_
private

Definition at line 199 of file planner_core.h.

ros::Publisher global_planner::GlobalPlanner::potential_pub_
private

Definition at line 194 of file planner_core.h.

bool global_planner::GlobalPlanner::publish_potential_
private

Definition at line 193 of file planner_core.h.

int global_planner::GlobalPlanner::publish_scale_
private

Definition at line 195 of file planner_core.h.

unsigned int global_planner::GlobalPlanner::start_x_
private

Definition at line 200 of file planner_core.h.

unsigned int global_planner::GlobalPlanner::start_y_
private

Definition at line 200 of file planner_core.h.

std::string global_planner::GlobalPlanner::tf_prefix_
private

Definition at line 184 of file planner_core.h.


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


global_planner
Author(s): David Lu!!
autogenerated on Thu Jan 21 2021 04:06:07