Class MoveBaseAction

Class Documentation

class MoveBaseAction

Public Types

typedef std::shared_ptr<MoveBaseAction> Ptr
typedef mbf_msgs::action::GetPath GetPath

Action clients for the MoveBase action.

typedef mbf_msgs::action::ExePath ExePath
typedef mbf_msgs::action::Recovery Recovery
typedef rclcpp_action::ServerGoalHandle<mbf_msgs::action::MoveBase> GoalHandle

Public Functions

MoveBaseAction(const rclcpp::Node::SharedPtr &node, const std::string &name, const mbf_utility::RobotInformation::ConstPtr &robot_info, const std::vector<std::string> &controllers)
~MoveBaseAction()
void start(std::shared_ptr<GoalHandle> goal_handle)
void cancel()
rcl_interfaces::msg::SetParametersResult reconfigure(const std::vector<rclcpp::Parameter> &parameters)

Protected Types

enum MoveBaseActionState

Values:

enumerator NONE
enumerator GET_PATH
enumerator EXE_PATH
enumerator RECOVERY
enumerator OSCILLATING
enumerator SUCCEEDED
enumerator CANCELED
enumerator FAILED

Protected Functions

void actionGetPathGoalResponse(const rclcpp_action::ClientGoalHandle<GetPath>::ConstSharedPtr &get_path_goal_handle)
void actionGetPathResult(const rclcpp_action::ClientGoalHandle<GetPath>::WrappedResult &result)
void actionExePathGoalResponse(const rclcpp_action::ClientGoalHandle<ExePath>::ConstSharedPtr &exe_path_goal_handle)
void actionExePathFeedback(const rclcpp_action::ClientGoalHandle<ExePath>::ConstSharedPtr &goal_handle, const ExePath::Feedback::ConstSharedPtr &feedback)
void actionExePathResult(const rclcpp_action::ClientGoalHandle<ExePath>::WrappedResult &result)
void actionRecoveryGoalResponse(const rclcpp_action::ClientGoalHandle<Recovery>::ConstSharedPtr &recovery_goal_handle)
void actionRecoveryResult(const rclcpp_action::ClientGoalHandle<Recovery>::WrappedResult &result)
void recoveryRejectedOrAborted(const rclcpp_action::ClientGoalHandle<Recovery>::WrappedResult &result)
bool checkAndHandleMoveBaseActionCanceled()

Checks whether the move base client requested canceling of action. If so, returns true and handles goal state transition. Otherwise, returns false. Regularly call this function before doing further work (e.g. before calling the next exepath action), so canceling remains responsive.

bool attemptRecovery()
bool replanningActive() const
void replanningThread()
template<typename ResultType>
inline void fillMoveBaseResult(const ResultType &result, mbf_msgs::action::MoveBase::Result &move_base_result)

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

Protected Attributes

ExePath::Goal exe_path_goal_
rclcpp_action::Client<ExePath>::SendGoalOptions exe_path_send_goal_options_
GetPath::Goal get_path_goal_
std::shared_future<rclcpp_action::ClientGoalHandle<GetPath>::SharedPtr> get_path_goal_handle_
rclcpp_action::Client<GetPath>::SendGoalOptions get_path_send_goal_options_
Recovery::Goal recovery_goal_
rclcpp_action::Client<Recovery>::SendGoalOptions recovery_send_goal_options_
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
geometry_msgs::msg::PoseStamped last_oscillation_pose_
rclcpp::Time last_oscillation_reset_
rclcpp::Duration oscillation_timeout_

timeout after a oscillation is detected

double oscillation_distance_

minimal move distance to not detect an oscillation

std::shared_ptr<GoalHandle> goal_handle_

handle of the active MoveBase action goal, if one exists

std::string name_
mbf_utility::RobotInformation::ConstPtr robot_info_

current robot state

geometry_msgs::msg::PoseStamped robot_pose_

current robot pose; updated with exe_path action feedback

geometry_msgs::msg::PoseStamped goal_pose_

current goal pose; used to compute remaining distance and angle

rclcpp::Node::SharedPtr node_
rclcpp_action::Client<ExePath>::SharedPtr action_client_exe_path_

Action client used by the move_base action.

rclcpp_action::Client<GetPath>::SharedPtr action_client_get_path_

Action client used by the move_base action.

rclcpp_action::Client<Recovery>::SharedPtr action_client_recovery_

Action client used by the move_base action.

double dist_to_goal_

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

rclcpp::Duration replanning_period_

Replanning period dynamically reconfigurable.

std::thread replanning_thread_

Replanning thread, running permanently.

bool replanning_thread_shutdown_
bool recovery_enabled_

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

std::vector<std::string> actions_recovery_behaviors_

Gets set when a move base actions starts. These are the recovery behaviors that will be used by the move base action.

std::vector<std::string>::iterator current_recovery_behavior_

Points to an element in actions_recovery_behaviors_. This is the current recovery behavior, we might try different behaviors for recovery one after another.

std::vector<std::string> available_recovery_behaviors_

All available recovery behaviors. Gets set in the constructor, will be used as default actions_recovery_behaviors_ if none are specified in the action goal.

MoveBaseActionState action_state_
MoveBaseActionState recovery_trigger_