#include <move_base_action.h>
Public Types | |
typedef actionlib::SimpleActionClient < mbf_msgs::ExePathAction > | ActionClientExePath |
typedef actionlib::SimpleActionClient < mbf_msgs::GetPathAction > | ActionClientGetPath |
Action clients for the MoveBase action. | |
typedef actionlib::SimpleActionClient < mbf_msgs::RecoveryAction > | ActionClientRecovery |
typedef actionlib::ActionServer < mbf_msgs::MoveBaseAction > ::GoalHandle | GoalHandle |
Public Member Functions | |
void | cancel () |
MoveBaseAction (const std::string &name, const RobotInformation &robot_info, const std::vector< std::string > &controllers) | |
void | reconfigure (mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level) |
void | start (GoalHandle &goal_handle) |
~MoveBaseAction () | |
Protected Types | |
enum | MoveBaseActionState { NONE, GET_PATH, EXE_PATH, RECOVERY, OSCILLATING, SUCCEEDED, CANCELED, FAILED } |
Protected Member Functions | |
void | actionExePathActive () |
void | actionExePathDone (const actionlib::SimpleClientGoalState &state, const mbf_msgs::ExePathResultConstPtr &result) |
void | actionExePathFeedback (const mbf_msgs::ExePathFeedbackConstPtr &feedback) |
void | actionGetPathDone (const actionlib::SimpleClientGoalState &state, const mbf_msgs::GetPathResultConstPtr &result) |
void | actionGetPathReplanningDone (const actionlib::SimpleClientGoalState &state, const mbf_msgs::GetPathResultConstPtr &result) |
void | actionRecoveryDone (const actionlib::SimpleClientGoalState &state, const mbf_msgs::RecoveryResultConstPtr &result) |
bool | attemptRecovery () |
Protected Attributes | |
ActionClientExePath | action_client_exe_path_ |
Action client used by the move_base action. | |
ActionClientGetPath | action_client_get_path_ |
Action client used by the move_base action. | |
ActionClientRecovery | action_client_recovery_ |
Action client used by the move_base action. | |
MoveBaseActionState | action_state_ |
const std::vector< std::string > & | behaviors_ |
std::vector< std::string > ::iterator | current_recovery_behavior_ |
mbf_msgs::ExePathGoal | exe_path_goal_ |
mbf_msgs::GetPathGoal | get_path_goal_ |
GoalHandle | goal_handle_ |
geometry_msgs::PoseStamped | last_oscillation_pose_ |
ros::Time | last_oscillation_reset_ |
mbf_msgs::MoveBaseFeedback | move_base_feedback_ |
std::string | name_ |
double | oscillation_distance_ |
ros::Duration | oscillation_timeout_ |
ros::NodeHandle | private_nh_ |
std::vector< std::string > | recovery_behaviors_ |
bool | recovery_enabled_ |
mbf_msgs::RecoveryGoal | recovery_goal_ |
MoveBaseActionState | recovery_trigger_ |
bool | replanning_ |
boost::mutex | replanning_mtx_ |
ros::Rate | replanning_rate_ |
RobotInformation | robot_info_ |
geometry_msgs::PoseStamped | robot_pose_ |
Definition at line 58 of file move_base_action.h.
typedef actionlib::SimpleActionClient<mbf_msgs::ExePathAction> mbf_abstract_nav::MoveBaseAction::ActionClientExePath |
Definition at line 64 of file move_base_action.h.
typedef actionlib::SimpleActionClient<mbf_msgs::GetPathAction> mbf_abstract_nav::MoveBaseAction::ActionClientGetPath |
Action clients for the MoveBase action.
Definition at line 63 of file move_base_action.h.
typedef actionlib::SimpleActionClient<mbf_msgs::RecoveryAction> mbf_abstract_nav::MoveBaseAction::ActionClientRecovery |
Definition at line 65 of file move_base_action.h.
typedef actionlib::ActionServer<mbf_msgs::MoveBaseAction>::GoalHandle mbf_abstract_nav::MoveBaseAction::GoalHandle |
Definition at line 67 of file move_base_action.h.
enum mbf_abstract_nav::MoveBaseAction::MoveBaseActionState [protected] |
Definition at line 148 of file move_base_action.h.
mbf_abstract_nav::MoveBaseAction::MoveBaseAction | ( | const std::string & | name, |
const RobotInformation & | robot_info, | ||
const std::vector< std::string > & | controllers | ||
) |
Definition at line 49 of file move_base_action.cpp.
Definition at line 67 of file move_base_action.cpp.
void mbf_abstract_nav::MoveBaseAction::actionExePathActive | ( | ) | [protected] |
Definition at line 181 of file move_base_action.cpp.
void mbf_abstract_nav::MoveBaseAction::actionExePathDone | ( | const actionlib::SimpleClientGoalState & | state, |
const mbf_msgs::ExePathResultConstPtr & | result | ||
) | [protected] |
Definition at line 355 of file move_base_action.cpp.
void mbf_abstract_nav::MoveBaseAction::actionExePathFeedback | ( | const mbf_msgs::ExePathFeedbackConstPtr & | feedback | ) | [protected] |
Definition at line 186 of file move_base_action.cpp.
void mbf_abstract_nav::MoveBaseAction::actionGetPathDone | ( | const actionlib::SimpleClientGoalState & | state, |
const mbf_msgs::GetPathResultConstPtr & | result | ||
) | [protected] |
Definition at line 246 of file move_base_action.cpp.
void mbf_abstract_nav::MoveBaseAction::actionGetPathReplanningDone | ( | const actionlib::SimpleClientGoalState & | state, |
const mbf_msgs::GetPathResultConstPtr & | result | ||
) | [protected] |
Definition at line 567 of file move_base_action.cpp.
void mbf_abstract_nav::MoveBaseAction::actionRecoveryDone | ( | const actionlib::SimpleClientGoalState & | state, |
const mbf_msgs::RecoveryResultConstPtr & | result | ||
) | [protected] |
Definition at line 477 of file move_base_action.cpp.
bool mbf_abstract_nav::MoveBaseAction::attemptRecovery | ( | ) | [protected] |
Definition at line 445 of file move_base_action.cpp.
Definition at line 102 of file move_base_action.cpp.
void mbf_abstract_nav::MoveBaseAction::reconfigure | ( | mbf_abstract_nav::MoveBaseFlexConfig & | config, |
uint32_t | level | ||
) |
Definition at line 71 of file move_base_action.cpp.
void mbf_abstract_nav::MoveBaseAction::start | ( | GoalHandle & | goal_handle | ) |
Definition at line 122 of file move_base_action.cpp.
Action client used by the move_base action.
Definition at line 126 of file move_base_action.h.
Action client used by the move_base action.
Definition at line 129 of file move_base_action.h.
Action client used by the move_base action.
Definition at line 132 of file move_base_action.h.
Definition at line 160 of file move_base_action.h.
const std::vector<std::string>& mbf_abstract_nav::MoveBaseAction::behaviors_ [protected] |
Definition at line 146 of file move_base_action.h.
std::vector<std::string>::iterator mbf_abstract_nav::MoveBaseAction::current_recovery_behavior_ [protected] |
Definition at line 144 of file move_base_action.h.
mbf_msgs::ExePathGoal mbf_abstract_nav::MoveBaseAction::exe_path_goal_ [protected] |
Definition at line 104 of file move_base_action.h.
mbf_msgs::GetPathGoal mbf_abstract_nav::MoveBaseAction::get_path_goal_ [protected] |
Definition at line 105 of file move_base_action.h.
Definition at line 115 of file move_base_action.h.
geometry_msgs::PoseStamped mbf_abstract_nav::MoveBaseAction::last_oscillation_pose_ [protected] |
Definition at line 108 of file move_base_action.h.
Definition at line 109 of file move_base_action.h.
mbf_msgs::MoveBaseFeedback mbf_abstract_nav::MoveBaseAction::move_base_feedback_ [protected] |
Definition at line 140 of file move_base_action.h.
std::string mbf_abstract_nav::MoveBaseAction::name_ [protected] |
Definition at line 117 of file move_base_action.h.
double mbf_abstract_nav::MoveBaseAction::oscillation_distance_ [protected] |
Definition at line 113 of file move_base_action.h.
Definition at line 111 of file move_base_action.h.
Definition at line 123 of file move_base_action.h.
std::vector<std::string> mbf_abstract_nav::MoveBaseAction::recovery_behaviors_ [protected] |
Definition at line 142 of file move_base_action.h.
bool mbf_abstract_nav::MoveBaseAction::recovery_enabled_ [protected] |
Definition at line 138 of file move_base_action.h.
mbf_msgs::RecoveryGoal mbf_abstract_nav::MoveBaseAction::recovery_goal_ [protected] |
Definition at line 106 of file move_base_action.h.
Definition at line 161 of file move_base_action.h.
bool mbf_abstract_nav::MoveBaseAction::replanning_ [protected] |
Definition at line 134 of file move_base_action.h.
boost::mutex mbf_abstract_nav::MoveBaseAction::replanning_mtx_ [protected] |
Definition at line 136 of file move_base_action.h.
Definition at line 135 of file move_base_action.h.
Definition at line 119 of file move_base_action.h.
geometry_msgs::PoseStamped mbf_abstract_nav::MoveBaseAction::robot_pose_ [protected] |
Definition at line 121 of file move_base_action.h.