14 rsm_msgs::GoalCompleted>(
"navigationGoalCompleted");
15 _name =
"E: Mapping Dummy";
32 rsm_msgs::GoalCompleted srv;
35 ROS_ERROR(
"Failed to call Complete Navigation Goal service");
40 std::string &message) {
42 message =
"Exploration running";
47 message =
"Exploration stopped";
52 std::string &message) {
54 message =
"Exploration running";
58 std::string &message) {
60 message =
"Exploration running";
67 boost::make_shared<EmergencyStopState>());
72 boost::make_shared<TeleoperationState>());
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="")
int _navigation_completed_status
void onWaypointFollowingStart(bool &success, std::string &message)
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)
#define TELEOPERATION_INTERRUPT
ros::ServiceClient _navigation_goal_completed_service
#define CALCULATEGOAL_STATE
StateInterface * _stateinterface
#define EMERGENCY_STOP_INTERRUPT
#define SIMPLE_GOAL_INTERRUPT
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void onExplorationStop(bool &success, std::string &message)