40 #ifndef MBF_ABSTRACT_NAV__MOVE_BASE_ACTION_H_    41 #define MBF_ABSTRACT_NAV__MOVE_BASE_ACTION_H_    46 #include <mbf_msgs/MoveBaseAction.h>    47 #include <mbf_msgs/GetPathAction.h>    48 #include <mbf_msgs/ExePathAction.h>    49 #include <mbf_msgs/RecoveryAction.h>    51 #include "mbf_abstract_nav/MoveBaseFlexConfig.h"    73   void start(GoalHandle &goal_handle);
    78       mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level);
    86       const mbf_msgs::GetPathResultConstPtr &result);
    92       const mbf_msgs::ExePathResultConstPtr &result);
    96       const mbf_msgs::GetPathResultConstPtr &result);
   100       const mbf_msgs::RecoveryResultConstPtr &result);
   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_
ros::Duration oscillation_timeout_
geometry_msgs::PoseStamped last_oscillation_pose_
void actionExePathDone(const actionlib::SimpleClientGoalState &state, const mbf_msgs::ExePathResultConstPtr &result)
ros::Time last_oscillation_reset_
MoveBaseAction(const std::string &name, const RobotInformation &robot_info, const std::vector< std::string > &controllers)
ros::Rate replanning_rate_
ActionClientGetPath action_client_get_path_
Action client used by the move_base action. 
void reconfigure(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
ros::NodeHandle private_nh_
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)
MoveBaseActionState action_state_
mbf_msgs::ExePathGoal exe_path_goal_
MoveBaseActionState recovery_trigger_
actionlib::SimpleActionClient< mbf_msgs::GetPathAction > ActionClientGetPath
Action clients for the MoveBase action. 
boost::mutex replanning_mtx_
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)
RobotInformation robot_info_
void actionExePathActive()
ActionClientExePath action_client_exe_path_
Action client used by the move_base action. 
void start(GoalHandle &goal_handle)
double oscillation_distance_