State being active when the robot should move to a previously set goal. First obtains the goal and then tries to reach it using the Move Base package. State is exited when the goal was reached, aborted or an interrupt occured. More...
#include <NavigationState.h>
Public Member Functions | |
NavigationState () | |
void | onActive () |
void | onEntry () |
void | onExit () |
void | onExplorationStart (bool &success, std::string &message) |
void | onExplorationStop (bool &success, std::string &message) |
void | onInterrupt (int interrupt) |
Called when an operation mode interrupt was received. More... | |
void | onSetup () |
void | onWaypointFollowingStart (bool &success, std::string &message) |
void | onWaypointFollowingStop (bool &success, std::string &message) |
~NavigationState () | |
Public Member Functions inherited from rsm::BaseState | |
BaseState () | |
std::string | getName () |
StateInterface * | getStateInterface () |
void | setStateInterface (StateInterface *stateinterface) |
virtual | ~BaseState () |
Private Types | |
typedef actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > | MoveBaseClient |
Private Member Functions | |
void | abortNavigation () |
void | comparePose () |
void | goalObsoleteCallback (const std_msgs::Bool::ConstPtr &msg) |
void | operationModeCallback (const rsm_msgs::OperationMode::ConstPtr &operation_mode) |
void | reverseModeCallback (const std_msgs::Bool::ConstPtr &reverse_mode) |
void | timerCallback (const ros::TimerEvent &event) |
Callback for idle timer. More... | |
Additional Inherited Members | |
Protected Attributes inherited from rsm::BaseState | |
bool | _interrupt_occured |
std::string | _name |
StateInterface * | _stateinterface |
State being active when the robot should move to a previously set goal. First obtains the goal and then tries to reach it using the Move Base package. State is exited when the goal was reached, aborted or an interrupt occured.
Definition at line 30 of file NavigationState.h.
|
private |
Definition at line 92 of file NavigationState.h.
rsm::NavigationState::NavigationState | ( | ) |
Constructor
Definition at line 5 of file NavigationState.cpp.
rsm::NavigationState::~NavigationState | ( | ) |
Destructor
Definition at line 8 of file NavigationState.cpp.
|
private |
Initiate transition to Idle State
Definition at line 362 of file NavigationState.cpp.
|
private |
Check if the robot's pose changed and reset idle timer if it did, restart it if not
Definition at line 299 of file NavigationState.cpp.
|
private |
Callback for checking if the current exploration goal is still viable or already obsolete, only checked for exploration mode 'interrupting"
msg | Is goal obsolete or not |
Definition at line 330 of file NavigationState.cpp.
|
virtual |
Process method (step-wise, never block this method)
Implements rsm::BaseState.
Definition at line 96 of file NavigationState.cpp.
|
virtual |
Called once when activated
Reimplemented from rsm::BaseState.
Definition at line 38 of file NavigationState.cpp.
|
virtual |
Called once when left
Reimplemented from rsm::BaseState.
Definition at line 169 of file NavigationState.cpp.
|
virtual |
Called when exploration was started manually
Reimplemented from rsm::BaseState.
Definition at line 182 of file NavigationState.cpp.
|
virtual |
Called when exploration was stopped manually
Reimplemented from rsm::BaseState.
Definition at line 203 of file NavigationState.cpp.
|
virtual |
Called when an operation mode interrupt was received.
interrupt | Kind of interrupt (0=EmergencyStop, 1=TeleoperationInterupt) |
Reimplemented from rsm::BaseState.
Definition at line 267 of file NavigationState.cpp.
|
virtual |
Called once when registered at StateInterface
Reimplemented from rsm::BaseState.
Definition at line 11 of file NavigationState.cpp.
|
virtual |
Called when waypoint following was started/paused manually
Reimplemented from rsm::BaseState.
Definition at line 225 of file NavigationState.cpp.
|
virtual |
Called when waypoint following was stopped manually
Reimplemented from rsm::BaseState.
Definition at line 244 of file NavigationState.cpp.
|
private |
Callback for Operation mode to only enable the idle timer when operation mode is set to autonomous
operation_mode | Mode of operation (0=stopped, 1=autonomous, 2=teleoperation) |
Definition at line 357 of file NavigationState.cpp.
|
private |
Callback for checking if reverse mode changed and if it did, reset SimpleActionClient to interface the Move Base node for reverse movement
reverse_mode | Is reverse mode active or not |
Definition at line 340 of file NavigationState.cpp.
|
private |
|
private |
Counter for comparing last with current pose only every 5th call
Definition at line 128 of file NavigationState.h.
|
private |
Mode of exploration (0=complete goal, 1=interrupt goal when frontier vanished)
Definition at line 132 of file NavigationState.h.
|
private |
Definition at line 99 of file NavigationState.h.
|
private |
Definition at line 101 of file NavigationState.h.
|
private |
Definition at line 96 of file NavigationState.h.
|
private |
Definition at line 100 of file NavigationState.h.
|
private |
Definition at line 98 of file NavigationState.h.
|
private |
Is goal currently active or does it need to be set first
Definition at line 112 of file NavigationState.h.
|
private |
Definition at line 103 of file NavigationState.h.
|
private |
Last pose of the robot
Definition at line 124 of file NavigationState.h.
|
private |
Definition at line 93 of file NavigationState.h.
|
private |
Navigation goal to reach
Definition at line 108 of file NavigationState.h.
|
private |
Was the navigation goal successfully reached or not or aborted
Definition at line 144 of file NavigationState.h.
|
private |
Definition at line 97 of file NavigationState.h.
|
private |
Mode of navigation (Exploration=0, Waypoint following=1 and Simple Goal=2)
Definition at line 116 of file NavigationState.h.
|
private |
Definition at line 95 of file NavigationState.h.
|
private |
Currently active mode of operation (0=stopped, 1=autonomous, 2=teleoperation)
Definition at line 140 of file NavigationState.h.
|
private |
Is robot driving in reverse or not
Definition at line 136 of file NavigationState.h.
|
private |
Definition at line 102 of file NavigationState.h.
|
private |
Routine to be executed when reaching waypoint
Definition at line 120 of file NavigationState.h.