WaypointFollowingState.h
Go to the documentation of this file.
1 #ifndef WAYPOINTFOLLOWINGSTATE_H
2 #define WAYPOINTFOLLOWINGSTATE_H
3 
4 #include <rsm_msgs/WaypointArray.h>
5 #include <rsm_msgs/GetWaypoints.h>
6 #include <rsm_msgs/SetWaypointFollowingMode.h>
7 #include <rsm_msgs/WaypointVisited.h>
8 #include <std_srvs/Trigger.h>
9 #include <rsm_msgs/SetNavigationGoal.h>
10 #include <rsm_core/BaseState.h>
12 #include <rsm_core/IdleState.h>
15 
16 namespace rsm {
17 
23 
24 public:
25 
30 
35 
39  void onSetup();
40 
44  void onEntry();
45 
49  void onActive();
50 
54  void onExit();
55 
59  void onExplorationStart(bool &success, std::string &message);
60 
64  void onExplorationStop(bool &success, std::string &message);
65 
69  void onWaypointFollowingStart(bool &success, std::string &message);
70 
74  void onWaypointFollowingStop(bool &success, std::string &message);
75 
80  void onInterrupt(int interrupt);
81 
82 private:
88 
92  rsm_msgs::WaypointArray _waypoint_array;
97 
101  void resetWaypoints();
105  void abortWaypointFollowing();
109  void getWaypoints();
111 };
112 
113 }
114 
115 #endif
ros::ServiceClient _set_waypoint_following_mode_service
void onInterrupt(int interrupt)
Called when an operation mode interrupt was received.
void onWaypointFollowingStart(bool &success, std::string &message)
void onExplorationStop(bool &success, std::string &message)
ros::ServiceClient _waypoint_visited_service
rsm_msgs::WaypointArray _waypoint_array
void onExplorationStart(bool &success, std::string &message)
Definition: BaseState.h:8
ros::ServiceClient _reset_waypoints_service
State to decide which waypoint will be the next navigation goal while in waypoint following mode...
ros::ServiceClient _get_waypoints_service
void onWaypointFollowingStop(bool &success, std::string &message)
ros::ServiceClient _set_navigation_goal_service


rsm_core
Author(s): Marco Steinbrink
autogenerated on Tue Mar 16 2021 02:44:31