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>
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 () |
StateInterface * | getStateInterface () |
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 |
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.
rsm::CalculateGoalState::CalculateGoalState | ( | ) |
Constructor.
Definition at line 5 of file CalculateGoalState.cpp.
rsm::CalculateGoalState::~CalculateGoalState | ( | ) |
Destructor.
Definition at line 9 of file CalculateGoalState.cpp.
|
private |
Initiate transition to idle state
Definition at line 160 of file CalculateGoalState.cpp.
|
private |
Checks if a point is different from a previously failed goals including a small tolerance.
Point | that is checked against previously failed goals |
Definition at line 143 of file CalculateGoalState.cpp.
|
private |
Called when new failed goals are received.
failed_goals | List of poses containing all previously failed goals |
Definition at line 137 of file CalculateGoalState.cpp.
|
private |
Called when new frontiers are received.
frontiers | List of poses containing all frontier centers |
Definition at line 131 of file CalculateGoalState.cpp.
|
virtual |
Process method (step-wise, never block this method)
Implements rsm::BaseState.
Definition at line 35 of file CalculateGoalState.cpp.
|
virtual |
Called once when activated.
Reimplemented from rsm::BaseState.
Definition at line 31 of file CalculateGoalState.cpp.
|
virtual |
Called once when left.
Reimplemented from rsm::BaseState.
Definition at line 76 of file CalculateGoalState.cpp.
|
virtual |
Called when exploration was started manually
Reimplemented from rsm::BaseState.
Definition at line 86 of file CalculateGoalState.cpp.
|
virtual |
Called when exploration was stopped manually.
Reimplemented from rsm::BaseState.
Definition at line 92 of file CalculateGoalState.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 111 of file CalculateGoalState.cpp.
|
virtual |
Called once when registered at StateInterface.
Reimplemented from rsm::BaseState.
Definition at line 12 of file CalculateGoalState.cpp.
|
virtual |
Called when waypoint following was started/paused manually
Reimplemented from rsm::BaseState.
Definition at line 99 of file CalculateGoalState.cpp.
|
virtual |
Called when waypoint following was stopped manually
Reimplemented from rsm::BaseState.
Definition at line 105 of file CalculateGoalState.cpp.
|
private |
Callback for when no goal was chosen in time and calculation likely failed.
event |
Definition at line 155 of file CalculateGoalState.cpp.
|
private |
List of previously failed goals
Definition at line 94 of file CalculateGoalState.h.
|
private |
Were failed goals received
Definition at line 110 of file CalculateGoalState.h.
|
private |
Definition at line 86 of file CalculateGoalState.h.
|
private |
List of all available frontier centers
Definition at line 102 of file CalculateGoalState.h.
|
private |
Were frontiers received
Definition at line 106 of file CalculateGoalState.h.
|
private |
Definition at line 85 of file CalculateGoalState.h.
|
private |
Definition at line 88 of file CalculateGoalState.h.
|
private |
Chosen goal to be forwarded to navigation
Definition at line 98 of file CalculateGoalState.h.
|
private |
Definition at line 89 of file CalculateGoalState.h.
|
private |
Definition at line 84 of file CalculateGoalState.h.
|
private |
Definition at line 87 of file CalculateGoalState.h.