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 
46 #include <boost/shared_ptr.hpp>
47 #include <boost/thread/recursive_mutex.hpp>
48 
50 #include <dynamic_reconfigure/server.h>
51 #include <geometry_msgs/PoseStamped.h>
52 
54 
59 
64 
65 #include "mbf_abstract_nav/MoveBaseFlexConfig.h"
66 
67 namespace mbf_abstract_nav
68 {
69 
84 
88 
92 
96 
98 const std::string name_action_exe_path = "exe_path";
100 const std::string name_action_get_path = "get_path";
102 const std::string name_action_recovery = "recovery";
104 const std::string name_action_move_base = "move_base";
105 
106 
108 
119  {
120  public:
121 
127  AbstractNavigationServer(const TFPtr &tf_listener_ptr);
128 
132  virtual ~AbstractNavigationServer();
133 
134  virtual void stop();
135 
143  const std::string &plugin_name,
144  const mbf_abstract_core::AbstractPlanner::Ptr &plugin_ptr);
145 
153  const std::string &plugin_name,
155 
163  const std::string &plugin_name,
164  const mbf_abstract_core::AbstractRecovery::Ptr &plugin_ptr);
165 
171  virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type) = 0;
172 
179  virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string &controller_type) = 0;
180 
186  virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type) = 0;
187 
195  virtual bool initializePlannerPlugin(
196  const std::string &name,
197  const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr
198  ) = 0;
199 
207  virtual bool initializeControllerPlugin(
208  const std::string &name,
209  const mbf_abstract_core::AbstractController::Ptr &controller_ptr
210  ) = 0;
211 
219  virtual bool initializeRecoveryPlugin(
220  const std::string &name,
221  const mbf_abstract_core::AbstractRecovery::Ptr &behavior_ptr
222  ) = 0;
223 
224 
230  virtual void callActionGetPath(ActionServerGetPath::GoalHandle goal_handle);
231 
232  virtual void cancelActionGetPath(ActionServerGetPath::GoalHandle goal_handle);
233 
239  virtual void callActionExePath(ActionServerExePath::GoalHandle goal_handle);
240 
241  virtual void cancelActionExePath(ActionServerExePath::GoalHandle goal_handle);
242 
248  virtual void callActionRecovery(ActionServerRecovery::GoalHandle goal_handle);
249 
250  virtual void cancelActionRecovery(ActionServerRecovery::GoalHandle goal_handle);
251 
257  virtual void callActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle);
258 
259  virtual void cancelActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle);
260 
264  virtual void startActionServers();
265 
270  virtual void initializeServerComponents();
271 
272  protected:
273 
280  bool transformPlanToGlobalFrame(std::vector<geometry_msgs::PoseStamped> &plan,
281  std::vector<geometry_msgs::PoseStamped> &global_plan);
282 
287  virtual void startDynamicReconfigureServer();
288 
294  virtual void reconfigure(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level);
295 
298 
302 
305 
308 
311 
314 
317 
319  boost::mutex configuration_mutex_;
320 
322  mbf_abstract_nav::MoveBaseFlexConfig last_config_;
323 
325  mbf_abstract_nav::MoveBaseFlexConfig default_config_;
326 
329 
331  std::string robot_frame_;
332 
334  std::string global_frame_;
335 
338 
341 
344 
347 
350 
355  };
356 
357 } /* namespace mbf_abstract_nav */
358 
359 #endif /* MBF_ABSTRACT_NAV__ABSTRACT_NAVIGATION_SERVER_H_ */
mbf_abstract_nav::AbstractNavigationServer::callActionMoveBase
virtual void callActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle)
MoveBase action execution method. This method will be called if the action server receives a goal.
Definition: abstract_navigation_server.cpp:299
mbf_abstract_nav::AbstractNavigationServer::move_base_action_
MoveBaseAction move_base_action_
Definition: abstract_navigation_server.h:354
mbf_abstract_nav::AbstractNavigationServer::last_config_
mbf_abstract_nav::MoveBaseFlexConfig last_config_
last configuration save
Definition: abstract_navigation_server.h:322
mbf_abstract_nav::AbstractNavigationServer::configuration_mutex_
boost::mutex configuration_mutex_
configuration mutex for derived classes and other threads.
Definition: abstract_navigation_server.h:319
ros::Publisher
mbf_abstract_nav::AbstractNavigationServer::transformPlanToGlobalFrame
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.
mbf_abstract_nav::AbstractNavigationServer::recovery_action_
RecoveryAction recovery_action_
Definition: abstract_navigation_server.h:353
mbf_abstract_nav::AbstractNavigationServer::action_server_exe_path_ptr_
ActionServerExePathPtr action_server_exe_path_ptr_
shared pointer to the ExePath action server
Definition: abstract_navigation_server.h:307
boost::shared_ptr< ActionServerGetPath >
mbf_abstract_nav::AbstractNavigationServer::planner_plugin_manager_
AbstractPluginManager< mbf_abstract_core::AbstractPlanner > planner_plugin_manager_
Definition: abstract_navigation_server.h:299
mbf_abstract_nav::AbstractNavigationServer::callActionExePath
virtual void callActionExePath(ActionServerExePath::GoalHandle goal_handle)
ExePath action execution method. This method will be called if the action server receives a goal.
Definition: abstract_navigation_server.cpp:183
actionlib::ServerGoalHandle
mbf_abstract_nav::ActionServerRecoveryPtr
boost::shared_ptr< ActionServerRecovery > ActionServerRecoveryPtr
Definition: abstract_navigation_server.h:91
mbf_abstract_nav::AbstractNavigationServer::robot_info_
mbf_utility::RobotInformation robot_info_
current robot state
Definition: abstract_navigation_server.h:349
mbf_utility::RobotInformation
mbf_abstract_nav::ActionServerExePath
actionlib::ActionServer< mbf_msgs::ExePathAction > ActionServerExePath
ExePath action server.
Definition: abstract_navigation_server.h:86
mbf_abstract_nav::ActionServerRecovery
actionlib::ActionServer< mbf_msgs::RecoveryAction > ActionServerRecovery
Recovery action server.
Definition: abstract_navigation_server.h:90
mbf_abstract_nav::AbstractNavigationServer::recovery_plugin_manager_
AbstractPluginManager< mbf_abstract_core::AbstractRecovery > recovery_plugin_manager_
Definition: abstract_navigation_server.h:301
mbf_abstract_nav::AbstractNavigationServer::callActionRecovery
virtual void callActionRecovery(ActionServerRecovery::GoalHandle goal_handle)
Recovery action execution method. This method will be called if the action server receives a goal.
Definition: abstract_navigation_server.cpp:241
mbf_abstract_nav::AbstractNavigationServer::initializeServerComponents
virtual void initializeServerComponents()
initializes all server components. Initializing the plugins of the Planner, the Controller,...
Definition: abstract_navigation_server.cpp:112
actionlib::ActionServer
mbf_abstract_nav::AbstractNavigationServer::action_server_get_path_ptr_
ActionServerGetPathPtr action_server_get_path_ptr_
shared pointer to the GetPath action server
Definition: abstract_navigation_server.h:310
mbf_abstract_nav::AbstractNavigationServer
The AbstractNavigationServer is the abstract base class for all navigation servers in move_base_flex ...
Definition: abstract_navigation_server.h:118
mbf_abstract_nav::ActionServerMoveBasePtr
boost::shared_ptr< ActionServerMoveBase > ActionServerMoveBasePtr
Definition: abstract_navigation_server.h:95
mbf_abstract_nav::AbstractNavigationServer::dsrv_
DynamicReconfigureServer dsrv_
dynamic reconfigure server
Definition: abstract_navigation_server.h:316
mbf_abstract_nav::AbstractNavigationServer::private_nh_
ros::NodeHandle private_nh_
Private node handle.
Definition: abstract_navigation_server.h:297
mbf_abstract_nav::AbstractNavigationServer::cancelActionGetPath
virtual void cancelActionGetPath(ActionServerGetPath::GoalHandle goal_handle)
Definition: abstract_navigation_server.cpp:177
mbf_abstract_nav::AbstractNavigationServer::newRecoveryExecution
virtual mbf_abstract_nav::AbstractRecoveryExecution::Ptr newRecoveryExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractRecovery::Ptr &plugin_ptr)
Create a new abstract recovery behavior execution.
Definition: abstract_navigation_server.cpp:327
mbf_abstract_nav::RecoveryAction
Definition: recovery_action.h:56
mbf_abstract_nav::name_action_exe_path
const std::string name_action_exe_path
ExePath action topic name.
Definition: abstract_navigation_server.h:98
mbf_abstract_nav::AbstractNavigationServer::cancelActionExePath
virtual void cancelActionExePath(ActionServerExePath::GoalHandle goal_handle)
Definition: abstract_navigation_server.cpp:235
mbf_abstract_nav
Definition: abstract_controller_execution.h:58
mbf_abstract_nav::AbstractNavigationServer::initializePlannerPlugin
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,...
mbf_abstract_nav::AbstractPluginManager< mbf_abstract_core::AbstractPlanner >
mbf_abstract_nav::AbstractNavigationServer::vel_pub_
ros::Publisher vel_pub_
cmd_vel publisher for all controller execution objects
Definition: abstract_navigation_server.h:343
mbf_abstract_nav::DynamicReconfigureServer
boost::shared_ptr< dynamic_reconfigure::Server< mbf_abstract_nav::MoveBaseFlexConfig > > DynamicReconfigureServer
Definition: abstract_navigation_server.h:107
mbf_abstract_nav::name_action_get_path
const std::string name_action_get_path
GetPath action topic name.
Definition: abstract_navigation_server.h:100
mbf_abstract_nav::AbstractNavigationServer::callActionGetPath
virtual void callActionGetPath(ActionServerGetPath::GoalHandle goal_handle)
GetPath action execution method. This method will be called if the action server receives a goal.
Definition: abstract_navigation_server.cpp:124
mbf_abstract_nav::AbstractNavigationServer::action_server_move_base_ptr_
ActionServerMoveBasePtr action_server_move_base_ptr_
shared pointer to the MoveBase action server
Definition: abstract_navigation_server.h:313
mbf_abstract_nav::AbstractNavigationServer::tf_listener_ptr_
const TFPtr tf_listener_ptr_
shared pointer to the common TransformListener
Definition: abstract_navigation_server.h:340
mbf_abstract_nav::AbstractNavigationServer::newPlannerExecution
virtual mbf_abstract_nav::AbstractPlannerExecution::Ptr newPlannerExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractPlanner::Ptr &plugin_ptr)
Create a new abstract planner execution.
Definition: abstract_navigation_server.cpp:312
mbf_abstract_nav::AbstractNavigationServer::initializeControllerPlugin
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,...
mbf_abstract_nav::ActionServerGetPath
actionlib::ActionServer< mbf_msgs::GetPathAction > ActionServerGetPath
GetPath action server.
Definition: abstract_navigation_server.h:82
controller_action.h
move_base_action.h
mbf_abstract_nav::AbstractNavigationServer::~AbstractNavigationServer
virtual ~AbstractNavigationServer()
Destructor.
Definition: abstract_navigation_server.cpp:119
mbf_abstract_nav::AbstractNavigationServer::robot_frame_
std::string robot_frame_
the robot frame, to get the current robot pose in the global_frame_
Definition: abstract_navigation_server.h:331
mbf_abstract_nav::AbstractNavigationServer::loadPlannerPlugin
virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type)=0
Loads the plugin associated with the given planner_type parameter.
mbf_abstract_nav::AbstractNavigationServer::reconfigure
virtual void reconfigure(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
Reconfiguration method called by dynamic reconfigure.
Definition: abstract_navigation_server.cpp:350
mbf_abstract_nav::AbstractNavigationServer::startActionServers
virtual void startActionServers()
starts all action server.
Definition: abstract_navigation_server.cpp:335
abstract_controller_execution.h
mbf_abstract_nav::AbstractNavigationServer::loadControllerPlugin
virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string &controller_type)=0
Loads the plugin associated with the given controller type parameter.
abstract_recovery_execution.h
mbf_abstract_nav::AbstractNavigationServer::planner_action_
PlannerAction planner_action_
Definition: abstract_navigation_server.h:352
action_server.h
mbf_abstract_nav::name_action_recovery
const std::string name_action_recovery
Recovery action topic name.
Definition: abstract_navigation_server.h:102
recovery_action.h
mbf_abstract_nav::AbstractNavigationServer::global_frame_
std::string global_frame_
the global frame, in which the robot is moving
Definition: abstract_navigation_server.h:334
mbf_abstract_nav::AbstractNavigationServer::controller_action_
ControllerAction controller_action_
Definition: abstract_navigation_server.h:351
mbf_abstract_nav::AbstractNavigationServer::loadRecoveryPlugin
virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type)=0
Loads a Recovery plugin associated with given recovery type parameter.
mbf_abstract_nav::MoveBaseAction
Definition: move_base_action.h:59
mbf_abstract_nav::AbstractNavigationServer::action_server_recovery_ptr_
ActionServerRecoveryPtr action_server_recovery_ptr_
shared pointer to the Recovery action server
Definition: abstract_navigation_server.h:304
mbf_abstract_nav::ActionServerGetPathPtr
boost::shared_ptr< ActionServerGetPath > ActionServerGetPathPtr
Definition: abstract_navigation_server.h:83
mbf_abstract_nav::AbstractNavigationServer::setup_reconfigure_
bool setup_reconfigure_
true, if the dynamic reconfigure has been setup.
Definition: abstract_navigation_server.h:328
mbf_abstract_nav::AbstractNavigationServer::controller_plugin_manager_
AbstractPluginManager< mbf_abstract_core::AbstractController > controller_plugin_manager_
Definition: abstract_navigation_server.h:300
mbf_abstract_nav::name_action_move_base
const std::string name_action_move_base
MoveBase action topic name.
Definition: abstract_navigation_server.h:104
mbf_abstract_nav::AbstractNavigationServer::default_config_
mbf_abstract_nav::MoveBaseFlexConfig default_config_
the default parameter configuration save
Definition: abstract_navigation_server.h:325
mbf_abstract_nav::AbstractNavigationServer::cancelActionRecovery
virtual void cancelActionRecovery(ActionServerRecovery::GoalHandle goal_handle)
Definition: abstract_navigation_server.cpp:293
mbf_abstract_nav::ActionServerExePathPtr
boost::shared_ptr< ActionServerExePath > ActionServerExePathPtr
Definition: abstract_navigation_server.h:87
mbf_abstract_nav::AbstractNavigationServer::startDynamicReconfigureServer
virtual void startDynamicReconfigureServer()
Start a dynamic reconfigure server. This must be called only if the extending doesn't create its own.
Definition: abstract_navigation_server.cpp:343
mbf_abstract_nav::AbstractNavigationServer::AbstractNavigationServer
AbstractNavigationServer(const TFPtr &tf_listener_ptr)
Constructor, reads all parameters and initializes all action servers and creates the plugin instances...
Definition: abstract_navigation_server.cpp:48
mbf_abstract_nav::AbstractNavigationServer::goal_pub_
ros::Publisher goal_pub_
current_goal publisher for all controller execution objects
Definition: abstract_navigation_server.h:346
mbf_abstract_nav::ControllerAction
Definition: controller_action.h:55
mbf_abstract_nav::ActionServerMoveBase
actionlib::ActionServer< mbf_msgs::MoveBaseAction > ActionServerMoveBase
MoveBase action server.
Definition: abstract_navigation_server.h:94
mbf_abstract_nav::AbstractNavigationServer::stop
virtual void stop()
Definition: abstract_navigation_server.cpp:376
navigation_utility.h
ros::Duration
mbf_abstract_nav::AbstractNavigationServer::tf_timeout_
ros::Duration tf_timeout_
timeout after tf returns without a result
Definition: abstract_navigation_server.h:337
abstract_plugin_manager.h
mbf_abstract_nav::AbstractNavigationServer::initializeRecoveryPlugin
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,...
mbf_abstract_nav::PlannerAction
Definition: planner_action.h:56
mbf_abstract_nav::AbstractNavigationServer::cancelActionMoveBase
virtual void cancelActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle)
Definition: abstract_navigation_server.cpp:305
ros::NodeHandle
mbf_abstract_nav::AbstractNavigationServer::newControllerExecution
virtual mbf_abstract_nav::AbstractControllerExecution::Ptr newControllerExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractController::Ptr &plugin_ptr)
Create a new abstract controller execution.
Definition: abstract_navigation_server.cpp:319
planner_action.h
abstract_planner_execution.h


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