simple_navigation_server.h
Go to the documentation of this file.
1 /*
2  * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón
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  * simple_navigation_server.h
34  *
35  * authors:
36  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
37  * Jorge Santos Simón <santos@magazino.eu>
38  *
39  */
40 
41 #ifndef MBF_SIMPLE_NAV__SIMPLE_NAVIGATION_SERVER_H_
42 #define MBF_SIMPLE_NAV__SIMPLE_NAVIGATION_SERVER_H_
43 
45 #include <pluginlib/class_loader.h>
46 #include <mbf_utility/types.h>
47 
48 namespace mbf_simple_nav
49 {
64 {
65 public:
66 
71  SimpleNavigationServer(const TFPtr &tf_listener_ptr);
72 
76  virtual ~SimpleNavigationServer();
77 
84  virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string& controller_type);
85 
92  virtual bool initializeControllerPlugin(
93  const std::string& name,
94  const mbf_abstract_core::AbstractController::Ptr& controller_ptr
95  );
96 
102  virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string& planner_type);
103 
110  virtual bool initializePlannerPlugin(
111  const std::string& name,
112  const mbf_abstract_core::AbstractPlanner::Ptr& planner_ptr
113  );
114 
120  virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string& recovery_type);
121 
129  virtual bool initializeRecoveryPlugin(
130  const std::string& name,
131  const mbf_abstract_core::AbstractRecovery::Ptr& behavior_ptr
132  );
133 
134  private:
138 };
139 
140 } /* namespace mbf_simple_nav */
141 
142 #endif /* MBF_SIMPLE_NAV__SIMPLE_NAVIGATION_SERVER_H_ */
The SimpleNavigationServer provides a simple navigation server, which does not bind a map representat...
virtual bool initializeRecoveryPlugin(const std::string &name, const mbf_abstract_core::AbstractRecovery::Ptr &behavior_ptr)
Pure virtual method, the derived class has to implement. Depending on the plugin base class...
virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type)
Loads a Recovery plugin associated with given recovery type parameter.
virtual bool initializePlannerPlugin(const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr)
Empty init method. Nothing to initialize.
pluginlib::ClassLoader< mbf_abstract_core::AbstractPlanner > planner_plugin_loader_
pluginlib::ClassLoader< mbf_abstract_core::AbstractController > controller_plugin_loader_
virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string &controller_type)
Loads the plugin associated with the given controller type parameter.
virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type)
Loads the plugin associated with the given planner_type parameter.
SimpleNavigationServer(const TFPtr &tf_listener_ptr)
Constructor.
virtual bool initializeControllerPlugin(const std::string &name, const mbf_abstract_core::AbstractController::Ptr &controller_ptr)
Empty init method. Nothing to initialize.
pluginlib::ClassLoader< mbf_abstract_core::AbstractRecovery > recovery_plugin_loader_


mbf_simple_nav
Author(s): Sebastian Pütz
autogenerated on Tue Jun 18 2019 19:34:42