Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
mbf_abstract_nav::MoveBaseAction Class Reference

#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 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)
 
bool replanningActive () const
 
void replanningThread ()
 

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_
 
double dist_to_goal_
 current distance to goal (we will stop replanning if very close to avoid destabilizing the controller) More...
 
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_
 
ros::Duration replanning_period_
 Replanning period dynamically reconfigurable. More...
 
boost::thread replanning_thread_
 Replanning thread, running permanently. More...
 
const mbf_utility::RobotInformationrobot_info_
 current robot state More...
 
geometry_msgs::PoseStamped robot_pose_
 current robot pose; updated with exe_path action feedback More...
 

Detailed Description

Definition at line 59 of file move_base_action.h.

Member Typedef Documentation

◆ ActionClientExePath

Definition at line 65 of file move_base_action.h.

◆ ActionClientGetPath

Action clients for the MoveBase action.

Definition at line 64 of file move_base_action.h.

◆ ActionClientRecovery

Definition at line 66 of file move_base_action.h.

◆ GoalHandle

Definition at line 68 of file move_base_action.h.

Member Enumeration Documentation

◆ MoveBaseActionState

Enumerator
NONE 
GET_PATH 
EXE_PATH 
RECOVERY 
OSCILLATING 
SUCCEEDED 
CANCELED 
FAILED 

Definition at line 179 of file move_base_action.h.

Constructor & Destructor Documentation

◆ MoveBaseAction()

mbf_abstract_nav::MoveBaseAction::MoveBaseAction ( const std::string &  name,
const mbf_utility::RobotInformation robot_info,
const std::vector< std::string > &  controllers 
)

Definition at line 50 of file move_base_action.cpp.

◆ ~MoveBaseAction()

mbf_abstract_nav::MoveBaseAction::~MoveBaseAction ( )

Definition at line 69 of file move_base_action.cpp.

Member Function Documentation

◆ actionExePathActive()

void mbf_abstract_nav::MoveBaseAction::actionExePathActive ( )
protected

Definition at line 168 of file move_base_action.cpp.

◆ actionExePathDone()

void mbf_abstract_nav::MoveBaseAction::actionExePathDone ( const actionlib::SimpleClientGoalState state,
const mbf_msgs::ExePathResultConstPtr &  result 
)
protected

Definition at line 319 of file move_base_action.cpp.

◆ actionExePathFeedback()

void mbf_abstract_nav::MoveBaseAction::actionExePathFeedback ( const mbf_msgs::ExePathFeedbackConstPtr &  feedback)
protected

Definition at line 173 of file move_base_action.cpp.

◆ actionGetPathDone()

void mbf_abstract_nav::MoveBaseAction::actionGetPathDone ( const actionlib::SimpleClientGoalState state,
const mbf_msgs::GetPathResultConstPtr &  result 
)
protected

Definition at line 232 of file move_base_action.cpp.

◆ actionRecoveryDone()

void mbf_abstract_nav::MoveBaseAction::actionRecoveryDone ( const actionlib::SimpleClientGoalState state,
const mbf_msgs::RecoveryResultConstPtr &  result 
)
protected

Definition at line 436 of file move_base_action.cpp.

◆ attemptRecovery()

bool mbf_abstract_nav::MoveBaseAction::attemptRecovery ( )
protected

Definition at line 404 of file move_base_action.cpp.

◆ cancel()

void mbf_abstract_nav::MoveBaseAction::cancel ( )

Definition at line 87 of file move_base_action.cpp.

◆ fillMoveBaseResult()

template<typename ResultType >
void mbf_abstract_nav::MoveBaseAction::fillMoveBaseResult ( const ResultType &  result,
mbf_msgs::MoveBaseResult &  move_base_result 
)
inlineprotected

Utility method that fills move base action result with the result of any of the action clients.

Template Parameters
ResultType
Parameters
result
move_base_result

Definition at line 114 of file move_base_action.h.

◆ reconfigure()

void mbf_abstract_nav::MoveBaseAction::reconfigure ( mbf_abstract_nav::MoveBaseFlexConfig &  config,
uint32_t  level 
)

Definition at line 75 of file move_base_action.cpp.

◆ replanningActive()

bool mbf_abstract_nav::MoveBaseAction::replanningActive ( ) const
protected

Definition at line 516 of file move_base_action.cpp.

◆ replanningThread()

void mbf_abstract_nav::MoveBaseAction::replanningThread ( )
protected

Definition at line 522 of file move_base_action.cpp.

◆ start()

void mbf_abstract_nav::MoveBaseAction::start ( GoalHandle goal_handle)

Definition at line 107 of file move_base_action.cpp.

Member Data Documentation

◆ action_client_exe_path_

ActionClientExePath mbf_abstract_nav::MoveBaseAction::action_client_exe_path_
protected

Action client used by the move_base action.

Definition at line 153 of file move_base_action.h.

◆ action_client_get_path_

ActionClientGetPath mbf_abstract_nav::MoveBaseAction::action_client_get_path_
protected

Action client used by the move_base action.

Definition at line 156 of file move_base_action.h.

◆ action_client_recovery_

ActionClientRecovery mbf_abstract_nav::MoveBaseAction::action_client_recovery_
protected

Action client used by the move_base action.

Definition at line 159 of file move_base_action.h.

◆ action_state_

MoveBaseActionState mbf_abstract_nav::MoveBaseAction::action_state_
protected

Definition at line 191 of file move_base_action.h.

◆ behaviors_

const std::vector<std::string>& mbf_abstract_nav::MoveBaseAction::behaviors_
protected

Definition at line 177 of file move_base_action.h.

◆ current_recovery_behavior_

std::vector<std::string>::iterator mbf_abstract_nav::MoveBaseAction::current_recovery_behavior_
protected

Definition at line 175 of file move_base_action.h.

◆ dist_to_goal_

double mbf_abstract_nav::MoveBaseAction::dist_to_goal_
protected

current distance to goal (we will stop replanning if very close to avoid destabilizing the controller)

Definition at line 162 of file move_base_action.h.

◆ exe_path_goal_

mbf_msgs::ExePathGoal mbf_abstract_nav::MoveBaseAction::exe_path_goal_
protected

Definition at line 124 of file move_base_action.h.

◆ get_path_goal_

mbf_msgs::GetPathGoal mbf_abstract_nav::MoveBaseAction::get_path_goal_
protected

Definition at line 125 of file move_base_action.h.

◆ goal_handle_

GoalHandle mbf_abstract_nav::MoveBaseAction::goal_handle_
protected

Definition at line 137 of file move_base_action.h.

◆ goal_pose_

geometry_msgs::PoseStamped mbf_abstract_nav::MoveBaseAction::goal_pose_
protected

current goal pose; used to compute remaining distance and angle

Definition at line 148 of file move_base_action.h.

◆ last_oscillation_pose_

geometry_msgs::PoseStamped mbf_abstract_nav::MoveBaseAction::last_oscillation_pose_
protected

Definition at line 128 of file move_base_action.h.

◆ last_oscillation_reset_

ros::Time mbf_abstract_nav::MoveBaseAction::last_oscillation_reset_
protected

Definition at line 129 of file move_base_action.h.

◆ name_

std::string mbf_abstract_nav::MoveBaseAction::name_
protected

Definition at line 139 of file move_base_action.h.

◆ oscillation_distance_

double mbf_abstract_nav::MoveBaseAction::oscillation_distance_
protected

minimal move distance to not detect an oscillation

Definition at line 135 of file move_base_action.h.

◆ oscillation_timeout_

ros::Duration mbf_abstract_nav::MoveBaseAction::oscillation_timeout_
protected

timeout after a oscillation is detected

Definition at line 132 of file move_base_action.h.

◆ private_nh_

ros::NodeHandle mbf_abstract_nav::MoveBaseAction::private_nh_
protected

Definition at line 150 of file move_base_action.h.

◆ recovery_behaviors_

std::vector<std::string> mbf_abstract_nav::MoveBaseAction::recovery_behaviors_
protected

Definition at line 173 of file move_base_action.h.

◆ recovery_enabled_

bool mbf_abstract_nav::MoveBaseAction::recovery_enabled_
protected

true, if recovery behavior for the MoveBase action is enabled.

Definition at line 171 of file move_base_action.h.

◆ recovery_goal_

mbf_msgs::RecoveryGoal mbf_abstract_nav::MoveBaseAction::recovery_goal_
protected

Definition at line 126 of file move_base_action.h.

◆ recovery_trigger_

MoveBaseActionState mbf_abstract_nav::MoveBaseAction::recovery_trigger_
protected

Definition at line 192 of file move_base_action.h.

◆ replanning_period_

ros::Duration mbf_abstract_nav::MoveBaseAction::replanning_period_
protected

Replanning period dynamically reconfigurable.

Definition at line 165 of file move_base_action.h.

◆ replanning_thread_

boost::thread mbf_abstract_nav::MoveBaseAction::replanning_thread_
protected

Replanning thread, running permanently.

Definition at line 168 of file move_base_action.h.

◆ robot_info_

const mbf_utility::RobotInformation& mbf_abstract_nav::MoveBaseAction::robot_info_
protected

current robot state

Definition at line 142 of file move_base_action.h.

◆ robot_pose_

geometry_msgs::PoseStamped mbf_abstract_nav::MoveBaseAction::robot_pose_
protected

current robot pose; updated with exe_path action feedback

Definition at line 145 of file move_base_action.h.


The documentation for this class was generated from the following files:


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:48