mesh_navigation_server.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  * authors:
34  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
35  *
36  */
37 
38 #ifndef MBF_MESH_NAV__MESH_NAVIGATION_SERVER_H
39 #define MBF_MESH_NAV__MESH_NAVIGATION_SERVER_H
40 
42 
44 #include "mesh_planner_execution.h"
46 
47 #include <mbf_mesh_nav/MoveBaseFlexConfig.h>
48 #include <mbf_msgs/CheckPath.h>
49 #include <mbf_msgs/CheckPose.h>
50 #include <std_srvs/Empty.h>
51 
52 #include <pluginlib/class_loader.h>
53 
54 namespace mbf_mesh_nav
55 {
63 
74 {
75 public:
77 
79 
84  MeshNavigationServer(const TFPtr& tf_listener_ptr);
85 
89  virtual ~MeshNavigationServer();
90 
91  virtual void stop();
92 
93 private:
96  newPlannerExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractPlanner::Ptr plugin_ptr);
97 
100  newControllerExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractController::Ptr plugin_ptr);
101 
104  newRecoveryExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractRecovery::Ptr plugin_ptr);
105 
111  virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string& planner_type);
112 
121  virtual bool initializePlannerPlugin(const std::string& name,
122  const mbf_abstract_core::AbstractPlanner::Ptr& planner_ptr);
123 
130  virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string& controller_type);
131 
140  virtual bool initializeControllerPlugin(const std::string& name,
141  const mbf_abstract_core::AbstractController::Ptr& controller_ptr);
142 
150  virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string& recovery_type);
151 
160  virtual bool initializeRecoveryPlugin(const std::string& name,
161  const mbf_abstract_core::AbstractRecovery::Ptr& behavior_ptr);
162 
171  bool callServiceCheckPoseCost(mbf_msgs::CheckPose::Request& request, mbf_msgs::CheckPose::Response& response);
172 
181  bool callServiceCheckPathCost(mbf_msgs::CheckPath::Request& request, mbf_msgs::CheckPath::Response& response);
182 
189  bool callServiceClearMesh(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);
190 
197  void reconfigure(mbf_mesh_nav::MoveBaseFlexConfig& config, uint32_t level);
198 
201 
204 
207 
210 
212  mbf_mesh_nav::MoveBaseFlexConfig last_config_;
213 
215  mbf_mesh_nav::MoveBaseFlexConfig default_config_;
216 
219 
222 
225 
228 
231 
233  boost::mutex check_meshs_mutex_;
234 };
235 
236 } /* namespace mbf_mesh_nav */
237 
238 #endif /* MBF_MESH_NAV__MESH_NAVIGATION_SERVER_H */
mbf_mesh_nav::MeshNavigationServer::callServiceCheckPathCost
bool callServiceCheckPathCost(mbf_msgs::CheckPath::Request &request, mbf_msgs::CheckPath::Response &response)
Callback method for the check_path_cost service.
Definition: mesh_navigation_server.cpp:274
mbf_mesh_nav::MeshNavigationServer::check_meshs_mutex_
boost::mutex check_meshs_mutex_
Start/stop meshs mutex; concurrent calls to start can lead to segfault.
Definition: mesh_navigation_server.h:233
mbf_mesh_nav::MeshNavigationServer::check_path_cost_srv_
ros::ServiceServer check_path_cost_srv_
Service Server for the check_path_cost service.
Definition: mesh_navigation_server.h:230
mbf_mesh_nav::DynamicReconfigureServerMeshNav
boost::shared_ptr< dynamic_reconfigure::Server< mbf_mesh_nav::MoveBaseFlexConfig > > DynamicReconfigureServerMeshNav
Definition: mesh_navigation_server.h:62
mbf_mesh_nav::MeshNavigationServer::loadPlannerPlugin
virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type)
Loads the plugin associated with the given planner_type parameter.
Definition: mesh_navigation_server.cpp:100
class_loader.h
boost::shared_ptr
mbf_mesh_nav::MeshNavigationServer::default_config_
mbf_mesh_nav::MoveBaseFlexConfig default_config_
the default parameter configuration save
Definition: mesh_navigation_server.h:215
mbf_mesh_nav::MeshNavigationServer::loadRecoveryPlugin
virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type)
Loads a Recovery plugin associated with given recovery type parameter.
Definition: mesh_navigation_server.cpp:176
mbf_abstract_nav::AbstractNavigationServer
mbf_mesh_nav::MeshNavigationServer::setup_reconfigure_
bool setup_reconfigure_
true, if the dynamic reconfigure has been setup
Definition: mesh_navigation_server.h:218
mbf_mesh_nav::MeshNavigationServer
The MeshNavigationServer makes Move Base Flex backwards compatible to the old move_base....
Definition: mesh_navigation_server.h:73
mbf_mesh_nav::MeshNavigationServer::clear_mesh_srv_
ros::ServiceServer clear_mesh_srv_
Service Server to clear the mesh.
Definition: mesh_navigation_server.h:224
mesh_controller_execution.h
mesh_recovery_execution.h
ros::ServiceServer
mbf_mesh_nav::MeshNavigationServer::~MeshNavigationServer
virtual ~MeshNavigationServer()
Destructor.
Definition: mesh_navigation_server.cpp:228
mesh_planner_execution.h
mbf_mesh_nav::MeshNavigationServer::callServiceCheckPoseCost
bool callServiceCheckPoseCost(mbf_msgs::CheckPose::Request &request, mbf_msgs::CheckPose::Response &response)
Callback method for the check_pose_cost service.
Definition: mesh_navigation_server.cpp:267
mbf_mesh_nav::MeshNavigationServer::initializePlannerPlugin
virtual bool initializePlannerPlugin(const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr)
Initializes the controller plugin with its name and pointer to the mesh.
Definition: mesh_navigation_server.cpp:119
mbf_mesh_nav::MeshNavigationServer::initializeRecoveryPlugin
virtual bool initializeRecoveryPlugin(const std::string &name, const mbf_abstract_core::AbstractRecovery::Ptr &behavior_ptr)
Initializes a recovery behavior plugin with its name and pointers to the global and local meshs.
Definition: mesh_navigation_server.cpp:197
mbf_mesh_nav::MeshNavigationServer::MeshNavigationServer
MeshNavigationServer(const TFPtr &tf_listener_ptr)
Constructor.
Definition: mesh_navigation_server.cpp:47
mbf_mesh_nav::MeshNavigationServer::newControllerExecution
virtual mbf_abstract_nav::AbstractControllerExecution::Ptr newControllerExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractController::Ptr plugin_ptr)
shared pointer to a new ControllerExecution
Definition: mesh_navigation_server.cpp:84
abstract_navigation_server.h
mbf_mesh_nav::MeshNavigationServer::callServiceClearMesh
bool callServiceClearMesh(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
Callback method for the make_plan service.
Definition: mesh_navigation_server.cpp:281
pluginlib::ClassLoader< mbf_mesh_core::MeshRecovery >
mbf_mesh_nav::MeshNavigationServer::newPlannerExecution
virtual mbf_abstract_nav::AbstractPlannerExecution::Ptr newPlannerExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractPlanner::Ptr plugin_ptr)
shared pointer to a new PlannerExecution
Definition: mesh_navigation_server.cpp:77
mbf_mesh_nav
Definition: mesh_controller_execution.h:46
mbf_mesh_nav::MeshNavigationServer::dsrv_mesh_
DynamicReconfigureServerMeshNav dsrv_mesh_
Dynamic reconfigure server for the mbf_mesh2d_specific part.
Definition: mesh_navigation_server.h:209
mbf_mesh_nav::MeshNavigationServer::loadControllerPlugin
virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string &controller_type)
Loads the plugin associated with the given controller type parameter.
Definition: mesh_navigation_server.cpp:135
mbf_mesh_nav::MeshNavigationServer::MeshPtr
boost::shared_ptr< mesh_map::MeshMap > MeshPtr
Definition: mesh_navigation_server.h:76
mbf_mesh_nav::MeshNavigationServer::newRecoveryExecution
virtual mbf_abstract_nav::AbstractRecoveryExecution::Ptr newRecoveryExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractRecovery::Ptr plugin_ptr)
shared pointer to a new RecoveryExecution
Definition: mesh_navigation_server.cpp:92
mbf_mesh_nav::MeshNavigationServer::Ptr
boost::shared_ptr< MeshNavigationServer > Ptr
Definition: mesh_navigation_server.h:78
mbf_mesh_nav::MeshNavigationServer::planner_plugin_loader_
pluginlib::ClassLoader< mbf_mesh_core::MeshPlanner > planner_plugin_loader_
plugin class loader for planner plugins
Definition: mesh_navigation_server.h:206
mbf_mesh_nav::MeshNavigationServer::mesh_ptr_
MeshPtr mesh_ptr_
Shared pointer to the common global mesh.
Definition: mesh_navigation_server.h:221
mbf_mesh_nav::MeshNavigationServer::check_pose_cost_srv_
ros::ServiceServer check_pose_cost_srv_
Service Server for the check_pose_cost service.
Definition: mesh_navigation_server.h:227
mbf_mesh_nav::MeshNavigationServer::controller_plugin_loader_
pluginlib::ClassLoader< mbf_mesh_core::MeshController > controller_plugin_loader_
plugin class loader for controller plugins
Definition: mesh_navigation_server.h:203
mbf_mesh_nav::MeshNavigationServer::stop
virtual void stop()
Definition: mesh_navigation_server.cpp:220
mbf_mesh_nav::MeshNavigationServer::recovery_plugin_loader_
pluginlib::ClassLoader< mbf_mesh_core::MeshRecovery > recovery_plugin_loader_
plugin class loader for recovery behaviors plugins
Definition: mesh_navigation_server.h:200
mbf_mesh_nav::MeshNavigationServer::last_config_
mbf_mesh_nav::MoveBaseFlexConfig last_config_
last configuration save
Definition: mesh_navigation_server.h:212
mbf_mesh_nav::MeshNavigationServer::reconfigure
void reconfigure(mbf_mesh_nav::MoveBaseFlexConfig &config, uint32_t level)
Reconfiguration method called by dynamic reconfigure.
Definition: mesh_navigation_server.cpp:232
mbf_mesh_nav::MeshNavigationServer::initializeControllerPlugin
virtual bool initializeControllerPlugin(const std::string &name, const mbf_abstract_core::AbstractController::Ptr &controller_ptr)
Initializes the controller plugin with its name, a pointer to the TransformListener and pointer to th...
Definition: mesh_navigation_server.cpp:152


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