#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. More... | |
| 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 mbf_utility::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 () |
| template<typename ResultType > | |
| void | fillMoveBaseResult (const ResultType &result, mbf_msgs::MoveBaseResult &move_base_result) |
Protected Attributes | |
| ActionClientExePath | action_client_exe_path_ |
| Action client used by the move_base action. More... | |
| ActionClientGetPath | action_client_get_path_ |
| Action client used by the move_base action. More... | |
| ActionClientRecovery | action_client_recovery_ |
| Action client used by the move_base action. More... | |
| 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 | goal_pose_ |
| current goal pose; used to compute remaining distance and angle More... | |
| geometry_msgs::PoseStamped | last_oscillation_pose_ |
| ros::Time | last_oscillation_reset_ |
| std::string | name_ |
| double | oscillation_distance_ |
| minimal move distance to not detect an oscillation More... | |
| ros::Duration | oscillation_timeout_ |
| timeout after a oscillation is detected More... | |
| ros::NodeHandle | private_nh_ |
| std::vector< std::string > | recovery_behaviors_ |
| bool | recovery_enabled_ |
| true, if recovery behavior for the MoveBase action is enabled. More... | |
| mbf_msgs::RecoveryGoal | recovery_goal_ |
| MoveBaseActionState | recovery_trigger_ |
| bool | replanning_ |
| boost::mutex | replanning_mtx_ |
| ros::Rate | replanning_rate_ |
| const mbf_utility::RobotInformation & | robot_info_ |
| current robot state More... | |
| geometry_msgs::PoseStamped | robot_pose_ |
| current robot pose; updated with exe_path action feedback More... | |
Definition at line 59 of file move_base_action.h.
| typedef actionlib::SimpleActionClient<mbf_msgs::ExePathAction> mbf_abstract_nav::MoveBaseAction::ActionClientExePath |
Definition at line 65 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 64 of file move_base_action.h.
| typedef actionlib::SimpleActionClient<mbf_msgs::RecoveryAction> mbf_abstract_nav::MoveBaseAction::ActionClientRecovery |
Definition at line 66 of file move_base_action.h.
| typedef actionlib::ActionServer<mbf_msgs::MoveBaseAction>::GoalHandle mbf_abstract_nav::MoveBaseAction::GoalHandle |
Definition at line 68 of file move_base_action.h.
|
protected |
| Enumerator | |
|---|---|
| NONE | |
| GET_PATH | |
| EXE_PATH | |
| RECOVERY | |
| OSCILLATING | |
| SUCCEEDED | |
| CANCELED | |
| FAILED | |
Definition at line 174 of file move_base_action.h.
| mbf_abstract_nav::MoveBaseAction::MoveBaseAction | ( | const std::string & | name, |
| const mbf_utility::RobotInformation & | robot_info, | ||
| const std::vector< std::string > & | controllers | ||
| ) |
Definition at line 49 of file move_base_action.cpp.
| mbf_abstract_nav::MoveBaseAction::~MoveBaseAction | ( | ) |
Definition at line 67 of file move_base_action.cpp.
|
protected |
Definition at line 181 of file move_base_action.cpp.
|
protected |
Definition at line 350 of file move_base_action.cpp.
|
protected |
Definition at line 186 of file move_base_action.cpp.
|
protected |
Definition at line 244 of file move_base_action.cpp.
|
protected |
Definition at line 547 of file move_base_action.cpp.
|
protected |
Definition at line 467 of file move_base_action.cpp.
|
protected |
Definition at line 435 of file move_base_action.cpp.
| void mbf_abstract_nav::MoveBaseAction::cancel | ( | ) |
Definition at line 102 of file move_base_action.cpp.
|
inlineprotected |
Utility method that fills move base action result with the result of any of the action clients.
| ResultType |
| result | |
| move_base_result |
Definition at line 114 of file move_base_action.h.
| 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.
|
protected |
Action client used by the move_base action.
Definition at line 153 of file move_base_action.h.
|
protected |
Action client used by the move_base action.
Definition at line 156 of file move_base_action.h.
|
protected |
Action client used by the move_base action.
Definition at line 159 of file move_base_action.h.
|
protected |
Definition at line 186 of file move_base_action.h.
|
protected |
Definition at line 172 of file move_base_action.h.
|
protected |
Definition at line 170 of file move_base_action.h.
|
protected |
Definition at line 124 of file move_base_action.h.
|
protected |
Definition at line 125 of file move_base_action.h.
|
protected |
Definition at line 137 of file move_base_action.h.
|
protected |
current goal pose; used to compute remaining distance and angle
Definition at line 148 of file move_base_action.h.
|
protected |
Definition at line 128 of file move_base_action.h.
|
protected |
Definition at line 129 of file move_base_action.h.
|
protected |
Definition at line 139 of file move_base_action.h.
|
protected |
minimal move distance to not detect an oscillation
Definition at line 135 of file move_base_action.h.
|
protected |
timeout after a oscillation is detected
Definition at line 132 of file move_base_action.h.
|
protected |
Definition at line 150 of file move_base_action.h.
|
protected |
Definition at line 168 of file move_base_action.h.
|
protected |
true, if recovery behavior for the MoveBase action is enabled.
Definition at line 166 of file move_base_action.h.
|
protected |
Definition at line 126 of file move_base_action.h.
|
protected |
Definition at line 187 of file move_base_action.h.
|
protected |
Definition at line 161 of file move_base_action.h.
|
protected |
Definition at line 163 of file move_base_action.h.
|
protected |
Definition at line 162 of file move_base_action.h.
|
protected |
current robot state
Definition at line 142 of file move_base_action.h.
|
protected |
current robot pose; updated with exe_path action feedback
Definition at line 145 of file move_base_action.h.