Planner - ROS wrapper for the Reeds-Shepp state space of OMPL.
More...
#include <reeds_shepp_planner.h>
|
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...
|
|
|
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...
|
|
Planner - ROS wrapper for the Reeds-Shepp state space of OMPL.
Definition at line 60 of file reeds_shepp_planner.h.
rsband_local_planner::ReedsSheppPlanner::ReedsSheppPlanner |
( |
std::string |
name, |
|
|
costmap_2d::Costmap2DROS * |
costmapROS, |
|
|
tf::TransformListener * |
tfListener |
|
) |
| |
Constructor.
- Parameters
-
name | Name used to load planner parameters |
costmapROS | Ptr to the ROS wrapper of the local costmap |
tfListener | Ptr to a tf transform listener |
Definition at line 44 of file reeds_shepp_planner.cpp.
rsband_local_planner::ReedsSheppPlanner::~ReedsSheppPlanner |
( |
| ) |
|
double rsband_local_planner::ReedsSheppPlanner::getBX |
( |
| ) |
|
|
inline |
double rsband_local_planner::ReedsSheppPlanner::getBY |
( |
| ) |
|
|
inline |
double rsband_local_planner::ReedsSheppPlanner::getMaxPlanningDuration |
( |
| ) |
|
|
inline |
double rsband_local_planner::ReedsSheppPlanner::getMinTurningRadius |
( |
| ) |
|
|
inline |
void rsband_local_planner::ReedsSheppPlanner::initialize |
( |
std::string |
name, |
|
|
costmap_2d::Costmap2DROS * |
costmapROS, |
|
|
tf::TransformListener * |
tfListener |
|
) |
| |
Initializes the planner.
- Parameters
-
name | Name used to load planner parameters |
costmapROS | Ptr to the ROS wrapper of the local costmap |
tfListener | Ptr 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
-
si | Ptr to an ompl space information object |
state | Ptr 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
-
startPose | The start pose of the path |
goalPose | The final pose of the path |
path | The 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
-
path | Contains the path poses to connect via Reeds-Shepp paths |
newPath | Container 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
-
path | Contains the path poses to connect via Reeds-Shepp paths |
newPath | Container 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
-
path | Contains the path poses to connect via Reeds-Shepp paths |
newPath | Container 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
-
pose | The pose to convert to an ompl state |
state | The 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
-
config | The dynamic reconfigure configuration |
Definition at line 112 of file reeds_shepp_planner.cpp.
void rsband_local_planner::ReedsSheppPlanner::setBoundaries |
( |
double |
bx, |
|
|
double |
by |
|
) |
| |
void rsband_local_planner::ReedsSheppPlanner::setMaxPlanningDuration |
( |
double |
tmax | ) |
|
|
inline |
void rsband_local_planner::ReedsSheppPlanner::setMinTurningRadius |
( |
double |
rho | ) |
|
|
inline |
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
-
state | The ompl state to convert to a pose msg |
pose | The 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
-
poseIn | The given pose to transform |
poseOut | The transformed pose container |
newFrameID | The 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
-
tfIn | The given tf pose to transform |
tfOut | The transformed tf pose container |
newFrameID | The target reference frame to use in the transform |
Definition at line 164 of file reeds_shepp_planner.cpp.
bool rsband_local_planner::ReedsSheppPlanner::allowUnknown_ |
|
private |
ompl::base::RealVectorBounds rsband_local_planner::ReedsSheppPlanner::bounds_ |
|
private |
double rsband_local_planner::ReedsSheppPlanner::bx_ |
|
private |
double rsband_local_planner::ReedsSheppPlanner::by_ |
|
private |
costmap_2d::Costmap2D* rsband_local_planner::ReedsSheppPlanner::costmap_ |
|
private |
base_local_planner::CostmapModel* rsband_local_planner::ReedsSheppPlanner::costmapModel_ |
|
private |
costmap_2d::Costmap2DROS* rsband_local_planner::ReedsSheppPlanner::costmapROS_ |
|
private |
bool rsband_local_planner::ReedsSheppPlanner::displayPlannerOutput_ |
|
private |
std::vector<geometry_msgs::Point> rsband_local_planner::ReedsSheppPlanner::footprint_ |
|
private |
std::string rsband_local_planner::ReedsSheppPlanner::globalFrame_ |
|
private |
bool rsband_local_planner::ReedsSheppPlanner::initialized_ |
|
private |
int rsband_local_planner::ReedsSheppPlanner::interpolationNumPoses_ |
|
private |
double rsband_local_planner::ReedsSheppPlanner::maxPlanningDuration_ |
|
private |
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 |
std::string rsband_local_planner::ReedsSheppPlanner::robotFrame_ |
|
private |
bool rsband_local_planner::ReedsSheppPlanner::robotStateValid_ |
|
private |
ompl::geometric::SimpleSetupPtr rsband_local_planner::ReedsSheppPlanner::simpleSetup_ |
|
private |
ros::Time rsband_local_planner::ReedsSheppPlanner::stamp_ |
|
private |
tf::TransformListener* rsband_local_planner::ReedsSheppPlanner::tfListener_ |
|
private |
int rsband_local_planner::ReedsSheppPlanner::validStateMaxCost_ |
|
private |
The documentation for this class was generated from the following files: