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

Private Attributes

int _comparison_counter
 
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
 
tf::Pose _last_pose
 
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
 
bool _reverse_mode
 
ros::Subscriber _reverse_mode_subscriber
 
std::string _routine
 

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 30 of file NavigationState.h.

Member Typedef Documentation

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

Definition at line 92 of file NavigationState.h.

Constructor & Destructor Documentation

rsm::NavigationState::NavigationState ( )

Constructor

Definition at line 5 of file NavigationState.cpp.

rsm::NavigationState::~NavigationState ( )

Destructor

Definition at line 8 of file NavigationState.cpp.

Member Function Documentation

void rsm::NavigationState::abortNavigation ( )
private

Initiate transition to Idle State

Definition at line 362 of file NavigationState.cpp.

void rsm::NavigationState::comparePose ( )
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.

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 330 of file NavigationState.cpp.

void rsm::NavigationState::onActive ( )
virtual

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

Implements rsm::BaseState.

Definition at line 96 of file NavigationState.cpp.

void rsm::NavigationState::onEntry ( )
virtual

Called once when activated

Reimplemented from rsm::BaseState.

Definition at line 38 of file NavigationState.cpp.

void rsm::NavigationState::onExit ( )
virtual

Called once when left

Reimplemented from rsm::BaseState.

Definition at line 169 of file NavigationState.cpp.

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

Called when exploration was started manually

Reimplemented from rsm::BaseState.

Definition at line 182 of file NavigationState.cpp.

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

Called when exploration was stopped manually

Reimplemented from rsm::BaseState.

Definition at line 203 of file NavigationState.cpp.

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 267 of file NavigationState.cpp.

void rsm::NavigationState::onSetup ( )
virtual

Called once when registered at StateInterface

Reimplemented from rsm::BaseState.

Definition at line 11 of file NavigationState.cpp.

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 225 of file NavigationState.cpp.

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

Called when waypoint following was stopped manually

Reimplemented from rsm::BaseState.

Definition at line 244 of file NavigationState.cpp.

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 357 of file NavigationState.cpp.

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 340 of file NavigationState.cpp.

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

Callback for idle timer.

Parameters
event

Definition at line 294 of file NavigationState.cpp.

Member Data Documentation

int rsm::NavigationState::_comparison_counter
private

Counter for comparing last with current pose only every 5th call

Definition at line 128 of file NavigationState.h.

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.

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

Definition at line 99 of file NavigationState.h.

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

Definition at line 101 of file NavigationState.h.

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

Definition at line 96 of file NavigationState.h.

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

Definition at line 100 of file NavigationState.h.

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

Definition at line 98 of file NavigationState.h.

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.

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

Definition at line 103 of file NavigationState.h.

tf::Pose rsm::NavigationState::_last_pose
private

Last pose of the robot

Definition at line 124 of file NavigationState.h.

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

Definition at line 93 of file NavigationState.h.

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

Navigation goal to reach

Definition at line 108 of file NavigationState.h.

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.

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

Definition at line 97 of file NavigationState.h.

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.

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

Definition at line 95 of file NavigationState.h.

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.

bool rsm::NavigationState::_reverse_mode
private

Is robot driving in reverse or not

Definition at line 136 of file NavigationState.h.

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

Definition at line 102 of file NavigationState.h.

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

Routine to be executed when reaching waypoint

Definition at line 120 of file NavigationState.h.


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


rsm_additions
Author(s): Marco Steinbrink
autogenerated on Tue Mar 16 2021 02:44:35