SBPLCartPlanner Class Reference

#include <sbpl_cart_planner.h>

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::Point > loadRobotFootprint (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::Point > cart_footprint_
sbpl_2Dpt_t cart_offset_
costmap_2d::Costmap2D cost_map_
std::string cost_map_topic_
costmap_2d::Costmap2DROS * costmap_ros_
EnvironmentNAVXYTHETACARTLATenv_
std::string environment_type_
std::vector< geometry_msgs::Point > footprint_
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_
SBPLPlanner * planner_
std::string planner_type_
std::string primitive_filename_
std::vector< geometry_msgs::Point > robot_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

ROS

Definition at line 61 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 96 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 796 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 591 of file sbpl_cart_planner.cpp.

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

Definition at line 286 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 708 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 827 of file sbpl_cart_planner.cpp.

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

Definition at line 668 of file sbpl_cart_planner.cpp.

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

Definition at line 682 of file sbpl_cart_planner.cpp.

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

Definition at line 695 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 813 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

Definition at line 94 of file sbpl_cart_planner.cpp.

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

Definition at line 299 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

Definition at line 353 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 772 of file sbpl_cart_planner.cpp.


Member Data Documentation

amount of time allowed for search

Definition at line 106 of file sbpl_cart_planner.h.

sbpl_2Dpt_t SBPLCartPlanner::cart_cp_offset_ [private]

Definition at line 126 of file sbpl_cart_planner.h.

std::vector<geometry_msgs::Point> SBPLCartPlanner::cart_footprint_ [private]

Definition at line 132 of file sbpl_cart_planner.h.

sbpl_2Dpt_t SBPLCartPlanner::cart_offset_ [private]

Definition at line 126 of file sbpl_cart_planner.h.

costmap_2d::Costmap2D SBPLCartPlanner::cost_map_ [private]

local copy of the costmap underlying cost_map_ros_

Definition at line 118 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 110 of file sbpl_cart_planner.h.

costmap_2d::Costmap2DROS* SBPLCartPlanner::costmap_ros_ [private]

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 117 of file sbpl_cart_planner.h.

Definition at line 102 of file sbpl_cart_planner.h.

std::string SBPLCartPlanner::environment_type_ [private]

Definition at line 109 of file sbpl_cart_planner.h.

std::vector<geometry_msgs::Point> SBPLCartPlanner::footprint_ [private]

Definition at line 122 of file sbpl_cart_planner.h.

where to find the motion primitives for the current robot

Definition at line 114 of file sbpl_cart_planner.h.

what topic is being used for the costmap topic

Definition at line 112 of file sbpl_cart_planner.h.

initial epsilon for beginning the anytime search

Definition at line 107 of file sbpl_cart_planner.h.

Definition at line 96 of file sbpl_cart_planner.h.

Definition at line 158 of file sbpl_cart_planner.h.

unsigned char SBPLCartPlanner::lethal_obstacle_ [private]

Definition at line 157 of file sbpl_cart_planner.h.

unsigned int SBPLCartPlanner::num_sbpl_markers_ [private]

Definition at line 159 of file sbpl_cart_planner.h.

ros::Publisher SBPLCartPlanner::plan_pub_ [private]

Definition at line 120 of file sbpl_cart_planner.h.

SBPLPlanner* SBPLCartPlanner::planner_ [private]

Definition at line 101 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 104 of file sbpl_cart_planner.h.

std::string SBPLCartPlanner::primitive_filename_ [private]

whether to use forward or backward search

Definition at line 113 of file sbpl_cart_planner.h.

std::vector<geometry_msgs::Point> SBPLCartPlanner::robot_footprint_ [private]

Definition at line 132 of file sbpl_cart_planner.h.

unsigned char SBPLCartPlanner::sbpl_cost_multiplier_ [private]

Definition at line 156 of file sbpl_cart_planner.h.

Definition at line 120 of file sbpl_cart_planner.h.

ros::Publisher SBPLCartPlanner::sbpl_plan_pub_ [private]

Definition at line 120 of file sbpl_cart_planner.h.

Definition at line 120 of file sbpl_cart_planner.h.

ros::Publisher SBPLCartPlanner::stats_publisher_ [private]

Definition at line 120 of file sbpl_cart_planner.h.

Definition at line 160 of file sbpl_cart_planner.h.


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


sbpl_cart_planner
Author(s): Sachin Chitta
autogenerated on Fri Jan 11 10:03:37 2013