planner_interface.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Christoph Rösmann
37  *********************************************************************/
38 
39 #ifndef PLANNER_INTERFACE_H_
40 #define PLANNER_INTERFACE_H_
41 
42 // boost
43 #include <boost/shared_ptr.hpp>
44 
45 // ros
46 #include <tf/transform_datatypes.h>
48 
49 // this package
51 
52 // messages
53 #include <geometry_msgs/PoseArray.h>
54 #include <geometry_msgs/PoseStamped.h>
55 #include <geometry_msgs/TwistStamped.h>
56 
57 
58 namespace teb_local_planner
59 {
60 
61 
67 {
68 public:
69 
74  {
75  }
80  {
81  }
82 
83 
86 
98  virtual bool plan(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false) = 0;
99 
111  virtual bool plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false) = 0;
112 
124  virtual bool plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false) = 0;
125 
134  virtual bool getVelocityCommand(double& vx, double& vy, double& omega) const = 0;
135 
137 
138 
142  virtual void clearPlanner() = 0;
143 
152  virtual void setPreferredTurningDir(RotType dir) {ROS_WARN("setPreferredTurningDir() not implemented for this planner.");}
153 
158  virtual void visualize()
159  {
160  }
161 
175  virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec,
176  double inscribed_radius = 0.0, double circumscribed_radius=0.0, int look_ahead_idx=-1) = 0;
177 
178 
189  virtual bool isHorizonReductionAppropriate(const std::vector<geometry_msgs::PoseStamped>& initial_plan) const {return false;}
190 
198  virtual void computeCurrentCost(std::vector<double>& cost, double obst_cost_scale=1.0, bool alternative_time_cost=false)
199  {
200  }
201 
202 };
203 
206 
207 
208 } // namespace teb_local_planner
209 
210 #endif /* PLANNER_INTERFACE_H__ */
boost::shared_ptr< PlannerInterface > PlannerInterfacePtr
Abbrev. for shared instances of PlannerInterface or it&#39;s subclasses.
virtual bool getVelocityCommand(double &vx, double &vy, double &omega) const =0
Get the velocity command from a previously optimized plan to control the robot at the current samplin...
This abstract class defines an interface for local planners.
virtual ~PlannerInterface()
Virtual destructor.
virtual bool isHorizonReductionAppropriate(const std::vector< geometry_msgs::PoseStamped > &initial_plan) const
Implement this method to check if the planner suggests a shorter horizon (e.g. to resolve problems) ...
PlannerInterface()
Default constructor.
virtual void visualize()
Visualize planner specific stuff. Overwrite this method to provide an interface to perform all planne...
virtual void setPreferredTurningDir(RotType dir)
Prefer a desired initial turning direction (by penalizing the opposing one)
#define ROS_WARN(...)
virtual void computeCurrentCost(std::vector< double > &cost, double obst_cost_scale=1.0, bool alternative_time_cost=false)
RotType
Symbols for left/none/right rotations.
Definition: misc.h:53
virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel *costmap_model, const std::vector< geometry_msgs::Point > &footprint_spec, double inscribed_radius=0.0, double circumscribed_radius=0.0, int look_ahead_idx=-1)=0
Check whether the planned trajectory is feasible or not.
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
Definition: pose_se2.h:57
virtual bool plan(const std::vector< geometry_msgs::PoseStamped > &initial_plan, const geometry_msgs::Twist *start_vel=NULL, bool free_goal_vel=false)=0
Plan a trajectory based on an initial reference plan.
virtual void clearPlanner()=0
Reset the planner.


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 5 2019 19:25:10