move_base_action.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  * move_base_action.h
34  *
35  * authors:
36  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
37  * Jorge Santos Simón <santos@magazino.eu>
38  *
39  */
40 #ifndef MBF_ABSTRACT_NAV__MOVE_BASE_ACTION_H_
41 #define MBF_ABSTRACT_NAV__MOVE_BASE_ACTION_H_
42 
45 
46 #include <mbf_msgs/MoveBaseAction.h>
47 #include <mbf_msgs/GetPathAction.h>
48 #include <mbf_msgs/ExePathAction.h>
49 #include <mbf_msgs/RecoveryAction.h>
50 
51 #include "mbf_abstract_nav/MoveBaseFlexConfig.h"
53 
54 
55 namespace mbf_abstract_nav
56 {
57 
59 {
60  public:
61 
66 
68 
69  MoveBaseAction(const std::string &name, const RobotInformation &robot_info, const std::vector<std::string> &controllers);
70 
72 
73  void start(GoalHandle &goal_handle);
74 
75  void cancel();
76 
77  void reconfigure(
78  mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level);
79 
80  protected:
81 
82  void actionExePathFeedback(const mbf_msgs::ExePathFeedbackConstPtr &feedback);
83 
84  void actionGetPathDone(
86  const mbf_msgs::GetPathResultConstPtr &result);
87 
88  void actionExePathActive();
89 
90  void actionExePathDone(
92  const mbf_msgs::ExePathResultConstPtr &result);
93 
96  const mbf_msgs::GetPathResultConstPtr &result);
97 
98  void actionRecoveryDone(
100  const mbf_msgs::RecoveryResultConstPtr &result);
101 
102  bool attemptRecovery();
103 
104  mbf_msgs::ExePathGoal exe_path_goal_;
105  mbf_msgs::GetPathGoal get_path_goal_;
106  mbf_msgs::RecoveryGoal recovery_goal_;
107 
108  geometry_msgs::PoseStamped last_oscillation_pose_;
110 
112 
114 
115  GoalHandle goal_handle_;
116 
117  std::string name_;
118 
120 
121  geometry_msgs::PoseStamped robot_pose_;
122 
124 
126  ActionClientExePath action_client_exe_path_;
127 
129  ActionClientGetPath action_client_get_path_;
130 
132  ActionClientRecovery action_client_recovery_;
133 
136  boost::mutex replanning_mtx_;
137 
139 
140  mbf_msgs::MoveBaseFeedback move_base_feedback_;
141 
142  std::vector<std::string> recovery_behaviors_;
143 
144  std::vector<std::string>::iterator current_recovery_behavior_;
145 
146  const std::vector<std::string> &behaviors_;
147 
149  {
158  };
159 
162 };
163 
164 } /* mbf_abstract_nav */
165 
166 #endif //MBF_ABSTRACT_NAV__MOVE_BASE_ACTION_H_
actionlib::SimpleActionClient< mbf_msgs::ExePathAction > ActionClientExePath
std::vector< std::string > recovery_behaviors_
mbf_msgs::GetPathGoal get_path_goal_
mbf_msgs::MoveBaseFeedback move_base_feedback_
geometry_msgs::PoseStamped last_oscillation_pose_
void actionExePathDone(const actionlib::SimpleClientGoalState &state, const mbf_msgs::ExePathResultConstPtr &result)
MoveBaseAction(const std::string &name, const RobotInformation &robot_info, const std::vector< std::string > &controllers)
ActionClientGetPath action_client_get_path_
Action client used by the move_base action.
void reconfigure(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
const std::vector< std::string > & behaviors_
mbf_msgs::RecoveryGoal recovery_goal_
void actionRecoveryDone(const actionlib::SimpleClientGoalState &state, const mbf_msgs::RecoveryResultConstPtr &result)
actionlib::SimpleActionClient< mbf_msgs::RecoveryAction > ActionClientRecovery
void actionGetPathDone(const actionlib::SimpleClientGoalState &state, const mbf_msgs::GetPathResultConstPtr &result)
mbf_msgs::ExePathGoal exe_path_goal_
MoveBaseActionState recovery_trigger_
actionlib::SimpleActionClient< mbf_msgs::GetPathAction > ActionClientGetPath
Action clients for the MoveBase action.
actionlib::ActionServer< mbf_msgs::MoveBaseAction >::GoalHandle GoalHandle
std::vector< std::string >::iterator current_recovery_behavior_
geometry_msgs::PoseStamped robot_pose_
ActionClientRecovery action_client_recovery_
Action client used by the move_base action.
void actionGetPathReplanningDone(const actionlib::SimpleClientGoalState &state, const mbf_msgs::GetPathResultConstPtr &result)
void actionExePathFeedback(const mbf_msgs::ExePathFeedbackConstPtr &feedback)
ActionClientExePath action_client_exe_path_
Action client used by the move_base action.
void start(GoalHandle &goal_handle)


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