Public Member Functions | Private Member Functions | Private Attributes | List of all members
rsm::StateInterface Class Reference

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::BaseStategetPluginState (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
 

Detailed Description

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.

Constructor & Destructor Documentation

rsm::StateInterface::StateInterface ( )

Constructor

Definition at line 5 of file StateInterface.cpp.

rsm::StateInterface::~StateInterface ( )
virtual

Destructor

Definition at line 39 of file StateInterface.cpp.

Member Function Documentation

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.

Parameters
Pluginstate type
Routineplugin name
Returns
Pointer to plugin state

Definition at line 45 of file StateInterface.cpp.

void rsm::StateInterface::operationModeCallback ( const rsm_msgs::OperationMode::ConstPtr &  operation_mode)
private

Callback to receive the current operation mode and issue interrupts to the current state accordingly

Parameters
operation_modeMode of operation

Definition at line 130 of file StateInterface.cpp.

void rsm::StateInterface::simpleGoalCallback ( const geometry_msgs::PoseStamped::ConstPtr &  goal)
private

Callback receiving goals issued in RViz GUI with the 2D Nav Goal Tool and calling the respective interrupt in the current state

Parameters
goalNavigation goal being set in RViz GUI

Definition at line 152 of file StateInterface.cpp.

bool rsm::StateInterface::startStopExplorationService ( std_srvs::SetBool::Request &  req,
std_srvs::SetBool::Response &  res 
)
private

Definition at line 167 of file StateInterface.cpp.

bool rsm::StateInterface::startStopWaypointFollowingService ( std_srvs::SetBool::Request &  req,
std_srvs::SetBool::Response &  res 
)
private

Definition at line 186 of file StateInterface.cpp.

bool rsm::StateInterface::stateInfoService ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
private

Definition at line 213 of file StateInterface.cpp.

bool rsm::StateInterface::stop2dNavGoal ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
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.

Parameters
nextState

Definition at line 116 of file StateInterface.cpp.

Member Data Documentation

std::string rsm::StateInterface::_calculate_goal_plugin
private

Calculate goal state plugin name for plugin loader.

Definition at line 90 of file StateInterface.h.

boost::shared_ptr<rsm::BaseState> rsm::StateInterface::_current_state
private

Currently active state.

Definition at line 77 of file StateInterface.h.

std::string rsm::StateInterface::_mapping_plugin
private

Mapping state plugin name for plugin loader.

Definition at line 98 of file StateInterface.h.

std::string rsm::StateInterface::_navigation_plugin
private

Navigation state plugin name for plugin loader.

Definition at line 94 of file StateInterface.h.

boost::shared_ptr<rsm::BaseState> rsm::StateInterface::_next_state
private

Upcoming state.

Definition at line 81 of file StateInterface.h.

ros::NodeHandle rsm::StateInterface::_nh
private

Definition at line 64 of file StateInterface.h.

bool rsm::StateInterface::_on_interrupt
private

Interrupt happened before

Definition at line 85 of file StateInterface.h.

ros::Subscriber rsm::StateInterface::_operation_mode_sub
private

Definition at line 65 of file StateInterface.h.

pluginlib::ClassLoader<rsm::BaseState> rsm::StateInterface::_plugin_loader
private

Plugin loader for state plugins.

Definition at line 102 of file StateInterface.h.

ros::ServiceClient rsm::StateInterface::_set_navigation_goal_client
private

Definition at line 70 of file StateInterface.h.

ros::Subscriber rsm::StateInterface::_simple_goal_sub
private

Definition at line 66 of file StateInterface.h.

ros::ServiceServer rsm::StateInterface::_start_stop_exploration_service
private

Definition at line 67 of file StateInterface.h.

ros::ServiceServer rsm::StateInterface::_start_stop_waypoint_following_service
private

Definition at line 68 of file StateInterface.h.

ros::Publisher rsm::StateInterface::_state_info_publisher
private

Definition at line 72 of file StateInterface.h.

ros::ServiceServer rsm::StateInterface::_state_info_service
private

Definition at line 71 of file StateInterface.h.

ros::ServiceServer rsm::StateInterface::_stop_2d_nav_goal_service
private

Definition at line 69 of file StateInterface.h.


The documentation for this class was generated from the following files:


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