StateInterface.h
Go to the documentation of this file.
1 #ifndef StateInterface_H_
2 #define StateInterface_H_
3 
4 #include <rsm_msgs/OperationMode.h>
5 #include <rsm_msgs/SetNavigationGoal.h>
6 #include <geometry_msgs/Twist.h>
7 #include <geometry_msgs/Pose.h>
8 #include <geometry_msgs/PoseStamped.h>
9 #include <std_msgs/String.h>
10 #include <std_srvs/SetBool.h>
11 #include <std_srvs/Trigger.h>
12 #include <pluginlib/class_loader.h>
13 #include <rsm_core/BaseState.h>
14 #include <rsm_core/IdleState.h>
15 
16 namespace rsm {
17 
18 #define CALCULATEGOAL_STATE 1
19 #define NAVIGATION_STATE 2
20 #define MAPPING_STATE 3
21 #define ROUTINE_STATE 4
22 
29 
30 public:
31 
36 
40  virtual ~StateInterface();
41 
49  std::string routine = "");
50 
54  void awake();
55 
62 
63 private:
73 
86 
94  std::string _navigation_plugin;
98  std::string _mapping_plugin;
103 
109  const rsm_msgs::OperationMode::ConstPtr& operation_mode);
115  void simpleGoalCallback(const geometry_msgs::PoseStamped::ConstPtr& goal);
116  bool startStopExplorationService(std_srvs::SetBool::Request &req,
117  std_srvs::SetBool::Response &res);
118  bool startStopWaypointFollowingService(std_srvs::SetBool::Request &req,
119  std_srvs::SetBool::Response &res);
120  bool stop2dNavGoal(std_srvs::Trigger::Request &req,
121  std_srvs::Trigger::Response &res);
122  bool stateInfoService(std_srvs::Trigger::Request &req,
123  std_srvs::Trigger::Response &res);
124 
125 };
126 
127 }
128 
129 #endif
ros::ServiceServer _start_stop_waypoint_following_service
ros::Publisher _state_info_publisher
bool stop2dNavGoal(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
boost::shared_ptr< rsm::BaseState > getPluginState(int plugin_type, std::string routine="")
Returns a plugin-state corresponding to the given type.
std::string _navigation_plugin
Navigation state plugin name for plugin loader.
ros::ServiceServer _start_stop_exploration_service
void transitionToVolatileState(boost::shared_ptr< rsm::BaseState > next_state)
pluginlib::ClassLoader< rsm::BaseState > _plugin_loader
Plugin loader for state plugins.
bool startStopWaypointFollowingService(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res)
bool stateInfoService(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ros::ServiceServer _state_info_service
Definition: BaseState.h:8
ros::Subscriber _simple_goal_sub
bool startStopExplorationService(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res)
ros::Subscriber _operation_mode_sub
ros::NodeHandle _nh
ros::ServiceClient _set_navigation_goal_client
std::string _mapping_plugin
Mapping state plugin name for plugin loader.
boost::shared_ptr< rsm::BaseState > _next_state
Upcoming state.
void simpleGoalCallback(const geometry_msgs::PoseStamped::ConstPtr &goal)
void operationModeCallback(const rsm_msgs::OperationMode::ConstPtr &operation_mode)
Handles the RSM transitions between the different state classes and holds a reference to the current ...
boost::shared_ptr< rsm::BaseState > _current_state
Currently active state.
std::string _calculate_goal_plugin
Calculate goal state plugin name for plugin loader.
ros::ServiceServer _stop_2d_nav_goal_service


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