mesh_controller.h
Go to the documentation of this file.
1 /*
2  * Copyright 2020, 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  * author: Sebastian Pütz <spuetz@uni-osnabrueck.de>
34  *
35  */
36 
37 #ifndef MBF_MESH_CORE__MESH_CONTROLLER_H
38 #define MBF_MESH_CORE__MESH_CONTROLLER_H
39 
40 #include <boost/shared_ptr.hpp>
41 #include <geometry_msgs/PoseStamped.h>
42 #include <geometry_msgs/TwistStamped.h>
44 #include <mesh_map/mesh_map.h>
45 #include <stdint.h>
46 #include <string>
47 #include <vector>
48 
49 namespace mbf_mesh_core
50 {
52 {
53 public:
55 
59  virtual ~MeshController(){};
60 
71  virtual uint32_t computeVelocityCommands(const geometry_msgs::PoseStamped& pose,
72  const geometry_msgs::TwistStamped& velocity,
73  geometry_msgs::TwistStamped& cmd_vel, std::string& message) = 0;
74 
83  virtual bool isGoalReached(double dist_tolerance, double angle_tolerance) = 0;
84 
90  virtual bool setPlan(const std::vector<geometry_msgs::PoseStamped>& plan) = 0;
91 
97  virtual bool cancel() = 0;
98 
106  virtual bool initialize(const std::string& name, const boost::shared_ptr<tf2_ros::Buffer>& tf_ptr,
107  const boost::shared_ptr<mesh_map::MeshMap>& mesh_map_ptr) = 0;
108 
109 protected:
114 };
115 } /* namespace mbf_mesh_core */
116 
117 #endif /* MBF_MESH_NAVIGATION__MESH_CONTROLLER_H */
mbf_mesh_core::MeshController::initialize
virtual bool initialize(const std::string &name, const boost::shared_ptr< tf2_ros::Buffer > &tf_ptr, const boost::shared_ptr< mesh_map::MeshMap > &mesh_map_ptr)=0
Initializes the controller plugin with a name, a tf pointer and a mesh map pointer.
boost::shared_ptr
mbf_mesh_core::MeshController::~MeshController
virtual ~MeshController()
Destructor.
Definition: mesh_controller.h:59
mbf_mesh_core::MeshController::isGoalReached
virtual bool isGoalReached(double dist_tolerance, double angle_tolerance)=0
Check if the goal pose has been achieved by the local planner.
mbf_mesh_core
Definition: mesh_controller.h:49
mbf_mesh_core::MeshController::Ptr
boost::shared_ptr< mbf_mesh_core::MeshController > Ptr
Definition: mesh_controller.h:54
abstract_controller.h
mbf_mesh_core::MeshController::MeshController
MeshController()
Constructor.
Definition: mesh_controller.h:113
mesh_map.h
mbf_abstract_core::AbstractController
mbf_mesh_core::MeshController
Definition: mesh_controller.h:51
mbf_mesh_core::MeshController::cancel
virtual bool cancel()=0
Requests the planner to cancel, e.g. if it takes too much time.
mbf_mesh_core::MeshController::computeVelocityCommands
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...
mbf_mesh_core::MeshController::setPlan
virtual bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan)=0
Set the plan that the local planner is following.


mbf_mesh_core
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:42:49