abstract_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  * abstract_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_ABSTRACT_NAV__ABSTRACT_NAVIGATION_SERVER_H_
42 #define MBF_ABSTRACT_NAV__ABSTRACT_NAVIGATION_SERVER_H_
43 
44 #include <string>
45 #include <stdint.h>
46 
47 #include <boost/shared_ptr.hpp>
48 #include <boost/thread/recursive_mutex.hpp>
49 
51 #include <dynamic_reconfigure/server.h>
52 #include <geometry_msgs/PoseStamped.h>
53 #include <tf/transform_listener.h>
54 
56 
61 
66 
67 #include "mbf_abstract_nav/MoveBaseFlexConfig.h"
68 
69 namespace mbf_abstract_nav
70 {
85 
89 
93 
97 
99 const std::string name_action_exe_path = "exe_path";
101 const std::string name_action_get_path = "get_path";
103 const std::string name_action_recovery = "recovery";
105 const std::string name_action_move_base = "move_base";
106 
107 
109 
120  {
121  public:
122 
131  AbstractNavigationServer(const TFPtr &tf_listener_ptr);
135  virtual ~AbstractNavigationServer();
136 
137  virtual void stop();
138 
141  const std::string plugin_name,
142  const mbf_abstract_core::AbstractPlanner::Ptr plugin_ptr);
143 
146  const std::string plugin_name,
148 
151  const std::string plugin_name,
153 
159  virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string& planner_type) = 0;
160 
167  virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string& controller_type) = 0;
168 
174  virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string& recovery_type) = 0;
175 
183  virtual bool initializePlannerPlugin(
184  const std::string& name,
185  const mbf_abstract_core::AbstractPlanner::Ptr& planner_ptr
186  ) = 0;
187 
195  virtual bool initializeControllerPlugin(
196  const std::string& name,
197  const mbf_abstract_core::AbstractController::Ptr& controller_ptr
198  ) = 0;
199 
207  virtual bool initializeRecoveryPlugin(
208  const std::string& name,
209  const mbf_abstract_core::AbstractRecovery::Ptr& behavior_ptr
210  ) = 0;
211 
212 
218  virtual void callActionGetPath(ActionServerGetPath::GoalHandle goal_handle);
219 
220  virtual void cancelActionGetPath(ActionServerGetPath::GoalHandle goal_handle);
221 
227  virtual void callActionExePath(ActionServerExePath::GoalHandle goal_handle);
228 
229  virtual void cancelActionExePath(ActionServerExePath::GoalHandle goal_handle);
230 
236  virtual void callActionRecovery(ActionServerRecovery::GoalHandle goal_handle);
237 
238  virtual void cancelActionRecovery(ActionServerRecovery::GoalHandle goal_handle);
239 
245  virtual void callActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle);
246 
247  virtual void cancelActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle);
248 
252  virtual void startActionServers();
253 
258  virtual void initializeServerComponents();
259 
265  bool getRobotPose(geometry_msgs::PoseStamped &robot_pose);
266 
267  protected:
268 
275  bool transformPlanToGlobalFrame(std::vector<geometry_msgs::PoseStamped> &plan,
276  std::vector<geometry_msgs::PoseStamped> &global_plan);
277 
282  virtual void startDynamicReconfigureServer();
283 
289  virtual void reconfigure(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level);
290 
293 
297 
299  ActionServerRecoveryPtr action_server_recovery_ptr_;
300 
302  ActionServerExePathPtr action_server_exe_path_ptr_;
303 
305  ActionServerGetPathPtr action_server_get_path_ptr_;
306 
308  ActionServerMoveBasePtr action_server_move_base_ptr_;
309 
311  DynamicReconfigureServer dsrv_;
312 
314  boost::mutex configuration_mutex_;
315 
317  mbf_abstract_nav::MoveBaseFlexConfig last_config_;
318 
320  mbf_abstract_nav::MoveBaseFlexConfig default_config_;
321 
324 
326  std::string robot_frame_;
327 
329  std::string global_frame_;
330 
333 
336 
338  geometry_msgs::PoseStamped robot_pose_;
339 
341  geometry_msgs::PoseStamped goal_pose_;
342 
345 
348 
351 
354 
357 
360 
362 
367  };
368 
369 } /* namespace mbf_abstract_nav */
370 
371 #endif /* navigation_controller.h */
bool recovery_enabled_
true, if recovery behavior for the MoveBase action is enabled.
ActionServerRecoveryPtr action_server_recovery_ptr_
shared pointer to the Recovery action server
actionlib::ActionServer< mbf_msgs::MoveBaseAction > ActionServerMoveBase
MoveBase action server.
virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type)=0
Loads a Recovery plugin associated with given recovery type parameter.
actionlib::ActionServer< mbf_msgs::RecoveryAction > ActionServerRecovery
Recovery action server.
ros::Publisher goal_pub_
current_goal publisher for all controller execution objects
virtual void cancelActionRecovery(ActionServerRecovery::GoalHandle goal_handle)
const TFPtr tf_listener_ptr_
shared pointer to the common TransformListener
virtual bool initializePlannerPlugin(const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr)=0
Pure virtual method, the derived class has to implement. Depending on the plugin base class...
std::string global_frame_
the global frame, in which the robot is moving
boost::shared_ptr< ActionServerMoveBase > ActionServerMoveBasePtr
std::string robot_frame_
the robot frame, to get the current robot pose in the global_frame_
AbstractPluginManager< mbf_abstract_core::AbstractController > controller_plugin_manager_
virtual void startDynamicReconfigureServer()
Start a dynamic reconfigure server. This must be called only if the extending doesn&#39;t create its own...
virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string &controller_type)=0
Loads the plugin associated with the given controller type parameter.
virtual bool initializeControllerPlugin(const std::string &name, const mbf_abstract_core::AbstractController::Ptr &controller_ptr)=0
Pure virtual method, the derived class has to implement. Depending on the plugin base class...
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
const std::string name_action_get_path
GetPath action topic name.
The AbstractNavigationServer is the abstract base class for all navigation servers in move_base_flex ...
virtual void cancelActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle)
virtual void reconfigure(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
Reconfiguration method called by dynamic reconfigure.
boost::shared_ptr< dynamic_reconfigure::Server< mbf_abstract_nav::MoveBaseFlexConfig > > DynamicReconfigureServer
actionlib::ActionServer< mbf_msgs::GetPathAction > ActionServerGetPath
GetPath action server.
virtual bool initializeRecoveryPlugin(const std::string &name, const mbf_abstract_core::AbstractRecovery::Ptr &behavior_ptr)=0
Pure virtual method, the derived class has to implement. Depending on the plugin base class...
actionlib::ActionServer< mbf_msgs::ExePathAction > ActionServerExePath
ExePath action server.
geometry_msgs::PoseStamped robot_pose_
current robot pose; moving controller is responsible to update it by calling getRobotPose ...
virtual void callActionExePath(ActionServerExePath::GoalHandle goal_handle)
ExePath action execution method. This method will be called if the action server receives a goal...
ActionServerGetPathPtr action_server_get_path_ptr_
shared pointer to the GetPath action server
const std::string name_action_exe_path
ExePath action topic name.
AbstractPluginManager< mbf_abstract_core::AbstractPlanner > planner_plugin_manager_
bool setup_reconfigure_
true, if the dynamic reconfigure has been setup.
bool clearing_rotation_allowed_
true, if clearing rotate is allowed.
bool getRobotPose(geometry_msgs::PoseStamped &robot_pose)
Computes the current robot pose (robot_frame_) in the global frame (global_frame_).
mbf_abstract_nav::MoveBaseFlexConfig default_config_
the default parameter configuration save
virtual void callActionRecovery(ActionServerRecovery::GoalHandle goal_handle)
Recovery action execution method. This method will be called if the action server receives a goal...
AbstractNavigationServer(const TFPtr &tf_listener_ptr)
Constructor, reads all parameters and initializes all action servers and creates the plugin instances...
ros::Publisher vel_pub_
cmd_vel publisher for all controller execution objects
virtual void cancelActionExePath(ActionServerExePath::GoalHandle goal_handle)
ros::Duration tf_timeout_
timeout after tf returns without a result
boost::shared_ptr< ActionServerGetPath > ActionServerGetPathPtr
virtual void callActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle)
MoveBase action execution method. This method will be called if the action server receives a goal...
geometry_msgs::PoseStamped goal_pose_
current goal pose; used to compute remaining distance and angle
mbf_abstract_nav::MoveBaseFlexConfig last_config_
last configuration save
ActionServerMoveBasePtr action_server_move_base_ptr_
shared pointer to the MoveBase action server
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
boost::shared_ptr< ActionServerExePath > ActionServerExePathPtr
ActionServerExePathPtr action_server_exe_path_ptr_
shared pointer to the ExePath action server
bool transformPlanToGlobalFrame(std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &global_plan)
Transforms a plan to the global frame (global_frame_) coord system.
const std::string name_action_recovery
Recovery action topic name.
virtual void callActionGetPath(ActionServerGetPath::GoalHandle goal_handle)
GetPath action execution method. This method will be called if the action server receives a goal...
boost::mutex configuration_mutex_
configuration mutex for derived classes and other threads.
AbstractPluginManager< mbf_abstract_core::AbstractRecovery > recovery_plugin_manager_
virtual void cancelActionGetPath(ActionServerGetPath::GoalHandle goal_handle)
virtual void startActionServers()
starts all action server.
virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type)=0
Loads the plugin associated with the given planner_type parameter.
const std::string name_action_move_base
MoveBase action topic name.
ros::Duration oscillation_timeout_
timeout after a oscillation is detected
DynamicReconfigureServer dsrv_
dynamic reconfigure server
virtual void initializeServerComponents()
initializes all server components. Initializing the plugins of the Planner, the Controller, and the Recovery Behavior.
double oscillation_distance_
minimal move distance to not detect an oscillation
boost::shared_ptr< ActionServerRecovery > ActionServerRecoveryPtr
ros::NodeHandle private_nh_
Private node handle.
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


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