Handles the RSM transitions between the different state classes and holds a reference to the current and the upcoming state class. More...
#include <StateInterface.h>
Public Member Functions | |
void | awake () |
boost::shared_ptr< rsm::BaseState > | getPluginState (int plugin_type, std::string routine="") |
Returns a plugin-state corresponding to the given type. More... | |
StateInterface () | |
void | transitionToVolatileState (boost::shared_ptr< rsm::BaseState > next_state) |
virtual | ~StateInterface () |
Private Member Functions | |
void | operationModeCallback (const rsm_msgs::OperationMode::ConstPtr &operation_mode) |
void | simpleGoalCallback (const geometry_msgs::PoseStamped::ConstPtr &goal) |
bool | startStopExplorationService (std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res) |
bool | startStopWaypointFollowingService (std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res) |
bool | stateInfoService (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) |
bool | stop2dNavGoal (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) |
Private Attributes | |
std::string | _calculate_goal_plugin |
Calculate goal state plugin name for plugin loader. More... | |
boost::shared_ptr< rsm::BaseState > | _current_state |
Currently active state. More... | |
std::string | _mapping_plugin |
Mapping state plugin name for plugin loader. More... | |
std::string | _navigation_plugin |
Navigation state plugin name for plugin loader. More... | |
boost::shared_ptr< rsm::BaseState > | _next_state |
Upcoming state. More... | |
ros::NodeHandle | _nh |
bool | _on_interrupt |
ros::Subscriber | _operation_mode_sub |
pluginlib::ClassLoader< rsm::BaseState > | _plugin_loader |
Plugin loader for state plugins. More... | |
ros::ServiceClient | _set_navigation_goal_client |
ros::Subscriber | _simple_goal_sub |
ros::ServiceServer | _start_stop_exploration_service |
ros::ServiceServer | _start_stop_waypoint_following_service |
ros::Publisher | _state_info_publisher |
ros::ServiceServer | _state_info_service |
ros::ServiceServer | _stop_2d_nav_goal_service |
Handles the RSM transitions between the different state classes and holds a reference to the current and the upcoming state class.
Definition at line 28 of file StateInterface.h.
rsm::StateInterface::StateInterface | ( | ) |
Constructor
Definition at line 5 of file StateInterface.cpp.
|
virtual |
Destructor
Definition at line 39 of file StateInterface.cpp.
void rsm::StateInterface::awake | ( | ) |
Awake StateInterface to do his job
Definition at line 86 of file StateInterface.cpp.
boost::shared_ptr< rsm::BaseState > rsm::StateInterface::getPluginState | ( | int | plugin_type, |
std::string | routine = "" |
||
) |
Returns a plugin-state corresponding to the given type.
Plugin | state type |
Routine | plugin name |
Definition at line 45 of file StateInterface.cpp.
|
private |
Callback to receive the current operation mode and issue interrupts to the current state accordingly
operation_mode | Mode of operation |
Definition at line 130 of file StateInterface.cpp.
|
private |
Callback receiving goals issued in RViz GUI with the 2D Nav Goal Tool and calling the respective interrupt in the current state
goal | Navigation goal being set in RViz GUI |
Definition at line 152 of file StateInterface.cpp.
|
private |
Definition at line 167 of file StateInterface.cpp.
|
private |
Definition at line 186 of file StateInterface.cpp.
|
private |
Definition at line 213 of file StateInterface.cpp.
|
private |
Definition at line 205 of file StateInterface.cpp.
void rsm::StateInterface::transitionToVolatileState | ( | boost::shared_ptr< rsm::BaseState > | next_state | ) |
Activate new state instance. Instance is deleted with next transition.
nextState |
Definition at line 116 of file StateInterface.cpp.
|
private |
Calculate goal state plugin name for plugin loader.
Definition at line 90 of file StateInterface.h.
|
private |
Currently active state.
Definition at line 77 of file StateInterface.h.
|
private |
Mapping state plugin name for plugin loader.
Definition at line 98 of file StateInterface.h.
|
private |
Navigation state plugin name for plugin loader.
Definition at line 94 of file StateInterface.h.
|
private |
Upcoming state.
Definition at line 81 of file StateInterface.h.
|
private |
Definition at line 64 of file StateInterface.h.
|
private |
Interrupt happened before
Definition at line 85 of file StateInterface.h.
|
private |
Definition at line 65 of file StateInterface.h.
|
private |
Plugin loader for state plugins.
Definition at line 102 of file StateInterface.h.
|
private |
Definition at line 70 of file StateInterface.h.
|
private |
Definition at line 66 of file StateInterface.h.
|
private |
Definition at line 67 of file StateInterface.h.
|
private |
Definition at line 68 of file StateInterface.h.
|
private |
Definition at line 72 of file StateInterface.h.
|
private |
Definition at line 71 of file StateInterface.h.
|
private |
Definition at line 69 of file StateInterface.h.