00001 /* 00002 * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón 00003 * 00004 * Redistribution and use in source and binary forms, with or without 00005 * modification, are permitted provided that the following conditions 00006 * are met: 00007 * 00008 * 1. Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * 00011 * 2. Redistributions in binary form must reproduce the above 00012 * copyright notice, this list of conditions and the following 00013 * disclaimer in the documentation and/or other materials provided 00014 * with the distribution. 00015 * 00016 * 3. Neither the name of the copyright holder nor the names of its 00017 * contributors may be used to endorse or promote products derived 00018 * from this software without specific prior written permission. 00019 * 00020 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 * POSSIBILITY OF SUCH DAMAGE. 00032 * 00033 * abstract_navigation_server.h 00034 * 00035 * authors: 00036 * Sebastian Pütz <spuetz@uni-osnabrueck.de> 00037 * Jorge Santos Simón <santos@magazino.eu> 00038 * 00039 */ 00040 00041 #ifndef MBF_ABSTRACT_NAV__ABSTRACT_NAVIGATION_SERVER_H_ 00042 #define MBF_ABSTRACT_NAV__ABSTRACT_NAVIGATION_SERVER_H_ 00043 00044 #include <string> 00045 #include <stdint.h> 00046 00047 #include <boost/shared_ptr.hpp> 00048 #include <boost/thread/recursive_mutex.hpp> 00049 00050 #include <actionlib/server/action_server.h> 00051 #include <dynamic_reconfigure/server.h> 00052 #include <geometry_msgs/PoseStamped.h> 00053 #include <tf/transform_listener.h> 00054 00055 #include <mbf_utility/navigation_utility.h> 00056 00057 #include "mbf_abstract_nav/abstract_plugin_manager.h" 00058 #include "mbf_abstract_nav/abstract_planner_execution.h" 00059 #include "mbf_abstract_nav/abstract_controller_execution.h" 00060 #include "mbf_abstract_nav/abstract_recovery_execution.h" 00061 00062 #include "mbf_abstract_nav/planner_action.h" 00063 #include "mbf_abstract_nav/controller_action.h" 00064 #include "mbf_abstract_nav/recovery_action.h" 00065 #include "mbf_abstract_nav/move_base_action.h" 00066 00067 #include "mbf_abstract_nav/MoveBaseFlexConfig.h" 00068 00069 namespace mbf_abstract_nav 00070 { 00082 00083 typedef actionlib::ActionServer<mbf_msgs::GetPathAction> ActionServerGetPath; 00084 typedef boost::shared_ptr<ActionServerGetPath> ActionServerGetPathPtr; 00085 00087 typedef actionlib::ActionServer<mbf_msgs::ExePathAction> ActionServerExePath; 00088 typedef boost::shared_ptr<ActionServerExePath> ActionServerExePathPtr; 00089 00091 typedef actionlib::ActionServer<mbf_msgs::RecoveryAction> ActionServerRecovery; 00092 typedef boost::shared_ptr<ActionServerRecovery> ActionServerRecoveryPtr; 00093 00095 typedef actionlib::ActionServer<mbf_msgs::MoveBaseAction> ActionServerMoveBase; 00096 typedef boost::shared_ptr<ActionServerMoveBase> ActionServerMoveBasePtr; 00097 00099 const std::string name_action_exe_path = "exe_path"; 00101 const std::string name_action_get_path = "get_path"; 00103 const std::string name_action_recovery = "recovery"; 00105 const std::string name_action_move_base = "move_base"; 00106 00107 00108 typedef boost::shared_ptr<dynamic_reconfigure::Server<mbf_abstract_nav::MoveBaseFlexConfig> > DynamicReconfigureServer; 00109 00119 class AbstractNavigationServer 00120 { 00121 public: 00122 00131 AbstractNavigationServer(const TFPtr &tf_listener_ptr); 00135 virtual ~AbstractNavigationServer(); 00136 00137 virtual void stop(); 00138 00140 virtual mbf_abstract_nav::AbstractPlannerExecution::Ptr newPlannerExecution( 00141 const std::string plugin_name, 00142 const mbf_abstract_core::AbstractPlanner::Ptr plugin_ptr); 00143 00145 virtual mbf_abstract_nav::AbstractControllerExecution::Ptr newControllerExecution( 00146 const std::string plugin_name, 00147 const mbf_abstract_core::AbstractController::Ptr plugin_ptr); 00148 00150 virtual mbf_abstract_nav::AbstractRecoveryExecution::Ptr newRecoveryExecution( 00151 const std::string plugin_name, 00152 const mbf_abstract_core::AbstractRecovery::Ptr plugin_ptr); 00153 00159 virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string& planner_type) = 0; 00160 00167 virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string& controller_type) = 0; 00168 00174 virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string& recovery_type) = 0; 00175 00183 virtual bool initializePlannerPlugin( 00184 const std::string& name, 00185 const mbf_abstract_core::AbstractPlanner::Ptr& planner_ptr 00186 ) = 0; 00187 00195 virtual bool initializeControllerPlugin( 00196 const std::string& name, 00197 const mbf_abstract_core::AbstractController::Ptr& controller_ptr 00198 ) = 0; 00199 00207 virtual bool initializeRecoveryPlugin( 00208 const std::string& name, 00209 const mbf_abstract_core::AbstractRecovery::Ptr& behavior_ptr 00210 ) = 0; 00211 00212 00218 virtual void callActionGetPath(ActionServerGetPath::GoalHandle goal_handle); 00219 00220 virtual void cancelActionGetPath(ActionServerGetPath::GoalHandle goal_handle); 00221 00227 virtual void callActionExePath(ActionServerExePath::GoalHandle goal_handle); 00228 00229 virtual void cancelActionExePath(ActionServerExePath::GoalHandle goal_handle); 00230 00236 virtual void callActionRecovery(ActionServerRecovery::GoalHandle goal_handle); 00237 00238 virtual void cancelActionRecovery(ActionServerRecovery::GoalHandle goal_handle); 00239 00245 virtual void callActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle); 00246 00247 virtual void cancelActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle); 00248 00252 virtual void startActionServers(); 00253 00258 virtual void initializeServerComponents(); 00259 00265 bool getRobotPose(geometry_msgs::PoseStamped &robot_pose); 00266 00267 protected: 00268 00275 bool transformPlanToGlobalFrame(std::vector<geometry_msgs::PoseStamped> &plan, 00276 std::vector<geometry_msgs::PoseStamped> &global_plan); 00277 00282 virtual void startDynamicReconfigureServer(); 00283 00289 virtual void reconfigure(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level); 00290 00292 ros::NodeHandle private_nh_; 00293 00294 AbstractPluginManager<mbf_abstract_core::AbstractPlanner> planner_plugin_manager_; 00295 AbstractPluginManager<mbf_abstract_core::AbstractController> controller_plugin_manager_; 00296 AbstractPluginManager<mbf_abstract_core::AbstractRecovery> recovery_plugin_manager_; 00297 00299 ActionServerRecoveryPtr action_server_recovery_ptr_; 00300 00302 ActionServerExePathPtr action_server_exe_path_ptr_; 00303 00305 ActionServerGetPathPtr action_server_get_path_ptr_; 00306 00308 ActionServerMoveBasePtr action_server_move_base_ptr_; 00309 00311 DynamicReconfigureServer dsrv_; 00312 00314 boost::mutex configuration_mutex_; 00315 00317 mbf_abstract_nav::MoveBaseFlexConfig last_config_; 00318 00320 mbf_abstract_nav::MoveBaseFlexConfig default_config_; 00321 00323 bool setup_reconfigure_; 00324 00326 std::string robot_frame_; 00327 00329 std::string global_frame_; 00330 00332 ros::Duration tf_timeout_; 00333 00335 const TFPtr tf_listener_ptr_; 00336 00338 geometry_msgs::PoseStamped robot_pose_; 00339 00341 geometry_msgs::PoseStamped goal_pose_; 00342 00344 ros::Duration oscillation_timeout_; 00345 00347 double oscillation_distance_; 00348 00350 bool recovery_enabled_; 00351 00353 bool clearing_rotation_allowed_; 00354 00356 ros::Publisher vel_pub_; 00357 00359 ros::Publisher goal_pub_; 00360 00361 RobotInformation robot_info_; 00362 00363 ControllerAction controller_action_; 00364 PlannerAction planner_action_; 00365 RecoveryAction recovery_action_; 00366 MoveBaseAction move_base_action_; 00367 }; 00368 00369 } /* namespace mbf_abstract_nav */ 00370 00371 #endif /* navigation_controller.h */