NavigationState.h
Go to the documentation of this file.
1 #ifndef NAVIGATIONSTATE_H
2 #define NAVIGATIONSTATE_H
3 
5 #include <rsm_core/BaseState.h>
6 #include <rsm_core/IdleState.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>
17 #include <tf/transform_datatypes.h>
18 #include <std_msgs/Bool.h>
19 
20 #define POSE_TOLERANCE 0.05
21 
22 namespace rsm {
23 
30 class NavigationState: public BaseState {
31 
32 public:
33 
38 
43 
47  void onSetup();
48 
52  void onEntry();
53 
57  void onActive();
58 
62  void onExit();
63 
67  void onExplorationStart(bool &success, std::string &message);
68 
72  void onExplorationStop(bool &success, std::string &message);
73 
77  void onWaypointFollowingStart(bool &success, std::string &message);
78 
82  void onWaypointFollowingStop(bool &success, std::string &message);
83 
88  void onInterrupt(int interrupt);
89 
90 private:
91 
94 
104 
108  geometry_msgs::Pose _nav_goal;
120  std::string _routine;
145 
150  void timerCallback(const ros::TimerEvent& event);
156  void goalObsoleteCallback(const std_msgs::Bool::ConstPtr& msg);
162  void reverseModeCallback(const std_msgs::Bool::ConstPtr& reverse_mode);
168  const rsm_msgs::OperationMode::ConstPtr& operation_mode);
172  void abortNavigation();
176  void comparePose();
177 };
178 
179 }
180 
181 #endif
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)
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
ros::NodeHandle _nh
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


rsm_additions
Author(s): Marco Steinbrink
autogenerated on Tue Mar 16 2021 02:44:35