MappingDummyState.cpp
Go to the documentation of this file.
2 
3 namespace rsm {
4 
6 }
7 
9 }
10 
12  ros::NodeHandle nh("rsm");
14  rsm_msgs::GoalCompleted>("navigationGoalCompleted");
15  _name = "E: Mapping Dummy";
16  _navigation_completed_status = rsm_msgs::GoalStatus::ABORTED;
17 }
18 
20 }
21 
23  //do mapping stuff
24  if (!_interrupt_occured) {
25  _navigation_completed_status = rsm_msgs::GoalStatus::REACHED;
28  }
29 }
30 
32  rsm_msgs::GoalCompleted srv;
33  srv.request.status.goal_status = _navigation_completed_status;
35  ROS_ERROR("Failed to call Complete Navigation Goal service");
36  }
37 }
38 
40  std::string &message) {
41  success = false;
42  message = "Exploration running";
43 }
44 
45 void MappingDummyState::onExplorationStop(bool &success, std::string &message) {
46  success = true;
47  message = "Exploration stopped";
48  _stateinterface->transitionToVolatileState(boost::make_shared<IdleState>());
49 }
50 
52  std::string &message) {
53  success = false;
54  message = "Exploration running";
55 }
56 
58  std::string &message) {
59  success = false;
60  message = "Exploration running";
61 }
62 
63 void MappingDummyState::onInterrupt(int interrupt) {
64  switch (interrupt) {
67  boost::make_shared<EmergencyStopState>());
68  _interrupt_occured = true;
69  break;
72  boost::make_shared<TeleoperationState>());
73  _interrupt_occured = true;
74  break;
78  _interrupt_occured = true;
79  break;
80  }
81 }
82 
83 }
84 
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void onInterrupt(int interrupt)
Called when an operation mode interrupt was received.
Dummy state for mapping at a reached goal during exploration. Only initiates transition to CalculateG...
boost::shared_ptr< rsm::BaseState > getPluginState(int plugin_type, std::string routine="")
void onWaypointFollowingStart(bool &success, std::string &message)
#define NAVIGATION_STATE
void onExplorationStart(bool &success, std::string &message)
bool call(MReq &req, MRes &res)
void onWaypointFollowingStop(bool &success, std::string &message)
void transitionToVolatileState(boost::shared_ptr< rsm::BaseState > next_state)
bool _interrupt_occured
#define TELEOPERATION_INTERRUPT
ros::ServiceClient _navigation_goal_completed_service
#define CALCULATEGOAL_STATE
std::string _name
StateInterface * _stateinterface
#define EMERGENCY_STOP_INTERRUPT
#define SIMPLE_GOAL_INTERRUPT
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
void onExplorationStop(bool &success, std::string &message)


rsm_additions
Author(s): Marco Steinbrink
autogenerated on Tue Mar 16 2021 02:44:35