costmap_controller.h
Go to the documentation of this file.
1 /*
2  * Copyright 2018, Sebastian Pütz
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * mbf_costmap_core.h
34  *
35  * author: Sebastian Pütz <spuetz@uni-osnabrueck.de>
36  *
37  */
38 
39 #ifndef MBF_COSTMAP_CORE__COSTMAP_CONTROLLER_H_
40 #define MBF_COSTMAP_CORE__COSTMAP_CONTROLLER_H_
41 
44 #include <mbf_utility/types.h>
45 
46 namespace mbf_costmap_core {
54  public:
55 
57 
85  virtual uint32_t computeVelocityCommands(const geometry_msgs::PoseStamped& pose,
86  const geometry_msgs::TwistStamped& velocity,
87  geometry_msgs::TwistStamped &cmd_vel,
88  std::string &message) = 0;
89 
97  virtual bool isGoalReached(double xy_tolerance, double yaw_tolerance) = 0;
98 
104  virtual bool setPlan(const std::vector<geometry_msgs::PoseStamped> &plan) = 0;
105 
111  virtual bool cancel() = 0;
112 
119  virtual void initialize(std::string name, ::TF *tf, costmap_2d::Costmap2DROS *costmap_ros) = 0;
120 
124  virtual ~CostmapController(){}
125 
126  protected:
128 
129  };
130 } /* namespace mbf_costmap_core */
131 
132 #endif /* MBF_COSTMAP_CORE__COSTMAP_CONTROLLER_H_ */
virtual uint32_t computeVelocityCommands(const geometry_msgs::PoseStamped &pose, const geometry_msgs::TwistStamped &velocity, geometry_msgs::TwistStamped &cmd_vel, std::string &message)=0
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
boost::shared_ptr< ::mbf_costmap_core::CostmapController > Ptr
virtual bool cancel()=0
Requests the planner to cancel, e.g. if it takes too much time.
virtual bool isGoalReached(double xy_tolerance, double yaw_tolerance)=0
Check if the goal pose has been achieved by the local planner within tolerance limits.
virtual void initialize(std::string name,::TF *tf, costmap_2d::Costmap2DROS *costmap_ros)=0
Constructs the local planner.
virtual ~CostmapController()
Virtual destructor for the interface.
virtual bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan)=0
Set the plan that the local planner is following.


mbf_costmap_core
Author(s): Jorge Santos , Sebastian Pütz
autogenerated on Fri Nov 6 2020 03:56:27