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 () | |
![]() | |
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 () |
bool | comparePose () |
void | goalObsoleteCallback (const std_msgs::Bool::ConstPtr &msg) |
void | idleTimerCallback (const ros::TimerEvent &event) |
Callback for idle timer. More... | |
void | operationModeCallback (const rsm_msgs::OperationMode::ConstPtr &operation_mode) |
void | reverseModeCallback (const std_msgs::Bool::ConstPtr &reverse_mode) |
void | unstuckTimerCallback (const ros::TimerEvent &event) |
Callback for switched mode navigation to unstuck robot. More... | |
Additional Inherited Members | |
![]() | |
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 28 of file NavigationState.h.
|
private |
Definition at line 90 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 467 of file NavigationState.cpp.
|
private |
Check if the robot's pose changed since the start of navigation or since the last comparison
Definition at line 405 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 434 of file NavigationState.cpp.
|
private |
|
virtual |
Process method (step-wise, never block this method)
Implements rsm::BaseState.
Definition at line 113 of file NavigationState.cpp.
|
virtual |
Called once when activated
Reimplemented from rsm::BaseState.
Definition at line 57 of file NavigationState.cpp.
|
virtual |
Called once when left
Reimplemented from rsm::BaseState.
Definition at line 216 of file NavigationState.cpp.
|
virtual |
Called when exploration was started manually
Reimplemented from rsm::BaseState.
Definition at line 230 of file NavigationState.cpp.
|
virtual |
Called when exploration was stopped manually
Reimplemented from rsm::BaseState.
Definition at line 251 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 315 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 273 of file NavigationState.cpp.
|
virtual |
Called when waypoint following was stopped manually
Reimplemented from rsm::BaseState.
Definition at line 292 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 462 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 445 of file NavigationState.cpp.
|
private |
Callback for switched mode navigation to unstuck robot.
event |
Definition at line 391 of file NavigationState.cpp.
|
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 97 of file NavigationState.h.
|
private |
Definition at line 99 of file NavigationState.h.
|
private |
Definition at line 94 of file NavigationState.h.
|
private |
Definition at line 98 of file NavigationState.h.
|
private |
Definition at line 96 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 102 of file NavigationState.h.
|
private |
If the idle timer when called should end exploration/waypoint following or just declare goal as failed (true=end,false=fail)
Definition at line 172 of file NavigationState.h.
|
private |
Time in s that the robot can remain stationary before navigation counts as aborted because the robot is stuck
Definition at line 156 of file NavigationState.h.
|
private |
Last position of the robot
Definition at line 124 of file NavigationState.h.
|
private |
Last yaw orientation of the robot
Definition at line 128 of file NavigationState.h.
|
private |
Definition at line 91 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 95 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 93 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 |
Definition at line 101 of file NavigationState.h.
|
private |
Tolerance in m or rad that, if the robot's pose difference is below, still make the robot count as stationary
Definition at line 152 of file NavigationState.h.
|
private |
Is robot driving in reverse or not
Definition at line 136 of file NavigationState.h.
|
private |
Definition at line 100 of file NavigationState.h.
|
private |
Did the robot move at all while this state was active
Definition at line 148 of file NavigationState.h.
|
private |
Routine to be executed when reaching waypoint
Definition at line 120 of file NavigationState.h.
|
private |
Definition at line 103 of file NavigationState.h.
|
private |
Time that navigation can try to unstuck the robot with switched mode
Definition at line 160 of file NavigationState.h.
|
private |
Was the mode switch already tried for this goal
Definition at line 168 of file NavigationState.h.
|
private |
Is switched mode used at the moment to unstuck robot
Definition at line 164 of file NavigationState.h.