1 #ifndef NAVIGATIONSTATE_H 2 #define NAVIGATIONSTATE_H 9 #include <geometry_msgs/PoseArray.h> 10 #include <move_base_msgs/MoveBaseAction.h> 12 #include <rsm_msgs/GetNavigationGoal.h> 13 #include <rsm_msgs/GetRobotPose.h> 14 #include <rsm_msgs/OperationMode.h> 15 #include <rsm_msgs/GoalCompleted.h> 16 #include <std_srvs/Trigger.h> 18 #include <std_msgs/Bool.h> 20 #define POSE_TOLERANCE 0.05 168 const rsm_msgs::OperationMode::ConstPtr& operation_mode);
void onWaypointFollowingStart(bool &success, std::string &message)
void goalObsoleteCallback(const std_msgs::Bool::ConstPtr &msg)
ros::Subscriber _get_goal_obsolete_subscriber
void onExplorationStart(bool &success, std::string &message)
int _navigation_completed_status
ros::ServiceClient _get_reverse_mode_service
ros::ServiceClient _get_navigation_goal_service
State being active when the robot should move to a previously set goal. First obtains the goal and th...
void onWaypointFollowingStop(bool &success, std::string &message)
geometry_msgs::Pose _nav_goal
void onInterrupt(int interrupt)
Called when an operation mode interrupt was received.
ros::ServiceClient _get_robot_pose_service
void onExplorationStop(bool &success, std::string &message)
void timerCallback(const ros::TimerEvent &event)
Callback for idle timer.
ros::ServiceClient _get_exploration_mode_service
void operationModeCallback(const rsm_msgs::OperationMode::ConstPtr &operation_mode)
ros::ServiceClient _navigation_goal_completed_service
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > MoveBaseClient
void reverseModeCallback(const std_msgs::Bool::ConstPtr &reverse_mode)
boost::shared_ptr< MoveBaseClient > _move_base_client
ros::Subscriber _reverse_mode_subscriber