$search

SBPLCartPlanner Class Reference

#include <sbpl_cart_planner.h>

Inheritance diagram for SBPLCartPlanner:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros)
 Initialization function for the SBPLCartPlanner object.
virtual 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.
 SBPLCartPlanner (std::string name, costmap_2d::Costmap2DROS *costmap_ros)
 Constructor for the SBPLCartPlanner object.
 SBPLCartPlanner ()
 Default constructor for the NavFnROS object.
virtual ~SBPLCartPlanner ()

Private Member Functions

bool clearFootprint (const geometry_msgs::Pose &robot_pose, const std::vector< geometry_msgs::Point > &footprint)
void convertPathToMarkerArray (const std::vector< EnvNAVXYTHETACARTLAT3Dpt_t > &sbpl_path, const std::string &path_frame_id, visualization_msgs::MarkerArray &ma)
unsigned char costMapCostToSBPLCost (unsigned char newcost)
void getFootprintList (const std::vector< EnvNAVXYTHETACARTLAT3Dpt_t > &sbpl_path, const std::string &path_frame_id, visualization_msgs::MarkerArray &ma)
geometry_msgs::Pose getGlobalCartPose (const geometry_msgs::Pose &robot_pose, const double &cart_angle)
geometry_msgs::Pose getGlobalCartPose (const EnvNAVXYTHETACARTLAT3Dpt_t &sbpl_pose)
geometry_msgs::Pose getLocalCartControlFramePose (const EnvNAVXYTHETACARTLAT3Dpt_t &sbpl_pose)
geometry_msgs::Pose getLocalCartPose (const EnvNAVXYTHETACARTLAT3Dpt_t &sbpl_pose)
void getOrientedFootprint (const geometry_msgs::Pose &robot_pose, const std::vector< geometry_msgs::Point > &footprint, std::vector< geometry_msgs::Point > &oriented_footprint)
std::vector< geometry_msgs::PointloadRobotFootprint (ros::NodeHandle node)
double sign (double x)
void transformFootprintToEdges (const geometry_msgs::Pose &robot_pose, const std::vector< geometry_msgs::Point > &footprint, std::vector< geometry_msgs::Point > &out_footprint)

Private Attributes

double allocated_time_
sbpl_2Dpt_t cart_cp_offset_
std::vector< geometry_msgs::Pointcart_footprint_
sbpl_2Dpt_t cart_offset_
costmap_2d::Costmap2D cost_map_
std::string cost_map_topic_
costmap_2d::Costmap2DROScostmap_ros_
EnvironmentNAVXYTHETACARTLATenv_
std::string environment_type_
std::vector< geometry_msgs::Pointfootprint_
int force_scratch_limit_
bool forward_search_
double initial_epsilon_
bool initialized_
unsigned char inscribed_inflated_obstacle_
unsigned char lethal_obstacle_
unsigned int num_sbpl_markers_
ros::Publisher plan_pub_
SBPLPlannerplanner_
std::string planner_type_
std::string primitive_filename_
std::vector< geometry_msgs::Pointrobot_footprint_
unsigned char sbpl_cost_multiplier_
ros::Publisher sbpl_plan_footprint_pub_
ros::Publisher sbpl_plan_pub_
ros::Publisher sbpl_robot_cart_plan_pub_
ros::Publisher stats_publisher_
int visualizer_skip_poses_

Detailed Description

Definition at line 67 of file sbpl_cart_planner.h.


Constructor & Destructor Documentation

SBPLCartPlanner::SBPLCartPlanner (  ) 

Default constructor for the NavFnROS object.

Definition at line 82 of file sbpl_cart_planner.cpp.

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

Constructor for the SBPLCartPlanner object.

Parameters:
name The name of this planner
costmap_ros A pointer to the ROS wrapper of the costmap to use

Definition at line 86 of file sbpl_cart_planner.cpp.

virtual SBPLCartPlanner::~SBPLCartPlanner (  )  [inline, virtual]

Definition at line 103 of file sbpl_cart_planner.h.


Member Function Documentation

bool SBPLCartPlanner::clearFootprint ( const geometry_msgs::Pose robot_pose,
const std::vector< geometry_msgs::Point > &  footprint 
) [private]

Definition at line 797 of file sbpl_cart_planner.cpp.

void SBPLCartPlanner::convertPathToMarkerArray ( const std::vector< EnvNAVXYTHETACARTLAT3Dpt_t > &  sbpl_path,
const std::string &  path_frame_id,
visualization_msgs::MarkerArray ma 
) [private]

Definition at line 592 of file sbpl_cart_planner.cpp.

unsigned char SBPLCartPlanner::costMapCostToSBPLCost ( unsigned char  newcost  )  [private]

Definition at line 292 of file sbpl_cart_planner.cpp.

void SBPLCartPlanner::getFootprintList ( const std::vector< EnvNAVXYTHETACARTLAT3Dpt_t > &  sbpl_path,
const std::string &  path_frame_id,
visualization_msgs::MarkerArray ma 
) [private]

Definition at line 709 of file sbpl_cart_planner.cpp.

geometry_msgs::Pose SBPLCartPlanner::getGlobalCartPose ( const geometry_msgs::Pose robot_pose,
const double &  cart_angle 
) [private]

Definition at line 828 of file sbpl_cart_planner.cpp.

geometry_msgs::Pose SBPLCartPlanner::getGlobalCartPose ( const EnvNAVXYTHETACARTLAT3Dpt_t sbpl_pose  )  [private]

Definition at line 669 of file sbpl_cart_planner.cpp.

geometry_msgs::Pose SBPLCartPlanner::getLocalCartControlFramePose ( const EnvNAVXYTHETACARTLAT3Dpt_t sbpl_pose  )  [private]

Definition at line 683 of file sbpl_cart_planner.cpp.

geometry_msgs::Pose SBPLCartPlanner::getLocalCartPose ( const EnvNAVXYTHETACARTLAT3Dpt_t sbpl_pose  )  [private]

Definition at line 696 of file sbpl_cart_planner.cpp.

void SBPLCartPlanner::getOrientedFootprint ( const geometry_msgs::Pose robot_pose,
const std::vector< geometry_msgs::Point > &  footprint,
std::vector< geometry_msgs::Point > &  oriented_footprint 
) [private]

Definition at line 814 of file sbpl_cart_planner.cpp.

void SBPLCartPlanner::initialize ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
) [virtual]

Initialization function for the SBPLCartPlanner object.

Parameters:
name The name of this planner
costmap_ros A pointer to the ROS wrapper of the costmap to use

Implements nav_core::BaseGlobalPlanner.

Definition at line 95 of file sbpl_cart_planner.cpp.

std::vector< geometry_msgs::Point > SBPLCartPlanner::loadRobotFootprint ( ros::NodeHandle  node  )  [private]

Definition at line 305 of file sbpl_cart_planner.cpp.

bool SBPLCartPlanner::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:
start The start pose
goal The goal pose
plan The plan... filled by the planner
Returns:
True if a valid plan was found, false otherwise

Implements nav_core::BaseGlobalPlanner.

Definition at line 359 of file sbpl_cart_planner.cpp.

double SBPLCartPlanner::sign ( double  x  )  [private]

Definition at line 77 of file sbpl_cart_planner.cpp.

void SBPLCartPlanner::transformFootprintToEdges ( const geometry_msgs::Pose robot_pose,
const std::vector< geometry_msgs::Point > &  footprint,
std::vector< geometry_msgs::Point > &  out_footprint 
) [private]

Definition at line 773 of file sbpl_cart_planner.cpp.


Member Data Documentation

amount of time allowed for search

Definition at line 113 of file sbpl_cart_planner.h.

Definition at line 133 of file sbpl_cart_planner.h.

Definition at line 139 of file sbpl_cart_planner.h.

Definition at line 133 of file sbpl_cart_planner.h.

local copy of the costmap underlying cost_map_ros_

Definition at line 125 of file sbpl_cart_planner.h.

std::string SBPLCartPlanner::cost_map_topic_ [private]

what type of environment in which to plan. choices are 2D and XYThetaLattice.

Definition at line 117 of file sbpl_cart_planner.h.

the number of cells that have to be changed in the costmap to force the planner to plan from scratch even if its an incremental planner manages the cost map for us

Definition at line 124 of file sbpl_cart_planner.h.

Definition at line 109 of file sbpl_cart_planner.h.

std::string SBPLCartPlanner::environment_type_ [private]

Definition at line 116 of file sbpl_cart_planner.h.

Definition at line 129 of file sbpl_cart_planner.h.

where to find the motion primitives for the current robot

Definition at line 121 of file sbpl_cart_planner.h.

what topic is being used for the costmap topic

Definition at line 119 of file sbpl_cart_planner.h.

initial epsilon for beginning the anytime search

Definition at line 114 of file sbpl_cart_planner.h.

Definition at line 103 of file sbpl_cart_planner.h.

Definition at line 165 of file sbpl_cart_planner.h.

unsigned char SBPLCartPlanner::lethal_obstacle_ [private]

Definition at line 164 of file sbpl_cart_planner.h.

unsigned int SBPLCartPlanner::num_sbpl_markers_ [private]

Definition at line 166 of file sbpl_cart_planner.h.

Definition at line 127 of file sbpl_cart_planner.h.

Definition at line 108 of file sbpl_cart_planner.h.

std::string SBPLCartPlanner::planner_type_ [private]

sbpl method to use for planning. choices are ARAPlanner and ADPlanner

Definition at line 111 of file sbpl_cart_planner.h.

std::string SBPLCartPlanner::primitive_filename_ [private]

whether to use forward or backward search

Definition at line 120 of file sbpl_cart_planner.h.

Definition at line 139 of file sbpl_cart_planner.h.

unsigned char SBPLCartPlanner::sbpl_cost_multiplier_ [private]

Definition at line 163 of file sbpl_cart_planner.h.

Definition at line 127 of file sbpl_cart_planner.h.

Definition at line 127 of file sbpl_cart_planner.h.

Definition at line 127 of file sbpl_cart_planner.h.

Definition at line 127 of file sbpl_cart_planner.h.

Definition at line 167 of file sbpl_cart_planner.h.


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


sbpl_cart_planner
Author(s): Sachin Chitta
autogenerated on Fri Mar 1 14:53:13 2013