38 #ifndef RSBAND_LOCAL_PLANNER_REEDS_SHEPP_PLANNER_H
39 #define RSBAND_LOCAL_PLANNER_REEDS_SHEPP_PLANNER_H
42 #include <costmap_2d/costmap_2d_ros.h>
43 #include <base_local_planner/costmap_model.h>
44 #include <geometry_msgs/Pose.h>
45 #include <geometry_msgs/PoseStamped.h>
47 #include <ompl/base/ScopedState.h>
48 #include <ompl/geometric/SimpleSetup.h>
49 #include <ompl/base/spaces/ReedsSheppStateSpace.h>
51 #include "rsband_local_planner/RSBandPlannerConfig.h"
53 namespace rsband_local_planner
72 costmap_2d::Costmap2DROS* costmapROS,
73 tf::TransformListener* tfListener);
88 costmap_2d::Costmap2DROS* costmapROS,
89 tf::TransformListener* tfListener);
105 const geometry_msgs::PoseStamped& startPose,
106 const geometry_msgs::PoseStamped& goalPose,
107 std::vector<geometry_msgs::PoseStamped>& path);
117 const std::vector<geometry_msgs::PoseStamped>& path,
118 std::vector<geometry_msgs::PoseStamped>& newPath);
128 const std::vector<geometry_msgs::PoseStamped>& path,
129 std::vector<geometry_msgs::PoseStamped>& newPath);
141 const std::vector<geometry_msgs::PoseStamped>& path,
142 std::vector<geometry_msgs::PoseStamped>& newPath);
166 void transform(
const geometry_msgs::PoseStamped& poseIn,
167 geometry_msgs::PoseStamped& poseOut, std::string newFrameID);
175 void transform(
const tf::Stamped<tf::Pose>& tfIn,
176 tf::Stamped<tf::Pose>& tfOut, std::string newFrameID);
184 const ompl::base::State* state, geometry_msgs::PoseStamped& pose);
192 const geometry_msgs::PoseStamped& pose, ompl::base::State* state);
203 const ompl::base::SpaceInformation* si,
const ompl::base::State *state);
260 #endif // RSBAND_LOCAL_PLANNER_REEDS_SHEPP_PLANNER_H
double minTurningRadius_
minimum turning radius of the robot (dependent on rear steering mode)
double getMinTurningRadius()
bool isStateValid(const ompl::base::SpaceInformation *si, const ompl::base::State *state)
Checks whether a state/pose is valid.
int interpolationNumPoses_
number of poses to interpolate in the reeds shepp path
void setMinTurningRadius(double rho)
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.
void pose2state(const geometry_msgs::PoseStamped &pose, ompl::base::State *state)
Converts a pose msg to an ompl state.
void setMaxPlanningDuration(double tmax)
double bx_
boundary size x
bool displayPlannerOutput_
display planning information
bool allowUnknown_
if true considers unknown costmap cells as free
void initialize(std::string name, costmap_2d::Costmap2DROS *costmapROS, tf::TransformListener *tfListener)
Initializes the planner.
void reconfigure(RSBandPlannerConfig &config)
Reconfigures the parameters of the planner.
base_local_planner::CostmapModel * costmapModel_
ptr to costmap model
ompl::base::RealVectorBounds bounds_
planner space boundaries (should match local costmap boundaries)
std::string globalFrame_
the reference frame of the costmap
ReedsSheppPlanner(std::string name, costmap_2d::Costmap2DROS *costmapROS, tf::TransformListener *tfListener)
Constructor.
double by_
boundary size y
StateCheckingMode
state checking mode enum
double maxPlanningDuration_
maximum Reeds-Shepp planning duration
tf::TransformListener * tfListener_
tf transform listener
costmap_2d::Costmap2DROS * costmapROS_
ptr to costmap ros wrapper
void state2pose(const ompl::base::State *state, geometry_msgs::PoseStamped &pose)
Converts an ompl state to a pose msg.
bool robotStateValid_
regard robot pose as free
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.
void transform(const geometry_msgs::PoseStamped &poseIn, geometry_msgs::PoseStamped &poseOut, std::string newFrameID)
Transforms the given pose to the target reference frame.
costmap_2d::Costmap2D * costmap_
ptr to costmap
void setBoundaries(double bx, double by)
int validStateMaxCost_
below this cost, a state is considered valid
ros::Time stamp_
the stamp to use in path poses
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.
StateCheckingMode stateCheckingMode_
state checking mode: center(0) or footprint(1)
ompl::base::StateSpacePtr reedsSheppStateSpace_
The ompl Reeds-Sheep state space.
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.
RearSteeringMode
steering mode enum
double getMaxPlanningDuration()
ompl::geometric::SimpleSetupPtr simpleSetup_
OMPL geometric simple setup object.
Planner - ROS wrapper for the Reeds-Shepp state space of OMPL.
std::string robotFrame_
the reference frame of the robot base
bool initialized_
is set if planner is initialized
std::vector< geometry_msgs::Point > footprint_
robot footprint, used in validity checking
~ReedsSheppPlanner()
Destructor.