IdleState.cpp
Go to the documentation of this file.
1 #include <rsm_core/IdleState.h>
2 
3 namespace rsm {
4 
6 }
7 
9 }
10 
12  _name = "Idle";
13 }
14 
16 }
17 
19 }
20 
22 }
23 
24 void IdleState::onExplorationStart(bool &success, std::string &message) {
25  success = true;
26  message = "Exploration started";
27  if (!_interrupt_occured) {
30  }
31 }
32 
33 void IdleState::onExplorationStop(bool &success, std::string &message) {
34  success = false;
35  message = "Exploration not running";
36 }
37 
38 void IdleState::onWaypointFollowingStart(bool &success, std::string &message) {
39  success = true;
40  message = "Waypoint following started";
42  boost::make_shared<WaypointFollowingState>());
43 }
44 
45 void IdleState::onWaypointFollowingStop(bool &success, std::string &message) {
46  success = false;
47  message = "Waypoint following not running";
48 }
49 
50 void IdleState::onInterrupt(int interrupt) {
51  switch (interrupt) {
54  boost::make_shared<EmergencyStopState>());
55  _interrupt_occured = true;
56  break;
59  boost::make_shared<TeleoperationState>());
60  _interrupt_occured = true;
61  break;
65  _interrupt_occured = true;
66  break;
67  }
68 }
69 
70 }
void onSetup()
Definition: IdleState.cpp:11
void onInterrupt(int interrupt)
Called when an operation mode interrupt was received.
Definition: IdleState.cpp:50
boost::shared_ptr< rsm::BaseState > getPluginState(int plugin_type, std::string routine="")
Returns a plugin-state corresponding to the given type.
#define NAVIGATION_STATE
void onActive()
Definition: IdleState.cpp:18
void transitionToVolatileState(boost::shared_ptr< rsm::BaseState > next_state)
void onExplorationStart(bool &success, std::string &message)
Definition: IdleState.cpp:24
bool _interrupt_occured
Shows if an interupt occured.
Definition: BaseState.h:129
void onExplorationStop(bool &success, std::string &message)
Definition: IdleState.cpp:33
#define TELEOPERATION_INTERRUPT
Definition: BaseState.h:12
void onEntry()
Definition: IdleState.cpp:15
Definition: BaseState.h:8
#define CALCULATEGOAL_STATE
std::string _name
Name of the state.
Definition: BaseState.h:133
StateInterface * _stateinterface
Pointer to State Interface handling all state transitions.
Definition: BaseState.h:125
#define EMERGENCY_STOP_INTERRUPT
Definition: BaseState.h:11
void onWaypointFollowingStop(bool &success, std::string &message)
Definition: IdleState.cpp:45
#define SIMPLE_GOAL_INTERRUPT
Definition: BaseState.h:13
void onWaypointFollowingStart(bool &success, std::string &message)
Definition: IdleState.cpp:38


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