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

State for choosing a goal from all provided frontiers and calling Navigation when successful. The frontier center closest to the robot is selected as navigation goal. More...

#include <CalculateGoalState.h>

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

Public Member Functions

 CalculateGoalState ()
 Constructor. More...
 
void onActive ()
 Process method (step-wise, never block this method) More...
 
void onEntry ()
 Called once when activated. More...
 
void onExit ()
 Called once when left. More...
 
void onExplorationStart (bool &success, std::string &message)
 
void onExplorationStop (bool &success, std::string &message)
 Called when exploration was stopped manually. More...
 
void onInterrupt (int interrupt)
 Called when an operation mode interrupt was received. More...
 
void onSetup ()
 Called once when registered at StateInterface. More...
 
void onWaypointFollowingStart (bool &success, std::string &message)
 
void onWaypointFollowingStop (bool &success, std::string &message)
 
 ~CalculateGoalState ()
 Destructor. More...
 
- Public Member Functions inherited from rsm::BaseState
 BaseState ()
 
std::string getName ()
 
StateInterfacegetStateInterface ()
 
void setStateInterface (StateInterface *stateinterface)
 
virtual ~BaseState ()
 

Private Member Functions

void abortCalculateGoal ()
 
bool differentFromFailedGoals (geometry_msgs::Point point)
 Checks if a point is different from a previously failed goals including a small tolerance. More...
 
void failedGoalsCallback (const geometry_msgs::PoseArray::ConstPtr &failed_goals)
 Called when new failed goals are received. More...
 
void frontiersCallback (const geometry_msgs::PoseArray::ConstPtr &frontiers)
 Called when new frontiers are received. More...
 
void timerCallback (const ros::TimerEvent &event)
 Callback for when no goal was chosen in time and calculation likely failed. More...
 

Private Attributes

geometry_msgs::PoseArray _failed_goals
 
bool _failed_goals_received
 
ros::Subscriber _failed_goals_sub
 
geometry_msgs::PoseArray _frontier_points
 
bool _frontiers_received
 
ros::Subscriber _frontiers_sub
 
ros::ServiceClient _get_robot_pose_service
 
geometry_msgs::Pose _goal
 
ros::Timer _idle_timer
 
ros::NodeHandle _nh
 
ros::ServiceClient _set_navigation_goal_service
 

Additional Inherited Members

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

Detailed Description

State for choosing a goal from all provided frontiers and calling Navigation when successful. The frontier center closest to the robot is selected as navigation goal.

Definition at line 22 of file CalculateGoalState.h.

Constructor & Destructor Documentation

rsm::CalculateGoalState::CalculateGoalState ( )

Constructor.

Definition at line 5 of file CalculateGoalState.cpp.

rsm::CalculateGoalState::~CalculateGoalState ( )

Destructor.

Definition at line 9 of file CalculateGoalState.cpp.

Member Function Documentation

void rsm::CalculateGoalState::abortCalculateGoal ( )
private

Initiate transition to idle state

Definition at line 160 of file CalculateGoalState.cpp.

bool rsm::CalculateGoalState::differentFromFailedGoals ( geometry_msgs::Point  point)
private

Checks if a point is different from a previously failed goals including a small tolerance.

Parameters
Pointthat is checked against previously failed goals
Returns
Returns if the given point is different from the previously failed goals

Definition at line 143 of file CalculateGoalState.cpp.

void rsm::CalculateGoalState::failedGoalsCallback ( const geometry_msgs::PoseArray::ConstPtr &  failed_goals)
private

Called when new failed goals are received.

Parameters
failed_goalsList of poses containing all previously failed goals

Definition at line 137 of file CalculateGoalState.cpp.

void rsm::CalculateGoalState::frontiersCallback ( const geometry_msgs::PoseArray::ConstPtr &  frontiers)
private

Called when new frontiers are received.

Parameters
frontiersList of poses containing all frontier centers

Definition at line 131 of file CalculateGoalState.cpp.

void rsm::CalculateGoalState::onActive ( )
virtual

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

Implements rsm::BaseState.

Definition at line 35 of file CalculateGoalState.cpp.

void rsm::CalculateGoalState::onEntry ( )
virtual

Called once when activated.

Reimplemented from rsm::BaseState.

Definition at line 31 of file CalculateGoalState.cpp.

void rsm::CalculateGoalState::onExit ( )
virtual

Called once when left.

Reimplemented from rsm::BaseState.

Definition at line 76 of file CalculateGoalState.cpp.

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

Called when exploration was started manually

Reimplemented from rsm::BaseState.

Definition at line 86 of file CalculateGoalState.cpp.

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

Called when exploration was stopped manually.

Reimplemented from rsm::BaseState.

Definition at line 92 of file CalculateGoalState.cpp.

void rsm::CalculateGoalState::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 111 of file CalculateGoalState.cpp.

void rsm::CalculateGoalState::onSetup ( )
virtual

Called once when registered at StateInterface.

Reimplemented from rsm::BaseState.

Definition at line 12 of file CalculateGoalState.cpp.

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

Called when waypoint following was started/paused manually

Reimplemented from rsm::BaseState.

Definition at line 99 of file CalculateGoalState.cpp.

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

Called when waypoint following was stopped manually

Reimplemented from rsm::BaseState.

Definition at line 105 of file CalculateGoalState.cpp.

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

Callback for when no goal was chosen in time and calculation likely failed.

Parameters
event

Definition at line 155 of file CalculateGoalState.cpp.

Member Data Documentation

geometry_msgs::PoseArray rsm::CalculateGoalState::_failed_goals
private

List of previously failed goals

Definition at line 94 of file CalculateGoalState.h.

bool rsm::CalculateGoalState::_failed_goals_received
private

Were failed goals received

Definition at line 110 of file CalculateGoalState.h.

ros::Subscriber rsm::CalculateGoalState::_failed_goals_sub
private

Definition at line 86 of file CalculateGoalState.h.

geometry_msgs::PoseArray rsm::CalculateGoalState::_frontier_points
private

List of all available frontier centers

Definition at line 102 of file CalculateGoalState.h.

bool rsm::CalculateGoalState::_frontiers_received
private

Were frontiers received

Definition at line 106 of file CalculateGoalState.h.

ros::Subscriber rsm::CalculateGoalState::_frontiers_sub
private

Definition at line 85 of file CalculateGoalState.h.

ros::ServiceClient rsm::CalculateGoalState::_get_robot_pose_service
private

Definition at line 88 of file CalculateGoalState.h.

geometry_msgs::Pose rsm::CalculateGoalState::_goal
private

Chosen goal to be forwarded to navigation

Definition at line 98 of file CalculateGoalState.h.

ros::Timer rsm::CalculateGoalState::_idle_timer
private

Definition at line 89 of file CalculateGoalState.h.

ros::NodeHandle rsm::CalculateGoalState::_nh
private

Definition at line 84 of file CalculateGoalState.h.

ros::ServiceClient rsm::CalculateGoalState::_set_navigation_goal_service
private

Definition at line 87 of file CalculateGoalState.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