20 rsm_msgs::GoalCompleted>(
"navigationGoalCompleted");
22 _name =
"W: Reversing";
29 std_srvs::Trigger srv;
33 ROS_ERROR(
"Failed to call Get Reverse Mode service");
37 boost::make_shared<WaypointFollowingState>());
44 std_srvs::SetBool srv;
47 ROS_ERROR(
"Failed to call Set Reverse Mode service");
52 boost::make_shared<WaypointFollowingState>());
57 rsm_msgs::GoalCompleted srv;
60 ROS_ERROR(
"Failed to call Complete Navigation Goal service");
65 std::string &message) {
67 message =
"Waypoint following running";
71 std::string &message) {
73 message =
"Waypoint following running";
77 std::string &message) {
79 message =
"Waypoint following running";
83 std::string &message) {
85 message =
"Waypoint following stopped";
93 boost::make_shared<EmergencyStopState>());
98 boost::make_shared<TeleoperationState>());
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::ServiceClient _set_reverse_moving_service
boost::shared_ptr< rsm::BaseState > getPluginState(int plugin_type, std::string routine="")
void onInterrupt(int interrupt)
Called when an operation mode interrupt was received.
ros::ServiceClient _navigation_goal_completed_service
bool call(MReq &req, MRes &res)
void onWaypointFollowingStart(bool &success, std::string &message)
void transitionToVolatileState(boost::shared_ptr< rsm::BaseState > next_state)
#define TELEOPERATION_INTERRUPT
ros::ServiceClient _get_reverse_moving_service
void onExplorationStart(bool &success, std::string &message)
void onExplorationStop(bool &success, std::string &message)
StateInterface * _stateinterface
void onWaypointFollowingStop(bool &success, std::string &message)
#define EMERGENCY_STOP_INTERRUPT
bool _reverse_mode_active
int _navigation_completed_status
#define SIMPLE_GOAL_INTERRUPT
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Routine state that toggles the reverse mode.