reeds_shepp_planner.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2016, George Kouros.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the the copyright holder nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: George Kouros
36 *********************************************************************/
37 
38 #ifndef RSBAND_LOCAL_PLANNER_REEDS_SHEPP_PLANNER_H
39 #define RSBAND_LOCAL_PLANNER_REEDS_SHEPP_PLANNER_H
40 
41 #include <ros/ros.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>
46 
47 #include <ompl/base/ScopedState.h>
48 #include <ompl/geometric/SimpleSetup.h>
49 #include <ompl/base/spaces/ReedsSheppStateSpace.h>
50 
51 #include "rsband_local_planner/RSBandPlannerConfig.h"
52 
53 namespace rsband_local_planner
54 {
55 
61  {
62  public:
63 
71  std::string name,
72  costmap_2d::Costmap2DROS* costmapROS,
73  tf::TransformListener* tfListener);
74 
79 
86  void initialize(
87  std::string name,
88  costmap_2d::Costmap2DROS* costmapROS,
89  tf::TransformListener* tfListener);
90 
95  void reconfigure(RSBandPlannerConfig& config);
96 
104  bool planPath(
105  const geometry_msgs::PoseStamped& startPose,
106  const geometry_msgs::PoseStamped& goalPose,
107  std::vector<geometry_msgs::PoseStamped>& path);
108 
117  const std::vector<geometry_msgs::PoseStamped>& path,
118  std::vector<geometry_msgs::PoseStamped>& newPath);
119 
128  const std::vector<geometry_msgs::PoseStamped>& path,
129  std::vector<geometry_msgs::PoseStamped>& newPath);
130 
140  int planRecedingPath(
141  const std::vector<geometry_msgs::PoseStamped>& path,
142  std::vector<geometry_msgs::PoseStamped>& newPath);
143 
146  double getBX() {return bx_;}
147  double getBY() {return by_;}
148  void setMinTurningRadius(double rho) {minTurningRadius_ = rho;}
149  void setMaxPlanningDuration(double tmax) {maxPlanningDuration_ = tmax;}
150  void setBoundaries(double bx, double by);
151 
154 
157 
158  private:
159 
166  void transform(const geometry_msgs::PoseStamped& poseIn,
167  geometry_msgs::PoseStamped& poseOut, std::string newFrameID);
168 
175  void transform(const tf::Stamped<tf::Pose>& tfIn,
176  tf::Stamped<tf::Pose>& tfOut, std::string newFrameID);
177 
183  void state2pose(
184  const ompl::base::State* state, geometry_msgs::PoseStamped& pose);
185 
191  void pose2state(
192  const geometry_msgs::PoseStamped& pose, ompl::base::State* state);
193 
202  bool isStateValid(
203  const ompl::base::SpaceInformation* si, const ompl::base::State *state);
204 
205 
207  ompl::base::StateSpacePtr reedsSheppStateSpace_;
209  ompl::geometric::SimpleSetupPtr simpleSetup_;
211  ompl::base::RealVectorBounds bounds_;
212 
214  costmap_2d::Costmap2D* costmap_;
216  costmap_2d::Costmap2DROS* costmapROS_;
218  base_local_planner::CostmapModel* costmapModel_;
220  std::vector<geometry_msgs::Point> footprint_;
221 
223  tf::TransformListener* tfListener_;
224 
226  std::string robotFrame_;
228  std::string globalFrame_;
229 
231  ros::Time stamp_;
232 
248  double bx_;
250  double by_;
253 
256  };
257 
258 } // namespace rsband_local_planner
259 
260 #endif // RSBAND_LOCAL_PLANNER_REEDS_SHEPP_PLANNER_H
double minTurningRadius_
minimum turning radius of the robot (dependent on rear steering mode)
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
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.
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 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
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.
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


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