Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
rsband_local_planner::ReedsSheppPlanner Class Reference

Planner - ROS wrapper for the Reeds-Shepp state space of OMPL. More...

#include <reeds_shepp_planner.h>

Public Types

enum  RearSteeringMode { none, counter, crab, hybrid }
 steering mode enum More...
 
enum  StateCheckingMode { center, footprint }
 state checking mode enum More...
 

Public Member Functions

double getBX ()
 
double getBY ()
 
double getMaxPlanningDuration ()
 
double getMinTurningRadius ()
 
void initialize (std::string name, costmap_2d::Costmap2DROS *costmapROS, tf::TransformListener *tfListener)
 Initializes the planner. More...
 
bool planPath (const geometry_msgs::PoseStamped &startPose, const geometry_msgs::PoseStamped &goalPose, std::vector< geometry_msgs::PoseStamped > &path)
 Plans a Reeds-Shepp path between the start and end poses. More...
 
int planPathSkipFailures (const std::vector< geometry_msgs::PoseStamped > &path, std::vector< geometry_msgs::PoseStamped > &newPath)
 Plans a series of Reeds-Shepp paths that connect the path poses. More...
 
int planPathUntilFailure (const std::vector< geometry_msgs::PoseStamped > &path, std::vector< geometry_msgs::PoseStamped > &newPath)
 Plans a series of Reeds-Shepp paths that connect the path poses. More...
 
int planRecedingPath (const std::vector< geometry_msgs::PoseStamped > &path, std::vector< geometry_msgs::PoseStamped > &newPath)
 Plans a Reeds-Shepp path between the start pose and a receding end pose. More...
 
void reconfigure (RSBandPlannerConfig &config)
 Reconfigures the parameters of the planner. More...
 
 ReedsSheppPlanner (std::string name, costmap_2d::Costmap2DROS *costmapROS, tf::TransformListener *tfListener)
 Constructor. More...
 
void setBoundaries (double bx, double by)
 
void setMaxPlanningDuration (double tmax)
 
void setMinTurningRadius (double rho)
 
 ~ReedsSheppPlanner ()
 Destructor. More...
 

Private Member Functions

bool isStateValid (const ompl::base::SpaceInformation *si, const ompl::base::State *state)
 Checks whether a state/pose is valid. More...
 
void pose2state (const geometry_msgs::PoseStamped &pose, ompl::base::State *state)
 Converts a pose msg to an ompl state. More...
 
void state2pose (const ompl::base::State *state, geometry_msgs::PoseStamped &pose)
 Converts an ompl state to a pose msg. More...
 
void transform (const geometry_msgs::PoseStamped &poseIn, geometry_msgs::PoseStamped &poseOut, std::string newFrameID)
 Transforms the given pose to the target reference frame. More...
 
void transform (const tf::Stamped< tf::Pose > &tfIn, tf::Stamped< tf::Pose > &tfOut, std::string newFrameID)
 Transforms the given pose to the target reference frame. More...
 

Private Attributes

bool allowUnknown_
 if true considers unknown costmap cells as free More...
 
ompl::base::RealVectorBounds bounds_
 planner space boundaries (should match local costmap boundaries) More...
 
double bx_
 boundary size x More...
 
double by_
 boundary size y More...
 
costmap_2d::Costmap2D * costmap_
 ptr to costmap More...
 
base_local_planner::CostmapModel * costmapModel_
 ptr to costmap model More...
 
costmap_2d::Costmap2DROS * costmapROS_
 ptr to costmap ros wrapper More...
 
bool displayPlannerOutput_
 display planning information More...
 
std::vector< geometry_msgs::Point > footprint_
 robot footprint, used in validity checking More...
 
std::string globalFrame_
 the reference frame of the costmap More...
 
bool initialized_
 is set if planner is initialized More...
 
int interpolationNumPoses_
 number of poses to interpolate in the reeds shepp path More...
 
double maxPlanningDuration_
 maximum Reeds-Shepp planning duration More...
 
double minTurningRadius_
 minimum turning radius of the robot (dependent on rear steering mode) More...
 
ompl::base::StateSpacePtr reedsSheppStateSpace_
 The ompl Reeds-Sheep state space. More...
 
std::string robotFrame_
 the reference frame of the robot base More...
 
bool robotStateValid_
 regard robot pose as free More...
 
ompl::geometric::SimpleSetupPtr simpleSetup_
 OMPL geometric simple setup object. More...
 
ros::Time stamp_
 the stamp to use in path poses More...
 
StateCheckingMode stateCheckingMode_
 state checking mode: center(0) or footprint(1) More...
 
tf::TransformListener * tfListener_
 tf transform listener More...
 
int validStateMaxCost_
 below this cost, a state is considered valid More...
 

Detailed Description

Planner - ROS wrapper for the Reeds-Shepp state space of OMPL.

Definition at line 60 of file reeds_shepp_planner.h.

Member Enumeration Documentation

steering mode enum

Enumerator
none 
counter 
crab 
hybrid 

Definition at line 156 of file reeds_shepp_planner.h.

state checking mode enum

Enumerator
center 
footprint 

Definition at line 153 of file reeds_shepp_planner.h.

Constructor & Destructor Documentation

rsband_local_planner::ReedsSheppPlanner::ReedsSheppPlanner ( std::string  name,
costmap_2d::Costmap2DROS *  costmapROS,
tf::TransformListener *  tfListener 
)

Constructor.

Parameters
nameName used to load planner parameters
costmapROSPtr to the ROS wrapper of the local costmap
tfListenerPtr to a tf transform listener

Definition at line 44 of file reeds_shepp_planner.cpp.

rsband_local_planner::ReedsSheppPlanner::~ReedsSheppPlanner ( )

Destructor.

Definition at line 58 of file reeds_shepp_planner.cpp.

Member Function Documentation

double rsband_local_planner::ReedsSheppPlanner::getBX ( )
inline

Definition at line 146 of file reeds_shepp_planner.h.

double rsband_local_planner::ReedsSheppPlanner::getBY ( )
inline

Definition at line 147 of file reeds_shepp_planner.h.

double rsband_local_planner::ReedsSheppPlanner::getMaxPlanningDuration ( )
inline

Definition at line 145 of file reeds_shepp_planner.h.

double rsband_local_planner::ReedsSheppPlanner::getMinTurningRadius ( )
inline

Definition at line 144 of file reeds_shepp_planner.h.

void rsband_local_planner::ReedsSheppPlanner::initialize ( std::string  name,
costmap_2d::Costmap2DROS *  costmapROS,
tf::TransformListener *  tfListener 
)

Initializes the planner.

Parameters
nameName used to load planner parameters
costmapROSPtr to the ROS wrapper of the local costmap
tfListenerPtr to a tf transform listener

Definition at line 64 of file reeds_shepp_planner.cpp.

bool rsband_local_planner::ReedsSheppPlanner::isStateValid ( const ompl::base::SpaceInformation *  si,
const ompl::base::State *  state 
)
private

Checks whether a state/pose is valid.

A state is valid if it is within defined boundaries and not in collision with the environment

Parameters
siPtr to an ompl space information object
statePtr to the state to check for validity
Returns
true if state is valid

Definition at line 197 of file reeds_shepp_planner.cpp.

bool rsband_local_planner::ReedsSheppPlanner::planPath ( const geometry_msgs::PoseStamped &  startPose,
const geometry_msgs::PoseStamped &  goalPose,
std::vector< geometry_msgs::PoseStamped > &  path 
)

Plans a Reeds-Shepp path between the start and end poses.

Parameters
startPoseThe start pose of the path
goalPoseThe final pose of the path
pathThe Reeds-Shepp path that will be returned
Returns
true if planning succeeds

Definition at line 250 of file reeds_shepp_planner.cpp.

int rsband_local_planner::ReedsSheppPlanner::planPathSkipFailures ( const std::vector< geometry_msgs::PoseStamped > &  path,
std::vector< geometry_msgs::PoseStamped > &  newPath 
)

Plans a series of Reeds-Shepp paths that connect the path poses.

If a subpath fails, the planner continues with the next pose

Parameters
pathContains the path poses to connect via Reeds-Shepp paths
newPathContainer for the returned path
Returns
The idx of the pose the planning failed at

Definition at line 360 of file reeds_shepp_planner.cpp.

int rsband_local_planner::ReedsSheppPlanner::planPathUntilFailure ( const std::vector< geometry_msgs::PoseStamped > &  path,
std::vector< geometry_msgs::PoseStamped > &  newPath 
)

Plans a series of Reeds-Shepp paths that connect the path poses.

If a subpath fails the function returns

Parameters
pathContains the path poses to connect via Reeds-Shepp paths
newPathContainer for the returned path
Returns
The idx of the pose the planning failed at

Definition at line 341 of file reeds_shepp_planner.cpp.

int rsband_local_planner::ReedsSheppPlanner::planRecedingPath ( const std::vector< geometry_msgs::PoseStamped > &  path,
std::vector< geometry_msgs::PoseStamped > &  newPath 
)

Plans a Reeds-Shepp path between the start pose and a receding end pose.

Each time the planner fails, it uses the immediate pose before the current end pose

Parameters
pathContains the path poses to connect via Reeds-Shepp paths
newPathContainer for the returned path
Returns
The idx of the pose the planning failed at

Definition at line 384 of file reeds_shepp_planner.cpp.

void rsband_local_planner::ReedsSheppPlanner::pose2state ( const geometry_msgs::PoseStamped &  pose,
ompl::base::State *  state 
)
private

Converts a pose msg to an ompl state.

Parameters
poseThe pose to convert to an ompl state
stateThe converted ompl state container

Definition at line 186 of file reeds_shepp_planner.cpp.

void rsband_local_planner::ReedsSheppPlanner::reconfigure ( RSBandPlannerConfig &  config)

Reconfigures the parameters of the planner.

Parameters
configThe dynamic reconfigure configuration

Definition at line 112 of file reeds_shepp_planner.cpp.

void rsband_local_planner::ReedsSheppPlanner::setBoundaries ( double  bx,
double  by 
)

Definition at line 144 of file reeds_shepp_planner.cpp.

void rsband_local_planner::ReedsSheppPlanner::setMaxPlanningDuration ( double  tmax)
inline

Definition at line 149 of file reeds_shepp_planner.h.

void rsband_local_planner::ReedsSheppPlanner::setMinTurningRadius ( double  rho)
inline

Definition at line 148 of file reeds_shepp_planner.h.

void rsband_local_planner::ReedsSheppPlanner::state2pose ( const ompl::base::State *  state,
geometry_msgs::PoseStamped &  pose 
)
private

Converts an ompl state to a pose msg.

Parameters
stateThe ompl state to convert to a pose msg
poseThe converted pose msg container

Definition at line 173 of file reeds_shepp_planner.cpp.

void rsband_local_planner::ReedsSheppPlanner::transform ( const geometry_msgs::PoseStamped &  poseIn,
geometry_msgs::PoseStamped &  poseOut,
std::string  newFrameID 
)
private

Transforms the given pose to the target reference frame.

Parameters
poseInThe given pose to transform
poseOutThe transformed pose container
newFrameIDThe target reference frame to use in the transform

Definition at line 155 of file reeds_shepp_planner.cpp.

void rsband_local_planner::ReedsSheppPlanner::transform ( const tf::Stamped< tf::Pose > &  tfIn,
tf::Stamped< tf::Pose > &  tfOut,
std::string  newFrameID 
)
private

Transforms the given pose to the target reference frame.

Parameters
tfInThe given tf pose to transform
tfOutThe transformed tf pose container
newFrameIDThe target reference frame to use in the transform

Definition at line 164 of file reeds_shepp_planner.cpp.

Member Data Documentation

bool rsband_local_planner::ReedsSheppPlanner::allowUnknown_
private

if true considers unknown costmap cells as free

Definition at line 246 of file reeds_shepp_planner.h.

ompl::base::RealVectorBounds rsband_local_planner::ReedsSheppPlanner::bounds_
private

planner space boundaries (should match local costmap boundaries)

Definition at line 211 of file reeds_shepp_planner.h.

double rsband_local_planner::ReedsSheppPlanner::bx_
private

boundary size x

Definition at line 248 of file reeds_shepp_planner.h.

double rsband_local_planner::ReedsSheppPlanner::by_
private

boundary size y

Definition at line 250 of file reeds_shepp_planner.h.

costmap_2d::Costmap2D* rsband_local_planner::ReedsSheppPlanner::costmap_
private

ptr to costmap

Definition at line 214 of file reeds_shepp_planner.h.

base_local_planner::CostmapModel* rsband_local_planner::ReedsSheppPlanner::costmapModel_
private

ptr to costmap model

Definition at line 218 of file reeds_shepp_planner.h.

costmap_2d::Costmap2DROS* rsband_local_planner::ReedsSheppPlanner::costmapROS_
private

ptr to costmap ros wrapper

Definition at line 216 of file reeds_shepp_planner.h.

bool rsband_local_planner::ReedsSheppPlanner::displayPlannerOutput_
private

display planning information

Definition at line 252 of file reeds_shepp_planner.h.

std::vector<geometry_msgs::Point> rsband_local_planner::ReedsSheppPlanner::footprint_
private

robot footprint, used in validity checking

Definition at line 220 of file reeds_shepp_planner.h.

std::string rsband_local_planner::ReedsSheppPlanner::globalFrame_
private

the reference frame of the costmap

Definition at line 228 of file reeds_shepp_planner.h.

bool rsband_local_planner::ReedsSheppPlanner::initialized_
private

is set if planner is initialized

Definition at line 255 of file reeds_shepp_planner.h.

int rsband_local_planner::ReedsSheppPlanner::interpolationNumPoses_
private

number of poses to interpolate in the reeds shepp path

Definition at line 238 of file reeds_shepp_planner.h.

double rsband_local_planner::ReedsSheppPlanner::maxPlanningDuration_
private

maximum Reeds-Shepp planning duration

Definition at line 236 of file reeds_shepp_planner.h.

double rsband_local_planner::ReedsSheppPlanner::minTurningRadius_
private

minimum turning radius of the robot (dependent on rear steering mode)

Definition at line 234 of file reeds_shepp_planner.h.

ompl::base::StateSpacePtr rsband_local_planner::ReedsSheppPlanner::reedsSheppStateSpace_
private

The ompl Reeds-Sheep state space.

Definition at line 207 of file reeds_shepp_planner.h.

std::string rsband_local_planner::ReedsSheppPlanner::robotFrame_
private

the reference frame of the robot base

Definition at line 226 of file reeds_shepp_planner.h.

bool rsband_local_planner::ReedsSheppPlanner::robotStateValid_
private

regard robot pose as free

Definition at line 242 of file reeds_shepp_planner.h.

ompl::geometric::SimpleSetupPtr rsband_local_planner::ReedsSheppPlanner::simpleSetup_
private

OMPL geometric simple setup object.

Definition at line 209 of file reeds_shepp_planner.h.

ros::Time rsband_local_planner::ReedsSheppPlanner::stamp_
private

the stamp to use in path poses

Definition at line 231 of file reeds_shepp_planner.h.

StateCheckingMode rsband_local_planner::ReedsSheppPlanner::stateCheckingMode_
private

state checking mode: center(0) or footprint(1)

Definition at line 240 of file reeds_shepp_planner.h.

tf::TransformListener* rsband_local_planner::ReedsSheppPlanner::tfListener_
private

tf transform listener

Definition at line 223 of file reeds_shepp_planner.h.

int rsband_local_planner::ReedsSheppPlanner::validStateMaxCost_
private

below this cost, a state is considered valid

Definition at line 244 of file reeds_shepp_planner.h.


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


rsband_local_planner
Author(s): George Kouros
autogenerated on Wed Nov 9 2016 19:13:53