Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
rsm::NavigationState Class Reference

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>

Inheritance diagram for rsm::NavigationState:
Inheritance graph
[legend]

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 ()
 
StateInterfacegetStateInterface ()
 
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...
 

Private Attributes

bool _exploration_mode
 
ros::ServiceClient _get_exploration_mode_service
 
ros::Subscriber _get_goal_obsolete_subscriber
 
ros::ServiceClient _get_navigation_goal_service
 
ros::ServiceClient _get_reverse_mode_service
 
ros::ServiceClient _get_robot_pose_service
 
bool _goal_active
 
ros::Timer _idle_timer
 
bool _idle_timer_behavior
 
double _idle_timer_duration
 
tf::Vector3 _last_position
 
double _last_yaw
 
boost::shared_ptr< MoveBaseClient_move_base_client
 
geometry_msgs::Pose _nav_goal
 
int _navigation_completed_status
 
ros::ServiceClient _navigation_goal_completed_service
 
int _navigation_mode
 
ros::NodeHandle _nh
 
int _operation_mode
 
ros::Subscriber _operation_mode_subscriber
 
double _pose_tolerance
 
bool _reverse_mode
 
ros::Subscriber _reverse_mode_subscriber
 
bool _robot_did_move
 
std::string _routine
 
ros::Timer _unstuck_timer
 
double _unstuck_timer_duration
 
bool _unstucking_executed
 
bool _unstucking_robot
 

Additional Inherited Members

- Protected Attributes inherited from rsm::BaseState
bool _interrupt_occured
 
std::string _name
 
StateInterface_stateinterface
 

Detailed Description

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.

Member Typedef Documentation

◆ MoveBaseClient

typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> rsm::NavigationState::MoveBaseClient
private

Definition at line 90 of file NavigationState.h.

Constructor & Destructor Documentation

◆ NavigationState()

rsm::NavigationState::NavigationState ( )

Constructor

Definition at line 5 of file NavigationState.cpp.

◆ ~NavigationState()

rsm::NavigationState::~NavigationState ( )

Destructor

Definition at line 8 of file NavigationState.cpp.

Member Function Documentation

◆ abortNavigation()

void rsm::NavigationState::abortNavigation ( )
private

Initiate transition to Idle State

Definition at line 467 of file NavigationState.cpp.

◆ comparePose()

bool rsm::NavigationState::comparePose ( )
private

Check if the robot's pose changed since the start of navigation or since the last comparison

Returns
True if the robot's pose changed or the operation mode is not autonomous

Definition at line 405 of file NavigationState.cpp.

◆ goalObsoleteCallback()

void rsm::NavigationState::goalObsoleteCallback ( const std_msgs::Bool::ConstPtr &  msg)
private

Callback for checking if the current exploration goal is still viable or already obsolete, only checked for exploration mode 'interrupting"

Parameters
msgIs goal obsolete or not

Definition at line 434 of file NavigationState.cpp.

◆ idleTimerCallback()

void rsm::NavigationState::idleTimerCallback ( const ros::TimerEvent event)
private

Callback for idle timer.

Parameters
event

Definition at line 342 of file NavigationState.cpp.

◆ onActive()

void rsm::NavigationState::onActive ( )
virtual

Process method (step-wise, never block this method)

Implements rsm::BaseState.

Definition at line 113 of file NavigationState.cpp.

◆ onEntry()

void rsm::NavigationState::onEntry ( )
virtual

Called once when activated

Reimplemented from rsm::BaseState.

Definition at line 57 of file NavigationState.cpp.

◆ onExit()

void rsm::NavigationState::onExit ( )
virtual

Called once when left

Reimplemented from rsm::BaseState.

Definition at line 216 of file NavigationState.cpp.

◆ onExplorationStart()

void rsm::NavigationState::onExplorationStart ( bool &  success,
std::string &  message 
)
virtual

Called when exploration was started manually

Reimplemented from rsm::BaseState.

Definition at line 230 of file NavigationState.cpp.

◆ onExplorationStop()

void rsm::NavigationState::onExplorationStop ( bool &  success,
std::string &  message 
)
virtual

Called when exploration was stopped manually

Reimplemented from rsm::BaseState.

Definition at line 251 of file NavigationState.cpp.

◆ onInterrupt()

void rsm::NavigationState::onInterrupt ( int  interrupt)
virtual

Called when an operation mode interrupt was received.

Parameters
interruptKind of interrupt (0=EmergencyStop, 1=TeleoperationInterupt)

Reimplemented from rsm::BaseState.

Definition at line 315 of file NavigationState.cpp.

◆ onSetup()

void rsm::NavigationState::onSetup ( )
virtual

Called once when registered at StateInterface

Reimplemented from rsm::BaseState.

Definition at line 11 of file NavigationState.cpp.

◆ onWaypointFollowingStart()

void rsm::NavigationState::onWaypointFollowingStart ( bool &  success,
std::string &  message 
)
virtual

Called when waypoint following was started/paused manually

Reimplemented from rsm::BaseState.

Definition at line 273 of file NavigationState.cpp.

◆ onWaypointFollowingStop()

void rsm::NavigationState::onWaypointFollowingStop ( bool &  success,
std::string &  message 
)
virtual

Called when waypoint following was stopped manually

Reimplemented from rsm::BaseState.

Definition at line 292 of file NavigationState.cpp.

◆ operationModeCallback()

void rsm::NavigationState::operationModeCallback ( const rsm_msgs::OperationMode::ConstPtr &  operation_mode)
private

Callback for Operation mode to only enable the idle timer when operation mode is set to autonomous

Parameters
operation_modeMode of operation (0=stopped, 1=autonomous, 2=teleoperation)

Definition at line 462 of file NavigationState.cpp.

◆ reverseModeCallback()

void rsm::NavigationState::reverseModeCallback ( const std_msgs::Bool::ConstPtr &  reverse_mode)
private

Callback for checking if reverse mode changed and if it did, reset SimpleActionClient to interface the Move Base node for reverse movement

Parameters
reverse_modeIs reverse mode active or not

Definition at line 445 of file NavigationState.cpp.

◆ unstuckTimerCallback()

void rsm::NavigationState::unstuckTimerCallback ( const ros::TimerEvent event)
private

Callback for switched mode navigation to unstuck robot.

Parameters
event

Definition at line 391 of file NavigationState.cpp.

Member Data Documentation

◆ _exploration_mode

bool rsm::NavigationState::_exploration_mode
private

Mode of exploration (0=complete goal, 1=interrupt goal when frontier vanished)

Definition at line 132 of file NavigationState.h.

◆ _get_exploration_mode_service

ros::ServiceClient rsm::NavigationState::_get_exploration_mode_service
private

Definition at line 97 of file NavigationState.h.

◆ _get_goal_obsolete_subscriber

ros::Subscriber rsm::NavigationState::_get_goal_obsolete_subscriber
private

Definition at line 99 of file NavigationState.h.

◆ _get_navigation_goal_service

ros::ServiceClient rsm::NavigationState::_get_navigation_goal_service
private

Definition at line 94 of file NavigationState.h.

◆ _get_reverse_mode_service

ros::ServiceClient rsm::NavigationState::_get_reverse_mode_service
private

Definition at line 98 of file NavigationState.h.

◆ _get_robot_pose_service

ros::ServiceClient rsm::NavigationState::_get_robot_pose_service
private

Definition at line 96 of file NavigationState.h.

◆ _goal_active

bool rsm::NavigationState::_goal_active
private

Is goal currently active or does it need to be set first

Definition at line 112 of file NavigationState.h.

◆ _idle_timer

ros::Timer rsm::NavigationState::_idle_timer
private

Definition at line 102 of file NavigationState.h.

◆ _idle_timer_behavior

bool rsm::NavigationState::_idle_timer_behavior
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.

◆ _idle_timer_duration

double rsm::NavigationState::_idle_timer_duration
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.

◆ _last_position

tf::Vector3 rsm::NavigationState::_last_position
private

Last position of the robot

Definition at line 124 of file NavigationState.h.

◆ _last_yaw

double rsm::NavigationState::_last_yaw
private

Last yaw orientation of the robot

Definition at line 128 of file NavigationState.h.

◆ _move_base_client

boost::shared_ptr<MoveBaseClient> rsm::NavigationState::_move_base_client
private

Definition at line 91 of file NavigationState.h.

◆ _nav_goal

geometry_msgs::Pose rsm::NavigationState::_nav_goal
private

Navigation goal to reach

Definition at line 108 of file NavigationState.h.

◆ _navigation_completed_status

int rsm::NavigationState::_navigation_completed_status
private

Was the navigation goal successfully reached or not or aborted

Definition at line 144 of file NavigationState.h.

◆ _navigation_goal_completed_service

ros::ServiceClient rsm::NavigationState::_navigation_goal_completed_service
private

Definition at line 95 of file NavigationState.h.

◆ _navigation_mode

int rsm::NavigationState::_navigation_mode
private

Mode of navigation (Exploration=0, Waypoint following=1 and Simple Goal=2)

Definition at line 116 of file NavigationState.h.

◆ _nh

ros::NodeHandle rsm::NavigationState::_nh
private

Definition at line 93 of file NavigationState.h.

◆ _operation_mode

int rsm::NavigationState::_operation_mode
private

Currently active mode of operation (0=stopped, 1=autonomous, 2=teleoperation)

Definition at line 140 of file NavigationState.h.

◆ _operation_mode_subscriber

ros::Subscriber rsm::NavigationState::_operation_mode_subscriber
private

Definition at line 101 of file NavigationState.h.

◆ _pose_tolerance

double rsm::NavigationState::_pose_tolerance
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.

◆ _reverse_mode

bool rsm::NavigationState::_reverse_mode
private

Is robot driving in reverse or not

Definition at line 136 of file NavigationState.h.

◆ _reverse_mode_subscriber

ros::Subscriber rsm::NavigationState::_reverse_mode_subscriber
private

Definition at line 100 of file NavigationState.h.

◆ _robot_did_move

bool rsm::NavigationState::_robot_did_move
private

Did the robot move at all while this state was active

Definition at line 148 of file NavigationState.h.

◆ _routine

std::string rsm::NavigationState::_routine
private

Routine to be executed when reaching waypoint

Definition at line 120 of file NavigationState.h.

◆ _unstuck_timer

ros::Timer rsm::NavigationState::_unstuck_timer
private

Definition at line 103 of file NavigationState.h.

◆ _unstuck_timer_duration

double rsm::NavigationState::_unstuck_timer_duration
private

Time that navigation can try to unstuck the robot with switched mode

Definition at line 160 of file NavigationState.h.

◆ _unstucking_executed

bool rsm::NavigationState::_unstucking_executed
private

Was the mode switch already tried for this goal

Definition at line 168 of file NavigationState.h.

◆ _unstucking_robot

bool rsm::NavigationState::_unstucking_robot
private

Is switched mode used at the moment to unstuck robot

Definition at line 164 of file NavigationState.h.


The documentation for this class was generated from the following files:


rsm_additions
Author(s): Marco Steinbrink
autogenerated on Mon Feb 28 2022 23:28:21