Go to the documentation of this file.
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>
53 #include "mbf_abstract_nav/MoveBaseFlexConfig.h"
72 const std::vector<std::string> &controllers);
81 mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level);
89 const mbf_msgs::GetPathResultConstPtr &result);
95 const mbf_msgs::ExePathResultConstPtr &result);
99 const mbf_msgs::RecoveryResultConstPtr &result);
113 template <
typename ResultType>
117 move_base_result.outcome = result.outcome;
118 move_base_result.message = result.message;
197 #endif //MBF_ABSTRACT_NAV__MOVE_BASE_ACTION_H_
double oscillation_distance_
minimal move distance to not detect an oscillation
void start(GoalHandle &goal_handle)
mbf_msgs::GetPathGoal get_path_goal_
MoveBaseAction(const std::string &name, const mbf_utility::RobotInformation &robot_info, const std::vector< std::string > &controllers)
double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
actionlib::SimpleActionClient< mbf_msgs::GetPathAction > ActionClientGetPath
Action clients for the MoveBase action.
mbf_msgs::RecoveryGoal recovery_goal_
void actionExePathActive()
ros::Time last_oscillation_reset_
bool replanningActive() const
void actionRecoveryDone(const actionlib::SimpleClientGoalState &state, const mbf_msgs::RecoveryResultConstPtr &result)
actionlib::ActionServer< mbf_msgs::MoveBaseAction >::GoalHandle GoalHandle
void actionExePathFeedback(const mbf_msgs::ExePathFeedbackConstPtr &feedback)
geometry_msgs::PoseStamped robot_pose_
current robot pose; updated with exe_path action feedback
std::vector< std::string >::iterator current_recovery_behavior_
mbf_msgs::ExePathGoal exe_path_goal_
actionlib::SimpleActionClient< mbf_msgs::RecoveryAction > ActionClientRecovery
const std::vector< std::string > & behaviors_
ActionClientRecovery action_client_recovery_
Action client used by the move_base action.
void actionGetPathDone(const actionlib::SimpleClientGoalState &state, const mbf_msgs::GetPathResultConstPtr &result)
MoveBaseActionState action_state_
double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
geometry_msgs::PoseStamped last_oscillation_pose_
ros::Duration replanning_period_
Replanning period dynamically reconfigurable.
ActionClientExePath action_client_exe_path_
Action client used by the move_base action.
const mbf_utility::RobotInformation & robot_info_
current robot state
void actionExePathDone(const actionlib::SimpleClientGoalState &state, const mbf_msgs::ExePathResultConstPtr &result)
void fillMoveBaseResult(const ResultType &result, mbf_msgs::MoveBaseResult &move_base_result)
geometry_msgs::PoseStamped goal_pose_
current goal pose; used to compute remaining distance and angle
ros::NodeHandle private_nh_
bool recovery_enabled_
true, if recovery behavior for the MoveBase action is enabled.
double dist_to_goal_
current distance to goal (we will stop replanning if very close to avoid destabilizing the controller...
void reconfigure(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
boost::thread replanning_thread_
Replanning thread, running permanently.
MoveBaseActionState recovery_trigger_
std::vector< std::string > recovery_behaviors_
ActionClientGetPath action_client_get_path_
Action client used by the move_base action.
ros::Duration oscillation_timeout_
timeout after a oscillation is detected
actionlib::SimpleActionClient< mbf_msgs::ExePathAction > ActionClientExePath
mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:47