costmap_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  * costmap_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_COSTMAP_NAV__COSTMAP_NAVIGATION_SERVER_H_
42 #define MBF_COSTMAP_NAV__COSTMAP_NAVIGATION_SERVER_H_
43 
45 
46 #include <std_srvs/Empty.h>
47 #include <mbf_msgs/CheckPath.h>
48 #include <mbf_msgs/CheckPose.h>
49 #include <mbf_msgs/CheckPoint.h>
50 
54 
55 #include "mbf_costmap_nav/MoveBaseFlexConfig.h"
60 
61 // Change this to std::unordered_map, once we move to C++11.
62 #include <boost/unordered_map.hpp>
63 #include <boost/shared_ptr.hpp>
64 
65 #include <string>
66 
67 namespace mbf_costmap_nav
68 {
76 
78 typedef boost::unordered_map<std::string, CostmapWrapper::Ptr> StringToMap;
79 
89 {
90 public:
91 
93 
98  CostmapNavigationServer(const TFPtr &tf_listener_ptr);
99 
103  virtual ~CostmapNavigationServer();
104 
105  virtual void stop();
106 
107 private:
108 
116  const std::string &plugin_name,
117  const mbf_abstract_core::AbstractPlanner::Ptr &plugin_ptr);
118 
126  const std::string &plugin_name,
128 
136  const std::string &plugin_name,
137  const mbf_abstract_core::AbstractRecovery::Ptr &plugin_ptr);
138 
144  virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type);
145 
152  virtual bool initializePlannerPlugin(
153  const std::string &name,
154  const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr
155  );
156 
163  virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string &controller_type);
164 
172  virtual bool initializeControllerPlugin(
173  const std::string &name,
174  const mbf_abstract_core::AbstractController::Ptr &controller_ptr
175  );
176 
182  virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type);
183 
190  virtual bool initializeRecoveryPlugin(
191  const std::string &name,
192  const mbf_abstract_core::AbstractRecovery::Ptr &behavior_ptr);
193 
200  bool callServiceCheckPointCost(mbf_msgs::CheckPoint::Request &request,
201  mbf_msgs::CheckPoint::Response &response);
202 
209  bool callServiceCheckPoseCost(mbf_msgs::CheckPose::Request &request,
210  mbf_msgs::CheckPose::Response &response);
211 
218  bool callServiceCheckPathCost(mbf_msgs::CheckPath::Request &request,
219  mbf_msgs::CheckPath::Response &response);
220 
227  bool callServiceClearCostmaps(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response);
228 
234  void reconfigure(mbf_costmap_nav::MoveBaseFlexConfig &config, uint32_t level);
235 
242 
245 
247  mbf_costmap_nav::MoveBaseFlexConfig last_config_;
248 
250  mbf_costmap_nav::MoveBaseFlexConfig default_config_;
251 
254 
257 
260 
263 
266 
269 
272 
275 
278 };
279 
280 } /* namespace mbf_costmap_nav */
281 
282 #endif /* MBF_COSTMAP_NAV__COSTMAP_NAVIGATION_SERVER_H_ */
mbf_costmap_nav::CostmapNavigationServer::nav_core_controller_plugin_loader_
pluginlib::ClassLoader< nav_core::BaseLocalPlanner > nav_core_controller_plugin_loader_
Definition: costmap_navigation_server.h:239
mbf_costmap_nav::CostmapNavigationServer::loadControllerPlugin
virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string &controller_type)
Loads the plugin associated with the given controller type parameter.
Definition: costmap_navigation_server.cpp:306
mbf_costmap_nav::CostmapNavigationServer::nav_core_recovery_plugin_loader_
pluginlib::ClassLoader< nav_core::RecoveryBehavior > nav_core_recovery_plugin_loader_
Definition: costmap_navigation_server.h:237
mbf_costmap_nav::CostmapNavigationServer::controller_plugin_loader_
pluginlib::ClassLoader< mbf_costmap_core::CostmapController > controller_plugin_loader_
Definition: costmap_navigation_server.h:238
mbf_costmap_nav::CostmapNavigationServer::newControllerExecution
virtual mbf_abstract_nav::AbstractControllerExecution::Ptr newControllerExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractController::Ptr &plugin_ptr)
Create a new controller execution.
Definition: costmap_navigation_server.cpp:228
mbf_costmap_nav::CostmapNavigationServer::nav_core_planner_plugin_loader_
pluginlib::ClassLoader< nav_core::BaseGlobalPlanner > nav_core_planner_plugin_loader_
Definition: costmap_navigation_server.h:241
boost::shared_ptr
mbf_costmap_nav::CostmapNavigationServer::loadRecoveryPlugin
virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type)
Loads a Recovery plugin associated with given recovery type parameter.
Definition: costmap_navigation_server.cpp:364
mbf_costmap_nav::CostmapNavigationServer::stop
virtual void stop()
Definition: costmap_navigation_server.cpp:433
mbf_costmap_nav::CostmapNavigationServer::check_point_cost_srv_
ros::ServiceServer check_point_cost_srv_
Service Server for the check_point_cost service.
Definition: costmap_navigation_server.h:268
mbf_abstract_nav::AbstractNavigationServer
mbf_costmap_nav::CostmapNavigationServer::last_config_
mbf_costmap_nav::MoveBaseFlexConfig last_config_
last configuration save
Definition: costmap_navigation_server.h:247
mbf_costmap_nav::CostmapNavigationServer::recovery_plugin_loader_
pluginlib::ClassLoader< mbf_costmap_core::CostmapRecovery > recovery_plugin_loader_
Definition: costmap_navigation_server.h:236
mbf_costmap_nav::CostmapNavigationServer::dsrv_costmap_
DynamicReconfigureServerCostmapNav dsrv_costmap_
Dynamic reconfigure server for the mbf_costmap2d_specific part.
Definition: costmap_navigation_server.h:244
costmap_planner_execution.h
mbf_costmap_nav::CostmapNavigationServer::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 costmap.
Definition: costmap_navigation_server.cpp:284
mbf_costmap_nav::CostmapNavigationServer::callServiceCheckPoseCost
bool callServiceCheckPoseCost(mbf_msgs::CheckPose::Request &request, mbf_msgs::CheckPose::Response &response)
Callback method for the check_pose_cost service.
Definition: costmap_navigation_server.cpp:556
mbf_costmap_nav::CostmapNavigationServer::planner_name_to_costmap_ptr_
StringToMap planner_name_to_costmap_ptr_
Maps planner names to the costmap ptr.
Definition: costmap_navigation_server.h:262
costmap_wrapper.h
mbf_costmap_nav::CostmapNavigationServer
The CostmapNavigationServer makes Move Base Flex backwards compatible to the old move_base....
Definition: costmap_navigation_server.h:88
ros::ServiceServer
costmap_controller_execution.h
base_local_planner.h
mbf_costmap_nav::CostmapNavigationServer::setup_reconfigure_
bool setup_reconfigure_
true, if the dynamic reconfigure has been setup
Definition: costmap_navigation_server.h:253
mbf_costmap_nav::CostmapNavigationServer::default_config_
mbf_costmap_nav::MoveBaseFlexConfig default_config_
the default parameter configuration save
Definition: costmap_navigation_server.h:250
mbf_costmap_nav::CostmapNavigationServer::~CostmapNavigationServer
virtual ~CostmapNavigationServer()
Destructor.
Definition: costmap_navigation_server.cpp:194
mbf_costmap_nav::CostmapNavigationServer::check_path_cost_srv_
ros::ServiceServer check_path_cost_srv_
Service Server for the check_path_cost service.
Definition: costmap_navigation_server.h:274
mbf_costmap_nav::CostmapNavigationServer::local_costmap_ptr_
const CostmapWrapper::Ptr local_costmap_ptr_
Shared pointer to the common local costmap.
Definition: costmap_navigation_server.h:256
mbf_costmap_nav
Definition: costmap_controller_execution.h:51
abstract_navigation_server.h
recovery_behavior.h
mbf_costmap_nav::CostmapNavigationServer::planner_plugin_loader_
pluginlib::ClassLoader< mbf_costmap_core::CostmapPlanner > planner_plugin_loader_
Definition: costmap_navigation_server.h:240
mbf_costmap_nav::CostmapNavigationServer::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 costmaps.
Definition: costmap_navigation_server.cpp:401
pluginlib::ClassLoader< mbf_costmap_core::CostmapRecovery >
mbf_costmap_nav::CostmapNavigationServer::check_pose_cost_srv_
ros::ServiceServer check_pose_cost_srv_
Service Server for the check_pose_cost service.
Definition: costmap_navigation_server.h:271
mbf_costmap_nav::CostmapNavigationServer::Ptr
boost::shared_ptr< CostmapNavigationServer > Ptr
Definition: costmap_navigation_server.h:92
mbf_costmap_nav::CostmapNavigationServer::CostmapNavigationServer
CostmapNavigationServer(const TFPtr &tf_listener_ptr)
Constructor.
Definition: costmap_navigation_server.cpp:156
mbf_costmap_nav::CostmapNavigationServer::newRecoveryExecution
virtual mbf_abstract_nav::AbstractRecoveryExecution::Ptr newRecoveryExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractRecovery::Ptr &plugin_ptr)
Create a new recovery behavior execution.
Definition: costmap_navigation_server.cpp:239
mbf_costmap_nav::CostmapNavigationServer::callServiceCheckPathCost
bool callServiceCheckPathCost(mbf_msgs::CheckPath::Request &request, mbf_msgs::CheckPath::Response &response)
Callback method for the check_path_cost service.
Definition: costmap_navigation_server.cpp:679
base_global_planner.h
mbf_costmap_nav::CostmapNavigationServer::newPlannerExecution
virtual mbf_abstract_nav::AbstractPlannerExecution::Ptr newPlannerExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractPlanner::Ptr &plugin_ptr)
Create a new planner execution.
Definition: costmap_navigation_server.cpp:217
mbf_costmap_nav::DynamicReconfigureServerCostmapNav
boost::shared_ptr< dynamic_reconfigure::Server< mbf_costmap_nav::MoveBaseFlexConfig > > DynamicReconfigureServerCostmapNav
Definition: costmap_navigation_server.h:75
mbf_costmap_nav::CostmapNavigationServer::reconfigure
void reconfigure(mbf_costmap_nav::MoveBaseFlexConfig &config, uint32_t level)
Reconfiguration method called by dynamic reconfigure.
Definition: costmap_navigation_server.cpp:441
mbf_costmap_nav::CostmapNavigationServer::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: costmap_navigation_server.cpp:337
mbf_costmap_nav::CostmapNavigationServer::loadPlannerPlugin
virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type)
Loads the plugin associated with the given planner_type parameter.
Definition: costmap_navigation_server.cpp:252
mbf_costmap_nav::CostmapNavigationServer::callServiceCheckPointCost
bool callServiceCheckPointCost(mbf_msgs::CheckPoint::Request &request, mbf_msgs::CheckPoint::Response &response)
Callback method for the check_point_cost service.
Definition: costmap_navigation_server.cpp:479
costmap_recovery_execution.h
mbf_costmap_nav::StringToMap
boost::unordered_map< std::string, CostmapWrapper::Ptr > StringToMap
A mapping from a string to a map-ptr.
Definition: costmap_navigation_server.h:78
mbf_costmap_nav::CostmapNavigationServer::global_costmap_ptr_
const CostmapWrapper::Ptr global_costmap_ptr_
Shared pointer to the common global costmap.
Definition: costmap_navigation_server.h:259
mbf_costmap_nav::CostmapNavigationServer::controller_name_to_costmap_ptr_
StringToMap controller_name_to_costmap_ptr_
Maps the controller names to the costmap ptr.
Definition: costmap_navigation_server.h:265
mbf_costmap_nav::CostmapNavigationServer::clear_costmaps_srv_
ros::ServiceServer clear_costmaps_srv_
Service Server for the clear_costmap service.
Definition: costmap_navigation_server.h:277
mbf_costmap_nav::CostmapNavigationServer::callServiceClearCostmaps
bool callServiceClearCostmaps(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
Callback method for the make_plan service.
Definition: costmap_navigation_server.cpp:822


mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:55