Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #ifndef MBF_ABSTRACT_NAV__MOVE_BASE_ACTION_H_
00041 #define MBF_ABSTRACT_NAV__MOVE_BASE_ACTION_H_
00042
00043 #include <actionlib/server/action_server.h>
00044 #include <actionlib/client/simple_action_client.h>
00045
00046 #include <mbf_msgs/MoveBaseAction.h>
00047 #include <mbf_msgs/GetPathAction.h>
00048 #include <mbf_msgs/ExePathAction.h>
00049 #include <mbf_msgs/RecoveryAction.h>
00050
00051 #include "mbf_abstract_nav/MoveBaseFlexConfig.h"
00052 #include "mbf_abstract_nav/robot_information.h"
00053
00054
00055 namespace mbf_abstract_nav
00056 {
00057
00058 class MoveBaseAction
00059 {
00060 public:
00061
00063 typedef actionlib::SimpleActionClient<mbf_msgs::GetPathAction> ActionClientGetPath;
00064 typedef actionlib::SimpleActionClient<mbf_msgs::ExePathAction> ActionClientExePath;
00065 typedef actionlib::SimpleActionClient<mbf_msgs::RecoveryAction> ActionClientRecovery;
00066
00067 typedef actionlib::ActionServer<mbf_msgs::MoveBaseAction>::GoalHandle GoalHandle;
00068
00069 MoveBaseAction(const std::string &name, const RobotInformation &robot_info, const std::vector<std::string> &controllers);
00070
00071 ~MoveBaseAction();
00072
00073 void start(GoalHandle &goal_handle);
00074
00075 void cancel();
00076
00077 void reconfigure(
00078 mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level);
00079
00080 protected:
00081
00082 void actionExePathFeedback(const mbf_msgs::ExePathFeedbackConstPtr &feedback);
00083
00084 void actionGetPathDone(
00085 const actionlib::SimpleClientGoalState &state,
00086 const mbf_msgs::GetPathResultConstPtr &result);
00087
00088 void actionExePathActive();
00089
00090 void actionExePathDone(
00091 const actionlib::SimpleClientGoalState &state,
00092 const mbf_msgs::ExePathResultConstPtr &result);
00093
00094 void actionGetPathReplanningDone(
00095 const actionlib::SimpleClientGoalState &state,
00096 const mbf_msgs::GetPathResultConstPtr &result);
00097
00098 void actionRecoveryDone(
00099 const actionlib::SimpleClientGoalState &state,
00100 const mbf_msgs::RecoveryResultConstPtr &result);
00101
00102 bool attemptRecovery();
00103
00104 mbf_msgs::ExePathGoal exe_path_goal_;
00105 mbf_msgs::GetPathGoal get_path_goal_;
00106 mbf_msgs::RecoveryGoal recovery_goal_;
00107
00108 geometry_msgs::PoseStamped last_oscillation_pose_;
00109 ros::Time last_oscillation_reset_;
00110
00111 ros::Duration oscillation_timeout_;
00112
00113 double oscillation_distance_;
00114
00115 GoalHandle goal_handle_;
00116
00117 std::string name_;
00118
00119 RobotInformation robot_info_;
00120
00121 geometry_msgs::PoseStamped robot_pose_;
00122
00123 ros::NodeHandle private_nh_;
00124
00126 ActionClientExePath action_client_exe_path_;
00127
00129 ActionClientGetPath action_client_get_path_;
00130
00132 ActionClientRecovery action_client_recovery_;
00133
00134 bool replanning_;
00135 ros::Rate replanning_rate_;
00136 boost::mutex replanning_mtx_;
00137
00138 bool recovery_enabled_;
00139
00140 mbf_msgs::MoveBaseFeedback move_base_feedback_;
00141
00142 std::vector<std::string> recovery_behaviors_;
00143
00144 std::vector<std::string>::iterator current_recovery_behavior_;
00145
00146 const std::vector<std::string> &behaviors_;
00147
00148 enum MoveBaseActionState
00149 {
00150 NONE,
00151 GET_PATH,
00152 EXE_PATH,
00153 RECOVERY,
00154 OSCILLATING,
00155 SUCCEEDED,
00156 CANCELED,
00157 FAILED
00158 };
00159
00160 MoveBaseActionState action_state_;
00161 MoveBaseActionState recovery_trigger_;
00162 };
00163
00164 }
00165
00166 #endif //MBF_ABSTRACT_NAV__MOVE_BASE_ACTION_H_