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
52 
53 // messages
54 #include <geometry_msgs/PoseArray.h>
55 #include <geometry_msgs/PoseStamped.h>
56 #include <geometry_msgs/TwistStamped.h>
57 
58 
59 namespace teb_local_planner
60 {
61 
62 
67 class PlannerInterface
68 {
69 public:
70 
75  {
76  }
80  virtual ~PlannerInterface()
81  {
82  }
83 
84 
87 
99  virtual bool plan(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false) = 0;
100 
112  virtual bool plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false) = 0;
113 
125  virtual bool plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false) = 0;
126 
136  virtual bool getVelocityCommand(double& vx, double& vy, double& omega, int look_ahead_poses) const = 0;
137 
139 
140 
144  virtual void clearPlanner() = 0;
145 
154  virtual void setPreferredTurningDir(RotType dir) {ROS_WARN("setPreferredTurningDir() not implemented for this planner.");}
155 
160  virtual void visualize()
161  {
162  }
163 
164  virtual void updateRobotModel(RobotFootprintModelPtr robot_model)
165  {
166  }
167 
181  virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec,
182  double inscribed_radius = 0.0, double circumscribed_radius=0.0, int look_ahead_idx=-1, double feasibility_check_lookahead_distance=-1.0) = 0;
183 
191  virtual void computeCurrentCost(std::vector<double>& cost, double obst_cost_scale=1.0, bool alternative_time_cost=false)
192  {
193  }
194 
198  virtual bool hasDiverged() const = 0;
199 
200 };
201 
204 
205 
206 } // namespace teb_local_planner
207 
208 #endif /* PLANNER_INTERFACE_H__ */
teb_local_planner::PlannerInterface::isTrajectoryFeasible
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, double feasibility_check_lookahead_distance=-1.0)=0
Check whether the planned trajectory is feasible or not.
teb_local_planner::RobotFootprintModelPtr
boost::shared_ptr< BaseRobotFootprintModel > RobotFootprintModelPtr
Abbrev. for shared obstacle pointers.
Definition: robot_footprint_model.h:156
cmd_vel_to_ackermann_drive.Twist
Twist
Definition: cmd_vel_to_ackermann_drive.py:56
teb_local_planner::PlannerInterface::clearPlanner
virtual void clearPlanner()=0
Reset the planner.
boost::shared_ptr< PlannerInterface >
teb_local_planner::PlannerInterface::plan
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.
teb_local_planner::RotType
RotType
Symbols for left/none/right rotations
Definition: misc.h:89
teb_local_planner::PlannerInterface::getVelocityCommand
virtual bool getVelocityCommand(double &vx, double &vy, double &omega, int look_ahead_poses) const =0
Get the velocity command from a previously optimized plan to control the robot at the current samplin...
teb_local_planner::PlannerInterface::computeCurrentCost
virtual void computeCurrentCost(std::vector< double > &cost, double obst_cost_scale=1.0, bool alternative_time_cost=false)
Definition: planner_interface.h:227
teb_local_planner::PlannerInterface::hasDiverged
virtual bool hasDiverged() const =0
Returns true if the planner has diverged.
base_local_planner::CostmapModel
costmap_model.h
robot_footprint_model.h
ROS_WARN
#define ROS_WARN(...)
teb_local_planner::PlannerInterface::visualize
virtual void visualize()
Visualize planner specific stuff. Overwrite this method to provide an interface to perform all planne...
Definition: planner_interface.h:196
tf::Transform
teb_local_planner::PlannerInterface::~PlannerInterface
virtual ~PlannerInterface()
Virtual destructor.
Definition: planner_interface.h:116
transform_datatypes.h
teb_local_planner::PlannerInterface::PlannerInterface
PlannerInterface()
Default constructor.
Definition: planner_interface.h:110
teb_local_planner::PlannerInterface::setPreferredTurningDir
virtual void setPreferredTurningDir(RotType dir)
Prefer a desired initial turning direction (by penalizing the opposing one)
Definition: planner_interface.h:190
teb_local_planner::PlannerInterfacePtr
boost::shared_ptr< PlannerInterface > PlannerInterfacePtr
Abbrev. for shared instances of PlannerInterface or it's subclasses.
Definition: planner_interface.h:239
pose_se2.h
teb_local_planner
Definition: distance_calculations.h:46
teb_local_planner::PlannerInterface::updateRobotModel
virtual void updateRobotModel(RobotFootprintModelPtr robot_model)
Definition: planner_interface.h:200


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15