1 #ifndef StateInterface_H_ 2 #define StateInterface_H_ 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> 18 #define CALCULATEGOAL_STATE 1 19 #define NAVIGATION_STATE 2 20 #define MAPPING_STATE 3 21 #define ROUTINE_STATE 4 49 std::string routine =
"");
109 const rsm_msgs::OperationMode::ConstPtr& operation_mode);
117 std_srvs::SetBool::Response &res);
119 std_srvs::SetBool::Response &res);
121 std_srvs::Trigger::Response &res);
123 std_srvs::Trigger::Response &res);
ros::ServiceServer _start_stop_waypoint_following_service
ros::Publisher _state_info_publisher
bool stop2dNavGoal(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
virtual ~StateInterface()
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
ros::Subscriber _simple_goal_sub
bool startStopExplorationService(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res)
ros::Subscriber _operation_mode_sub
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