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 
49 
50 #include <mbf_costmap_nav/MoveBaseFlexConfig.h>
51 #include <std_srvs/Empty.h>
52 #include <mbf_msgs/CheckPath.h>
53 #include <mbf_msgs/CheckPose.h>
54 #include <mbf_msgs/CheckPoint.h>
55 
59 
60 namespace mbf_costmap_nav
61 {
69 
79 {
80 public:
81 
83 
85 
90  CostmapNavigationServer(const TFPtr &tf_listener_ptr);
91 
95  virtual ~CostmapNavigationServer();
96 
97  virtual void stop();
98 
99 private:
100 
103  const std::string name,
104  const mbf_abstract_core::AbstractPlanner::Ptr plugin_ptr);
105 
108  const std::string name,
110 
113  const std::string name,
115 
121  virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string& planner_type);
122 
129  virtual bool initializePlannerPlugin(
130  const std::string& name,
131  const mbf_abstract_core::AbstractPlanner::Ptr& planner_ptr
132  );
133 
140  virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string& controller_type);
141 
149  virtual bool initializeControllerPlugin(
150  const std::string& name,
151  const mbf_abstract_core::AbstractController::Ptr& controller_ptr
152  );
153 
159  virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string& recovery_type);
160 
167  virtual bool initializeRecoveryPlugin(
168  const std::string& name,
169  const mbf_abstract_core::AbstractRecovery::Ptr& behavior_ptr);
170 
171 
175  void checkActivateCostmaps();
176 
181 
185  void deactivateCostmaps(const ros::TimerEvent &event);
186 
193  bool callServiceCheckPointCost(mbf_msgs::CheckPoint::Request &request,
194  mbf_msgs::CheckPoint::Response &response);
195 
202  bool callServiceCheckPoseCost(mbf_msgs::CheckPose::Request &request,
203  mbf_msgs::CheckPose::Response &response);
204 
211  bool callServiceCheckPathCost(mbf_msgs::CheckPath::Request &request,
212  mbf_msgs::CheckPath::Response &response);
213 
220  bool callServiceClearCostmaps(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response);
221 
227  void reconfigure(mbf_costmap_nav::MoveBaseFlexConfig &config, uint32_t level);
228 
235 
237  DynamicReconfigureServerCostmapNav dsrv_costmap_;
238 
240  mbf_costmap_nav::MoveBaseFlexConfig last_config_;
241 
243  mbf_costmap_nav::MoveBaseFlexConfig default_config_;
244 
247 
249  CostmapPtr local_costmap_ptr_;
250 
253 
256 
259 
262 
265 
268  uint16_t costmaps_users_;
271 
273  boost::mutex check_costmaps_mutex_;
274 };
275 
276 } /* namespace mbf_costmap_nav */
277 
278 #endif /* MBF_COSTMAP_NAV__COSTMAP_NAVIGATION_SERVER_H_ */
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...
bool callServiceCheckPathCost(mbf_msgs::CheckPath::Request &request, mbf_msgs::CheckPath::Response &response)
Callback method for the check_path_cost service.
CostmapPtr global_costmap_ptr_
Shared pointer to the common global costmap.
bool callServiceCheckPointCost(mbf_msgs::CheckPoint::Request &request, mbf_msgs::CheckPoint::Response &response)
Callback method for the check_point_cost service.
boost::mutex check_costmaps_mutex_
Start/stop costmaps mutex; concurrent calls to start can lead to segfault.
bool shutdown_costmaps_
Stop updating costmaps when not planning or controlling, if true.
CostmapNavigationServer(const TFPtr &tf_listener_ptr)
Constructor.
void reconfigure(mbf_costmap_nav::MoveBaseFlexConfig &config, uint32_t level)
Reconfiguration method called by dynamic reconfigure.
mbf_costmap_nav::MoveBaseFlexConfig default_config_
the default parameter configuration save
virtual mbf_abstract_nav::AbstractControllerExecution::Ptr newControllerExecution(const std::string name, const mbf_abstract_core::AbstractController::Ptr plugin_ptr)
shared pointer to a new ControllerExecution
virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type)
Loads the plugin associated with the given planner_type parameter.
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...
virtual mbf_abstract_nav::AbstractPlannerExecution::Ptr newPlannerExecution(const std::string name, const mbf_abstract_core::AbstractPlanner::Ptr plugin_ptr)
shared pointer to a new PlannerExecution
void checkActivateCostmaps()
Check whether the costmaps should be activated.
pluginlib::ClassLoader< mbf_costmap_core::CostmapController > controller_plugin_loader_
boost::shared_ptr< dynamic_reconfigure::Server< mbf_costmap_nav::MoveBaseFlexConfig > > DynamicReconfigureServerCostmapNav
ros::ServiceServer check_point_cost_srv_
Service Server for the check_point_cost service.
ros::ServiceServer clear_costmaps_srv_
Service Server for the clear_costmap service.
mbf_costmap_nav::MoveBaseFlexConfig last_config_
last configuration save
virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type)
Loads a Recovery plugin associated with given recovery type parameter.
ros::Duration shutdown_costmaps_delay_
costmpas delayed shutdown delay
pluginlib::ClassLoader< mbf_costmap_core::CostmapRecovery > recovery_plugin_loader_
DynamicReconfigureServerCostmapNav dsrv_costmap_
Dynamic reconfigure server for the mbf_costmap2d_specific part.
uint16_t costmaps_users_
keep track of plugins using costmaps
CostmapPtr local_costmap_ptr_
Shared pointer to the common local costmap.
bool callServiceClearCostmaps(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
Callback method for the make_plan service.
void checkDeactivateCostmaps()
Check whether the costmaps should and could be deactivated.
ros::Timer shutdown_costmaps_timer_
costmpas delayed shutdown timer
pluginlib::ClassLoader< nav_core::BaseGlobalPlanner > nav_core_planner_plugin_loader_
ros::ServiceServer check_pose_cost_srv_
Service Server for the check_pose_cost service.
bool setup_reconfigure_
true, if the dynamic reconfigure has been setup
pluginlib::ClassLoader< nav_core::RecoveryBehavior > nav_core_recovery_plugin_loader_
The CostmapNavigationServer makes Move Base Flex backwards compatible to the old move_base. It combines the execution classes which use the nav_core/BaseLocalPlanner, nav_core/BaseCostmapPlanner and the nav_core/RecoveryBehavior base classes as plugin interfaces. These plugin interface are the same for the old move_base.
ros::ServiceServer check_path_cost_srv_
Service Server for the check_path_cost service.
boost::shared_ptr< costmap_2d::Costmap2DROS > CostmapPtr
pluginlib::ClassLoader< nav_core::BaseLocalPlanner > nav_core_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.
boost::shared_ptr< CostmapNavigationServer > Ptr
void deactivateCostmaps(const ros::TimerEvent &event)
Timer-triggered deactivation of both costmaps.
bool callServiceCheckPoseCost(mbf_msgs::CheckPose::Request &request, mbf_msgs::CheckPose::Response &response)
Callback method for the check_pose_cost service.
virtual mbf_abstract_nav::AbstractRecoveryExecution::Ptr newRecoveryExecution(const std::string name, const mbf_abstract_core::AbstractRecovery::Ptr plugin_ptr)
shared pointer to a new RecoveryExecution
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.
pluginlib::ClassLoader< mbf_costmap_core::CostmapPlanner > planner_plugin_loader_


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